AP_DroneCAN: support FlexDebug message

This commit is contained in:
Andrew Tridgell 2024-10-23 10:44:56 +09:00 committed by Peter Barker
parent bfe567cd51
commit 25631291d7
2 changed files with 77 additions and 1 deletions

View File

@ -128,7 +128,7 @@ const AP_Param::GroupInfo AP_DroneCAN::var_info[] = {
// @Param: OPTION
// @DisplayName: DroneCAN options
// @Description: Option flags
// @Bitmask: 0:ClearDNADatabase,1:IgnoreDNANodeConflicts,2:EnableCanfd,3:IgnoreDNANodeUnhealthy,4:SendServoAsPWM,5:SendGNSS,6:UseHimarkServo,7:HobbyWingESC,8:EnableStats
// @Bitmask: 0:ClearDNADatabase,1:IgnoreDNANodeConflicts,2:EnableCanfd,3:IgnoreDNANodeUnhealthy,4:SendServoAsPWM,5:SendGNSS,6:UseHimarkServo,7:HobbyWingESC,8:EnableStats,9:EnableFlexDebug
// @User: Advanced
AP_GROUPINFO("OPTION", 5, AP_DroneCAN, _options, 0),
@ -1503,6 +1503,62 @@ bool AP_DroneCAN::is_esc_data_index_valid(const uint8_t index) {
return true;
}
#if AP_SCRIPTING_ENABLED
/*
handle FlexDebug message, holding a copy locally for a lua script to access
*/
void AP_DroneCAN::handle_FlexDebug(const CanardRxTransfer& transfer, const dronecan_protocol_FlexDebug &msg)
{
if (!option_is_set(Options::ENABLE_FLEX_DEBUG)) {
return;
}
// find an existing element in the list
const uint8_t source_node = transfer.source_node_id;
for (auto *p = flexDebug_list; p != nullptr; p = p->next) {
if (p->node_id == source_node && p->msg.id == msg.id) {
p->msg = msg;
p->timestamp_us = uint32_t(transfer.timestamp_usec);
return;
}
}
// new message ID, add to the list. Note that this gets called
// only from one thread, so no lock needed
auto *p = NEW_NOTHROW FlexDebug;
if (p == nullptr) {
return;
}
p->node_id = source_node;
p->msg = msg;
p->timestamp_us = uint32_t(transfer.timestamp_usec);
p->next = flexDebug_list;
// link into the list
flexDebug_list = p;
}
/*
get the last FlexDebug message from a node
*/
bool AP_DroneCAN::get_FlexDebug(uint8_t node_id, uint16_t msg_id, uint32_t &timestamp_us, dronecan_protocol_FlexDebug &msg) const
{
for (const auto *p = flexDebug_list; p != nullptr; p = p->next) {
if (p->node_id == node_id && p->msg.id == msg_id) {
if (timestamp_us == p->timestamp_us) {
// stale message
return false;
}
timestamp_us = p->timestamp_us;
msg = p->msg;
return true;
}
}
return false;
}
#endif // AP_SCRIPTING_ENABLED
/*
handle LogMessage debug
*/

View File

@ -148,6 +148,7 @@ public:
USE_HIMARK_SERVO = (1U<<6),
USE_HOBBYWING_ESC = (1U<<7),
ENABLE_STATS = (1U<<8),
ENABLE_FLEX_DEBUG = (1U<<9),
};
// check if a option is set
@ -176,6 +177,10 @@ public:
Canard::Publisher<uavcan_equipment_hardpoint_Command> relay_hardpoint{canard_iface};
#endif
#if AP_SCRIPTING_ENABLED
bool get_FlexDebug(uint8_t node_id, uint16_t msg_id, uint32_t &timestamp_us, dronecan_protocol_FlexDebug &msg) const;
#endif
private:
void loop(void);
@ -363,6 +368,11 @@ private:
Canard::Server<uavcan_protocol_GetNodeInfoRequest> node_info_server{canard_iface, node_info_req_cb};
uavcan_protocol_GetNodeInfoResponse node_info_rsp;
#if AP_SCRIPTING_ENABLED
Canard::ObjCallback<AP_DroneCAN, dronecan_protocol_FlexDebug> FlexDebug_cb{this, &AP_DroneCAN::handle_FlexDebug};
Canard::Subscriber<dronecan_protocol_FlexDebug> FlexDebug_listener{FlexDebug_cb, _driver_index};
#endif
#if AP_DRONECAN_HOBBYWING_ESC_SUPPORT
/*
Hobbywing ESC support. Note that we need additional meta-data as
@ -409,6 +419,16 @@ private:
void handle_param_get_set_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_GetSetResponse& rsp);
void handle_param_save_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_ExecuteOpcodeResponse& rsp);
void handle_node_info_request(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoRequest& req);
#if AP_SCRIPTING_ENABLED
void handle_FlexDebug(const CanardRxTransfer& transfer, const dronecan_protocol_FlexDebug& msg);
struct FlexDebug {
struct FlexDebug *next;
uint32_t timestamp_us;
uint8_t node_id;
dronecan_protocol_FlexDebug msg;
} *flexDebug_list;
#endif
};
#endif // #if HAL_ENABLE_DRONECAN_DRIVERS