2023-04-08 00:53:24 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2023-04-08 00:55:40 -03:00
|
|
|
#include "AP_Compass_DroneCAN.h"
|
2023-04-08 00:53:24 -03:00
|
|
|
|
2023-04-08 00:58:13 -03:00
|
|
|
#if AP_COMPASS_DRONECAN_ENABLED
|
2023-04-08 00:53:24 -03:00
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
|
|
|
#include <AP_CANManager/AP_CANManager.h>
|
|
|
|
#include <AP_DroneCAN/AP_DroneCAN.h>
|
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
2024-03-02 18:04:32 -04:00
|
|
|
#include <AP_Logger/AP_Logger.h>
|
2023-04-08 00:53:24 -03:00
|
|
|
#include <SITL/SITL.h>
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
#define LOG_TAG "COMPASS"
|
|
|
|
|
2023-04-08 01:09:10 -03:00
|
|
|
AP_Compass_DroneCAN::DetectedModules AP_Compass_DroneCAN::_detected_modules[];
|
|
|
|
HAL_Semaphore AP_Compass_DroneCAN::_sem_registry;
|
2023-04-08 00:53:24 -03:00
|
|
|
|
2023-08-26 01:12:08 -03:00
|
|
|
AP_Compass_DroneCAN::AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint32_t devid) :
|
|
|
|
_devid(devid)
|
2023-04-08 00:53:24 -03:00
|
|
|
{
|
|
|
|
}
|
|
|
|
|
2024-11-16 23:21:13 -04:00
|
|
|
bool AP_Compass_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
2023-04-08 00:53:24 -03:00
|
|
|
{
|
2024-11-16 23:21:13 -04:00
|
|
|
const auto driver_index = ap_dronecan->get_driver_index();
|
2024-03-02 18:04:32 -04:00
|
|
|
|
2024-11-16 23:21:13 -04:00
|
|
|
return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field, driver_index) != nullptr)
|
|
|
|
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_2, driver_index) != nullptr)
|
2024-03-02 18:04:32 -04:00
|
|
|
#if AP_COMPASS_DRONECAN_HIRES_ENABLED
|
2024-11-16 23:21:13 -04:00
|
|
|
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_hires, driver_index) != nullptr)
|
2024-03-02 18:04:32 -04:00
|
|
|
#endif
|
2024-11-16 23:21:13 -04:00
|
|
|
;
|
2023-04-08 00:53:24 -03:00
|
|
|
}
|
|
|
|
|
2023-04-08 01:09:10 -03:00
|
|
|
AP_Compass_Backend* AP_Compass_DroneCAN::probe(uint8_t index)
|
2023-04-08 00:53:24 -03:00
|
|
|
{
|
2023-04-08 01:09:10 -03:00
|
|
|
AP_Compass_DroneCAN* driver = nullptr;
|
2023-04-08 00:53:24 -03:00
|
|
|
if (!_detected_modules[index].driver && _detected_modules[index].ap_dronecan) {
|
|
|
|
WITH_SEMAPHORE(_sem_registry);
|
|
|
|
// Register new Compass mode to a backend
|
2024-05-26 22:24:10 -03:00
|
|
|
driver = NEW_NOTHROW AP_Compass_DroneCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].devid);
|
2023-04-08 00:53:24 -03:00
|
|
|
if (driver) {
|
|
|
|
if (!driver->init()) {
|
|
|
|
delete driver;
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
_detected_modules[index].driver = driver;
|
|
|
|
AP::can().log_text(AP_CANManager::LOG_INFO,
|
|
|
|
LOG_TAG,
|
|
|
|
"Found Mag Node %d on Bus %d Sensor ID %d\n",
|
|
|
|
_detected_modules[index].node_id,
|
|
|
|
_detected_modules[index].ap_dronecan->get_driver_index(),
|
|
|
|
_detected_modules[index].sensor_id);
|
|
|
|
#if AP_TEST_DRONECAN_DRIVERS
|
|
|
|
// Scroll through the registered compasses, and set the offsets
|
|
|
|
if (driver->_compass.get_offsets(index).is_zero()) {
|
|
|
|
driver->_compass.set_offsets(index, AP::sitl()->mag_ofs[index]);
|
|
|
|
}
|
|
|
|
|
|
|
|
// we want to simulate a calibrated compass by default, so set
|
|
|
|
// scale to 1
|
|
|
|
AP_Param::set_default_by_name("COMPASS_SCALE", 1);
|
|
|
|
AP_Param::set_default_by_name("COMPASS_SCALE2", 1);
|
|
|
|
AP_Param::set_default_by_name("COMPASS_SCALE3", 1);
|
|
|
|
driver->save_dev_id(index);
|
|
|
|
driver->set_rotation(index, ROTATION_NONE);
|
|
|
|
|
|
|
|
// make first compass external
|
|
|
|
driver->set_external(index, true);
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return driver;
|
|
|
|
}
|
|
|
|
|
2023-04-08 01:09:10 -03:00
|
|
|
bool AP_Compass_DroneCAN::init()
|
2023-04-08 00:53:24 -03:00
|
|
|
{
|
2023-10-11 04:41:52 -03:00
|
|
|
// Adding 1 is necessary to allow backward compatibility, where this field was set as 1 by default
|
2023-04-08 00:53:24 -03:00
|
|
|
if (!register_compass(_devid, _instance)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
set_dev_id(_instance, _devid);
|
|
|
|
set_external(_instance, true);
|
|
|
|
|
2023-04-08 01:09:10 -03:00
|
|
|
AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "AP_Compass_DroneCAN loaded\n\r");
|
2023-04-08 00:53:24 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2023-04-08 01:27:51 -03:00
|
|
|
AP_Compass_DroneCAN* AP_Compass_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id)
|
2023-04-08 00:53:24 -03:00
|
|
|
{
|
|
|
|
if (ap_dronecan == nullptr) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {
|
|
|
|
if (_detected_modules[i].driver &&
|
|
|
|
_detected_modules[i].ap_dronecan == ap_dronecan &&
|
|
|
|
_detected_modules[i].node_id == node_id &&
|
|
|
|
_detected_modules[i].sensor_id == sensor_id) {
|
|
|
|
return _detected_modules[i].driver;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
bool already_detected = false;
|
2023-10-11 04:41:52 -03:00
|
|
|
// Check if there's an empty spot for possible registration
|
2023-04-08 00:53:24 -03:00
|
|
|
for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) {
|
|
|
|
if (_detected_modules[i].ap_dronecan == ap_dronecan &&
|
|
|
|
_detected_modules[i].node_id == node_id &&
|
|
|
|
_detected_modules[i].sensor_id == sensor_id) {
|
|
|
|
// Already Detected
|
|
|
|
already_detected = true;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (!already_detected) {
|
|
|
|
for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) {
|
|
|
|
if (nullptr == _detected_modules[i].ap_dronecan) {
|
|
|
|
_detected_modules[i].ap_dronecan = ap_dronecan;
|
|
|
|
_detected_modules[i].node_id = node_id;
|
|
|
|
_detected_modules[i].sensor_id = sensor_id;
|
|
|
|
_detected_modules[i].devid = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN,
|
|
|
|
ap_dronecan->get_driver_index(),
|
|
|
|
node_id,
|
|
|
|
sensor_id + 1); // we use sensor_id as devtype
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
struct DetectedModules tempslot;
|
|
|
|
// Sort based on the node_id, larger values first
|
|
|
|
// we do this, so that we have repeatable compass
|
|
|
|
// registration, especially in cases of extraneous
|
|
|
|
// CAN compass is connected.
|
|
|
|
for (uint8_t i = 1; i < COMPASS_MAX_BACKEND; i++) {
|
|
|
|
for (uint8_t j = i; j > 0; j--) {
|
|
|
|
if (_detected_modules[j].node_id > _detected_modules[j-1].node_id) {
|
|
|
|
tempslot = _detected_modules[j];
|
|
|
|
_detected_modules[j] = _detected_modules[j-1];
|
|
|
|
_detected_modules[j-1] = tempslot;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
2023-04-08 01:09:10 -03:00
|
|
|
void AP_Compass_DroneCAN::handle_mag_msg(const Vector3f &mag)
|
2023-04-08 00:53:24 -03:00
|
|
|
{
|
|
|
|
Vector3f raw_field = mag * 1000.0;
|
|
|
|
|
|
|
|
accumulate_sample(raw_field, _instance);
|
|
|
|
}
|
|
|
|
|
2023-04-08 01:09:10 -03:00
|
|
|
void AP_Compass_DroneCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg)
|
2023-04-08 00:53:24 -03:00
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_sem_registry);
|
|
|
|
|
|
|
|
Vector3f mag_vector;
|
2023-04-08 01:27:51 -03:00
|
|
|
AP_Compass_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, 0);
|
2023-04-08 00:53:24 -03:00
|
|
|
if (driver != nullptr) {
|
|
|
|
mag_vector[0] = msg.magnetic_field_ga[0];
|
|
|
|
mag_vector[1] = msg.magnetic_field_ga[1];
|
|
|
|
mag_vector[2] = msg.magnetic_field_ga[2];
|
|
|
|
driver->handle_mag_msg(mag_vector);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2023-04-08 01:09:10 -03:00
|
|
|
void AP_Compass_DroneCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg)
|
2023-04-08 00:53:24 -03:00
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_sem_registry);
|
|
|
|
|
|
|
|
Vector3f mag_vector;
|
|
|
|
uint8_t sensor_id = msg.sensor_id;
|
2023-04-08 01:27:51 -03:00
|
|
|
AP_Compass_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, sensor_id);
|
2023-04-08 00:53:24 -03:00
|
|
|
if (driver != nullptr) {
|
|
|
|
mag_vector[0] = msg.magnetic_field_ga[0];
|
|
|
|
mag_vector[1] = msg.magnetic_field_ga[1];
|
|
|
|
mag_vector[2] = msg.magnetic_field_ga[2];
|
|
|
|
driver->handle_mag_msg(mag_vector);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2024-03-02 18:04:32 -04:00
|
|
|
#if AP_COMPASS_DRONECAN_HIRES_ENABLED
|
|
|
|
/*
|
|
|
|
just log hires magnetic field data for magnetic surveying
|
|
|
|
*/
|
|
|
|
void AP_Compass_DroneCAN::handle_magnetic_field_hires(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer,
|
|
|
|
const dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes &msg)
|
|
|
|
{
|
|
|
|
// @LoggerMessage: MAGH
|
|
|
|
// @Description: Magnetometer high resolution data
|
|
|
|
// @Field: TimeUS: Time since system startup
|
|
|
|
// @Field: Node: CAN node
|
|
|
|
// @Field: Sensor: sensor ID on node
|
|
|
|
// @Field: Bus: CAN bus
|
|
|
|
// @Field: Mx: X axis field
|
|
|
|
// @Field: My: y axis field
|
|
|
|
// @Field: Mz: z axis field
|
|
|
|
|
2024-08-11 21:11:04 -03:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2024-03-02 18:04:32 -04:00
|
|
|
// just log it for now
|
2024-05-28 15:03:38 -03:00
|
|
|
AP::logger().WriteStreaming("MAGH", "TimeUS,Node,Sensor,Bus,Mx,My,Mz", "s#-----", "F------", "QBBBfff",
|
2024-03-02 18:04:32 -04:00
|
|
|
transfer.timestamp_usec,
|
|
|
|
transfer.source_node_id,
|
|
|
|
ap_dronecan->get_driver_index(),
|
|
|
|
msg.sensor_id,
|
|
|
|
msg.magnetic_field_ga[0]*1000,
|
|
|
|
msg.magnetic_field_ga[1]*1000,
|
|
|
|
msg.magnetic_field_ga[2]*1000);
|
2024-08-11 21:11:04 -03:00
|
|
|
#endif // HAL_LOGGING_ENABLED
|
2024-03-02 18:04:32 -04:00
|
|
|
}
|
2024-08-11 21:11:04 -03:00
|
|
|
#endif // AP_COMPASS_DRONECAN_HIRES_ENABLED
|
2024-03-02 18:04:32 -04:00
|
|
|
|
2023-04-08 01:09:10 -03:00
|
|
|
void AP_Compass_DroneCAN::read(void)
|
2023-04-08 00:53:24 -03:00
|
|
|
{
|
|
|
|
drain_accumulated_samples(_instance);
|
|
|
|
}
|
2023-04-08 00:58:13 -03:00
|
|
|
#endif // AP_COMPASS_DRONECAN_ENABLED
|