mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 01:48:29 -04:00
AP_Compass: adapt to changes in AP_BoardConfig_CAN
This commit is contained in:
parent
31b8a051cc
commit
317e8e0296
@ -19,19 +19,11 @@
|
|||||||
|
|
||||||
#include "AP_Compass_UAVCAN.h"
|
#include "AP_Compass_UAVCAN.h"
|
||||||
|
|
||||||
#if HAL_OS_POSIX_IO
|
|
||||||
#include <sys/types.h>
|
|
||||||
#include <sys/stat.h>
|
|
||||||
#include <fcntl.h>
|
|
||||||
#include <unistd.h>
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
|
||||||
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
|
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#define debug_mag_uavcan(level, fmt, args...) do { if ((level) <= AP_BoardConfig_CAN::get_can_debug()) { printf(fmt, ##args); }} while (0)
|
#define debug_mag_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { printf(fmt, ##args); }} while (0)
|
||||||
|
|
||||||
/*
|
/*
|
||||||
constructor - registers instance at top Compass driver
|
constructor - registers instance at top Compass driver
|
||||||
@ -56,18 +48,16 @@ AP_Compass_UAVCAN::~AP_Compass_UAVCAN()
|
|||||||
ap_uavcan->remove_mag_listener(this);
|
ap_uavcan->remove_mag_listener(this);
|
||||||
delete _sem_mag;
|
delete _sem_mag;
|
||||||
|
|
||||||
debug_mag_uavcan(2, "AP_Compass_UAVCAN destructed\n\r");
|
debug_mag_uavcan(2, _manager, "AP_Compass_UAVCAN destructed\n\r");
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Compass_Backend *AP_Compass_UAVCAN::probe(Compass &compass)
|
AP_Compass_Backend *AP_Compass_UAVCAN::probe(Compass &compass)
|
||||||
{
|
{
|
||||||
if (AP_BoardConfig_CAN::get_can_num_ifaces() == 0) {
|
uint8_t can_num_drivers = AP::can().get_num_drivers();
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
AP_Compass_UAVCAN *sensor;
|
AP_Compass_UAVCAN *sensor;
|
||||||
|
|
||||||
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
|
for (uint8_t i = 0; i < can_num_drivers; i++) {
|
||||||
AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i);
|
AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i);
|
||||||
if (ap_uavcan == nullptr) {
|
if (ap_uavcan == nullptr) {
|
||||||
continue;
|
continue;
|
||||||
@ -79,7 +69,7 @@ AP_Compass_Backend *AP_Compass_UAVCAN::probe(Compass &compass)
|
|||||||
sensor = new AP_Compass_UAVCAN(compass);
|
sensor = new AP_Compass_UAVCAN(compass);
|
||||||
|
|
||||||
if (sensor->register_uavcan_compass(i, freemag)) {
|
if (sensor->register_uavcan_compass(i, freemag)) {
|
||||||
debug_mag_uavcan(2, "AP_Compass_UAVCAN probed, drv: %d, node: %d\n\r", i, freemag);
|
debug_mag_uavcan(2, i, "AP_Compass_UAVCAN probed, drv: %d, node: %d\n\r", i, freemag);
|
||||||
return sensor;
|
return sensor;
|
||||||
} else {
|
} else {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
@ -123,7 +113,7 @@ bool AP_Compass_UAVCAN::register_uavcan_compass(uint8_t mgr, uint8_t node)
|
|||||||
_sum.zero();
|
_sum.zero();
|
||||||
_count = 0;
|
_count = 0;
|
||||||
|
|
||||||
debug_mag_uavcan(2, "AP_Compass_UAVCAN loaded\n\r");
|
debug_mag_uavcan(2, mgr, "AP_Compass_UAVCAN loaded\n\r");
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user