|
|
|
@ -41,6 +41,7 @@
@@ -41,6 +41,7 @@
|
|
|
|
|
#include <ardupilot/indication/Button.hpp> |
|
|
|
|
#include <ardupilot/equipment/trafficmonitor/TrafficReport.hpp> |
|
|
|
|
#include <uavcan/equipment/gnss/RTCMStream.hpp> |
|
|
|
|
#include <uavcan/protocol/debug/LogMessage.hpp> |
|
|
|
|
|
|
|
|
|
#include <AP_Baro/AP_Baro_UAVCAN.h> |
|
|
|
|
#include <AP_RangeFinder/AP_RangeFinder_UAVCAN.h> |
|
|
|
@ -129,6 +130,10 @@ static uavcan::Subscriber<uavcan::equipment::actuator::Status, ActuatorStatusCb>
@@ -129,6 +130,10 @@ static uavcan::Subscriber<uavcan::equipment::actuator::Status, ActuatorStatusCb>
|
|
|
|
|
UC_REGISTRY_BINDER(ESCStatusCb, uavcan::equipment::esc::Status); |
|
|
|
|
static uavcan::Subscriber<uavcan::equipment::esc::Status, ESCStatusCb> *esc_status_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS]; |
|
|
|
|
|
|
|
|
|
// handler DEBUG
|
|
|
|
|
UC_REGISTRY_BINDER(DebugCb, uavcan::protocol::debug::LogMessage); |
|
|
|
|
static uavcan::Subscriber<uavcan::protocol::debug::LogMessage, DebugCb> *debug_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS]; |
|
|
|
|
|
|
|
|
|
AP_UAVCAN::esc_data AP_UAVCAN::_escs_data[]; |
|
|
|
|
HAL_Semaphore AP_UAVCAN::_telem_sem; |
|
|
|
|
|
|
|
|
@ -302,6 +307,11 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters)
@@ -302,6 +307,11 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters)
|
|
|
|
|
if (esc_status_listener[driver_index]) { |
|
|
|
|
esc_status_listener[driver_index]->start(ESCStatusCb(this, &handle_ESC_status)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
debug_listener[driver_index] = new uavcan::Subscriber<uavcan::protocol::debug::LogMessage, DebugCb>(*_node); |
|
|
|
|
if (debug_listener[driver_index]) { |
|
|
|
|
debug_listener[driver_index]->start(DebugCb(this, &handle_debug)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_led_conf.devices_count = 0; |
|
|
|
|
if (enable_filters) { |
|
|
|
@ -871,4 +881,21 @@ bool AP_UAVCAN::is_esc_data_index_valid(const uint8_t index) {
@@ -871,4 +881,21 @@ bool AP_UAVCAN::is_esc_data_index_valid(const uint8_t index) {
|
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
handle LogMessage debug |
|
|
|
|
*/ |
|
|
|
|
void AP_UAVCAN::handle_debug(AP_UAVCAN* ap_uavcan, uint8_t node_id, const DebugCb &cb) |
|
|
|
|
{ |
|
|
|
|
#ifndef HAL_NO_LOGGING |
|
|
|
|
const auto &msg = *cb.msg; |
|
|
|
|
if (AP::can().get_log_level() != AP_CANManager::LOG_NONE) { |
|
|
|
|
// log to onboard log and mavlink
|
|
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "CAN[%u] %s", node_id, msg.text.c_str()); |
|
|
|
|
} else { |
|
|
|
|
// only log to onboard log
|
|
|
|
|
AP::logger().Write_MessageF("CAN[%u] %s", node_id, msg.text.c_str()); |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#endif // HAL_NUM_CAN_IFACES
|
|
|
|
|