29 #define debug_gps_uavcan(level, fmt, args...) do { if ((level) <= AP_BoardConfig_CAN::get_can_debug()) { printf(fmt, ##args); }} while (0) 40 if (hal.
can_mgr[_manager] !=
nullptr) {
42 if (ap_uavcan !=
nullptr) {
45 debug_gps_uavcan(2,
"AP_GPS_UAVCAN destructed\n\r");
62 state = _interm_state;
82 #endif // HAL_WITH_UAVCAN
~AP_GPS_UAVCAN() override
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual Semaphore * new_semaphore(void)
AP_HAL::CANManager ** can_mgr
void set_uavcan_manager(uint8_t mgr)
void remove_gps_listener(AP_GPS_Backend *rem_listener)
AP_GPS::GPS_State & state
public state for this instance
void handle_gnss_msg(const AP_GPS::GPS_State &msg) override
AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)