Path: blob/master/libraries/AP_Compass/AP_Compass_DroneCAN.cpp
9460 views
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AP_Compass_DroneCAN.h"1617#if AP_COMPASS_DRONECAN_ENABLED1819#include <AP_HAL/AP_HAL.h>2021#include <AP_CANManager/AP_CANManager.h>22#include <AP_DroneCAN/AP_DroneCAN.h>23#include <AP_BoardConfig/AP_BoardConfig.h>24#include <AP_Logger/AP_Logger.h>25#include <SITL/SITL.h>2627#define LOG_TAG "COMPASS"2829AP_Compass_DroneCAN::DetectedModules AP_Compass_DroneCAN::_detected_modules[];30HAL_Semaphore AP_Compass_DroneCAN::_sem_registry;3132AP_Compass_DroneCAN::AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint32_t devid) :33_devid(devid)34{35}3637bool AP_Compass_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)38{39const auto driver_index = ap_dronecan->get_driver_index();4041return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field, driver_index) != nullptr)42&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_2, driver_index) != nullptr)43#if AP_COMPASS_DRONECAN_HIRES_ENABLED44&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_hires, driver_index) != nullptr)45#endif46;47}4849AP_Compass_Backend* AP_Compass_DroneCAN::probe(uint8_t index)50{51AP_Compass_DroneCAN* driver = nullptr;52if (!_detected_modules[index].driver && _detected_modules[index].ap_dronecan) {53WITH_SEMAPHORE(_sem_registry);54// Register new Compass mode to a backend55driver = NEW_NOTHROW AP_Compass_DroneCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].devid);56if (driver) {57if (!driver->init()) {58delete driver;59return nullptr;60}61_detected_modules[index].driver = driver;62AP::can().log_text(AP_CANManager::LOG_INFO,63LOG_TAG,64"Found Mag Node %d on Bus %d Sensor ID %d\n",65_detected_modules[index].node_id,66_detected_modules[index].ap_dronecan->get_driver_index(),67_detected_modules[index].sensor_id);68#if AP_TEST_DRONECAN_DRIVERS69// Scroll through the registered compasses, and set the offsets70if (driver->_compass.get_offsets(index).is_zero()) {71driver->_compass.set_offsets(index, AP::sitl()->mag_ofs[index]);72}7374// we want to simulate a calibrated compass by default, so set75// scale to 176AP_Param::set_default_by_name("COMPASS_SCALE", 1);77AP_Param::set_default_by_name("COMPASS_SCALE2", 1);78AP_Param::set_default_by_name("COMPASS_SCALE3", 1);79driver->save_dev_id(index);80driver->set_rotation(index, ROTATION_NONE);8182// make first compass external83driver->set_external(index, true);84#endif85}86}87return driver;88}8990bool AP_Compass_DroneCAN::init()91{92// Adding 1 is necessary to allow backward compatibility, where this field was set as 1 by default93if (!register_compass(_devid)) {94return false;95}96set_external(true);9798AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "AP_Compass_DroneCAN loaded\n\r");99return true;100}101102AP_Compass_DroneCAN* AP_Compass_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id)103{104if (ap_dronecan == nullptr) {105return nullptr;106}107for (uint8_t i=0; i<ARRAY_SIZE(_detected_modules); i++) {108if (_detected_modules[i].driver &&109_detected_modules[i].ap_dronecan == ap_dronecan &&110_detected_modules[i].node_id == node_id &&111_detected_modules[i].sensor_id == sensor_id) {112return _detected_modules[i].driver;113}114}115116bool already_detected = false;117// Check if there's an empty spot for possible registration118for (uint8_t i = 0; i < ARRAY_SIZE(_detected_modules); i++) {119if (_detected_modules[i].ap_dronecan == ap_dronecan &&120_detected_modules[i].node_id == node_id &&121_detected_modules[i].sensor_id == sensor_id) {122// Already Detected123already_detected = true;124break;125}126}127if (!already_detected) {128for (uint8_t i = 0; i < ARRAY_SIZE(_detected_modules); i++) {129if (nullptr == _detected_modules[i].ap_dronecan) {130_detected_modules[i].ap_dronecan = ap_dronecan;131_detected_modules[i].node_id = node_id;132_detected_modules[i].sensor_id = sensor_id;133_detected_modules[i].devid = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN,134ap_dronecan->get_driver_index(),135node_id,136sensor_id + 1); // we use sensor_id as devtype137break;138}139}140}141142struct DetectedModules tempslot;143// Sort based on the node_id, larger values first144// we do this, so that we have repeatable compass145// registration, especially in cases of extraneous146// CAN compass is connected.147for (uint8_t i = 1; i < ARRAY_SIZE(_detected_modules); i++) {148for (uint8_t j = i; j > 0; j--) {149if (_detected_modules[j].node_id > _detected_modules[j-1].node_id) {150tempslot = _detected_modules[j];151_detected_modules[j] = _detected_modules[j-1];152_detected_modules[j-1] = tempslot;153}154}155}156157return nullptr;158}159160void AP_Compass_DroneCAN::handle_mag_msg(const Vector3f &mag)161{162Vector3f raw_field = mag * 1000.0;163164accumulate_sample(raw_field, _instance);165}166167void AP_Compass_DroneCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg)168{169WITH_SEMAPHORE(_sem_registry);170171Vector3f mag_vector;172AP_Compass_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, 0);173if (driver != nullptr) {174mag_vector[0] = msg.magnetic_field_ga[0];175mag_vector[1] = msg.magnetic_field_ga[1];176mag_vector[2] = msg.magnetic_field_ga[2];177driver->handle_mag_msg(mag_vector);178}179}180181void AP_Compass_DroneCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg)182{183WITH_SEMAPHORE(_sem_registry);184185Vector3f mag_vector;186uint8_t sensor_id = msg.sensor_id;187AP_Compass_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, sensor_id);188if (driver != nullptr) {189mag_vector[0] = msg.magnetic_field_ga[0];190mag_vector[1] = msg.magnetic_field_ga[1];191mag_vector[2] = msg.magnetic_field_ga[2];192driver->handle_mag_msg(mag_vector);193}194}195196#if AP_COMPASS_DRONECAN_HIRES_ENABLED197/*198just log hires magnetic field data for magnetic surveying199*/200void AP_Compass_DroneCAN::handle_magnetic_field_hires(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer,201const dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes &msg)202{203// @LoggerMessage: MAGH204// @Description: Magnetometer high resolution data205// @Field: TimeUS: Time since system startup206// @Field: Node: CAN node207// @Field: Sensor: sensor ID on node208// @Field: Bus: CAN bus209// @Field: Mx: X axis field210// @Field: My: y axis field211// @Field: Mz: z axis field212213#if HAL_LOGGING_ENABLED214// just log it for now215AP::logger().WriteStreaming("MAGH", "TimeUS,Node,Sensor,Bus,Mx,My,Mz", "s#-----", "F------", "QBBBfff",216transfer.timestamp_usec,217transfer.source_node_id,218ap_dronecan->get_driver_index(),219msg.sensor_id,220msg.magnetic_field_ga[0]*1000,221msg.magnetic_field_ga[1]*1000,222msg.magnetic_field_ga[2]*1000);223#endif // HAL_LOGGING_ENABLED224}225#endif // AP_COMPASS_DRONECAN_HIRES_ENABLED226227void AP_Compass_DroneCAN::read(void)228{229drain_accumulated_samples();230}231#endif // AP_COMPASS_DRONECAN_ENABLED232233234