Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Compass/AP_Compass_DroneCAN.cpp
Views: 1798
/*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>2627extern const AP_HAL::HAL& hal;2829#define LOG_TAG "COMPASS"3031AP_Compass_DroneCAN::DetectedModules AP_Compass_DroneCAN::_detected_modules[];32HAL_Semaphore AP_Compass_DroneCAN::_sem_registry;3334AP_Compass_DroneCAN::AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint32_t devid) :35_devid(devid)36{37}3839bool AP_Compass_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)40{41const auto driver_index = ap_dronecan->get_driver_index();4243return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field, driver_index) != nullptr)44&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_2, driver_index) != nullptr)45#if AP_COMPASS_DRONECAN_HIRES_ENABLED46&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_hires, driver_index) != nullptr)47#endif48;49}5051AP_Compass_Backend* AP_Compass_DroneCAN::probe(uint8_t index)52{53AP_Compass_DroneCAN* driver = nullptr;54if (!_detected_modules[index].driver && _detected_modules[index].ap_dronecan) {55WITH_SEMAPHORE(_sem_registry);56// Register new Compass mode to a backend57driver = NEW_NOTHROW AP_Compass_DroneCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].devid);58if (driver) {59if (!driver->init()) {60delete driver;61return nullptr;62}63_detected_modules[index].driver = driver;64AP::can().log_text(AP_CANManager::LOG_INFO,65LOG_TAG,66"Found Mag Node %d on Bus %d Sensor ID %d\n",67_detected_modules[index].node_id,68_detected_modules[index].ap_dronecan->get_driver_index(),69_detected_modules[index].sensor_id);70#if AP_TEST_DRONECAN_DRIVERS71// Scroll through the registered compasses, and set the offsets72if (driver->_compass.get_offsets(index).is_zero()) {73driver->_compass.set_offsets(index, AP::sitl()->mag_ofs[index]);74}7576// we want to simulate a calibrated compass by default, so set77// scale to 178AP_Param::set_default_by_name("COMPASS_SCALE", 1);79AP_Param::set_default_by_name("COMPASS_SCALE2", 1);80AP_Param::set_default_by_name("COMPASS_SCALE3", 1);81driver->save_dev_id(index);82driver->set_rotation(index, ROTATION_NONE);8384// make first compass external85driver->set_external(index, true);86#endif87}88}89return driver;90}9192bool AP_Compass_DroneCAN::init()93{94// Adding 1 is necessary to allow backward compatibility, where this field was set as 1 by default95if (!register_compass(_devid, _instance)) {96return false;97}9899set_dev_id(_instance, _devid);100set_external(_instance, true);101102AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "AP_Compass_DroneCAN loaded\n\r");103return true;104}105106AP_Compass_DroneCAN* AP_Compass_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id)107{108if (ap_dronecan == nullptr) {109return nullptr;110}111for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {112if (_detected_modules[i].driver &&113_detected_modules[i].ap_dronecan == ap_dronecan &&114_detected_modules[i].node_id == node_id &&115_detected_modules[i].sensor_id == sensor_id) {116return _detected_modules[i].driver;117}118}119120bool already_detected = false;121// Check if there's an empty spot for possible registration122for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) {123if (_detected_modules[i].ap_dronecan == ap_dronecan &&124_detected_modules[i].node_id == node_id &&125_detected_modules[i].sensor_id == sensor_id) {126// Already Detected127already_detected = true;128break;129}130}131if (!already_detected) {132for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) {133if (nullptr == _detected_modules[i].ap_dronecan) {134_detected_modules[i].ap_dronecan = ap_dronecan;135_detected_modules[i].node_id = node_id;136_detected_modules[i].sensor_id = sensor_id;137_detected_modules[i].devid = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN,138ap_dronecan->get_driver_index(),139node_id,140sensor_id + 1); // we use sensor_id as devtype141break;142}143}144}145146struct DetectedModules tempslot;147// Sort based on the node_id, larger values first148// we do this, so that we have repeatable compass149// registration, especially in cases of extraneous150// CAN compass is connected.151for (uint8_t i = 1; i < COMPASS_MAX_BACKEND; i++) {152for (uint8_t j = i; j > 0; j--) {153if (_detected_modules[j].node_id > _detected_modules[j-1].node_id) {154tempslot = _detected_modules[j];155_detected_modules[j] = _detected_modules[j-1];156_detected_modules[j-1] = tempslot;157}158}159}160return nullptr;161}162163void AP_Compass_DroneCAN::handle_mag_msg(const Vector3f &mag)164{165Vector3f raw_field = mag * 1000.0;166167accumulate_sample(raw_field, _instance);168}169170void AP_Compass_DroneCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg)171{172WITH_SEMAPHORE(_sem_registry);173174Vector3f mag_vector;175AP_Compass_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, 0);176if (driver != nullptr) {177mag_vector[0] = msg.magnetic_field_ga[0];178mag_vector[1] = msg.magnetic_field_ga[1];179mag_vector[2] = msg.magnetic_field_ga[2];180driver->handle_mag_msg(mag_vector);181}182}183184void AP_Compass_DroneCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg)185{186WITH_SEMAPHORE(_sem_registry);187188Vector3f mag_vector;189uint8_t sensor_id = msg.sensor_id;190AP_Compass_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, sensor_id);191if (driver != nullptr) {192mag_vector[0] = msg.magnetic_field_ga[0];193mag_vector[1] = msg.magnetic_field_ga[1];194mag_vector[2] = msg.magnetic_field_ga[2];195driver->handle_mag_msg(mag_vector);196}197}198199#if AP_COMPASS_DRONECAN_HIRES_ENABLED200/*201just log hires magnetic field data for magnetic surveying202*/203void AP_Compass_DroneCAN::handle_magnetic_field_hires(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer,204const dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes &msg)205{206// @LoggerMessage: MAGH207// @Description: Magnetometer high resolution data208// @Field: TimeUS: Time since system startup209// @Field: Node: CAN node210// @Field: Sensor: sensor ID on node211// @Field: Bus: CAN bus212// @Field: Mx: X axis field213// @Field: My: y axis field214// @Field: Mz: z axis field215216#if HAL_LOGGING_ENABLED217// just log it for now218AP::logger().WriteStreaming("MAGH", "TimeUS,Node,Sensor,Bus,Mx,My,Mz", "s#-----", "F------", "QBBBfff",219transfer.timestamp_usec,220transfer.source_node_id,221ap_dronecan->get_driver_index(),222msg.sensor_id,223msg.magnetic_field_ga[0]*1000,224msg.magnetic_field_ga[1]*1000,225msg.magnetic_field_ga[2]*1000);226#endif // HAL_LOGGING_ENABLED227}228#endif // AP_COMPASS_DRONECAN_HIRES_ENABLED229230void AP_Compass_DroneCAN::read(void)231{232drain_accumulated_samples(_instance);233}234#endif // AP_COMPASS_DRONECAN_ENABLED235236237