mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: added support for FlexDebug message
allows lua to retrieve vendor specific data from CAN nodes
This commit is contained in:
parent
e7bfd400e8
commit
349ebde101
|
@ -414,6 +414,16 @@ function CAN:get_device(buffer_len) end
|
|||
---@return ScriptingCANBuffer_ud|nil
|
||||
function CAN:get_device2(buffer_len) end
|
||||
|
||||
|
||||
-- get latest FlexDebug message from a CAN node
|
||||
---@param bus number -- CAN bus number, 0 for first bus, 1 for 2nd
|
||||
---@param node number -- CAN node
|
||||
---@param id number -- FlexDebug message ID
|
||||
---@param last_us uint32_t_ud|integer|number -- timestamp of last received message, new message will be returned if timestamp is different
|
||||
---@return uint32_t_ud|nil -- timestamp of message (first frame arrival time)
|
||||
---@return string|nil -- up to 255 byte buffer
|
||||
function DroneCAN_get_FlexDebug(bus,node,id,last_us) end
|
||||
|
||||
-- Auto generated binding
|
||||
|
||||
-- desc
|
||||
|
|
|
@ -698,6 +698,9 @@ ap_object ScriptingCANBuffer method write_frame boolean AP_HAL::CANFrame uint32_
|
|||
ap_object ScriptingCANBuffer method read_frame boolean AP_HAL::CANFrame'Null
|
||||
ap_object ScriptingCANBuffer method add_filter boolean uint32_t'skip_check uint32_t'skip_check
|
||||
|
||||
include AP_DroneCAN/AP_DroneCAN.h
|
||||
global manual DroneCAN_get_FlexDebug lua_DroneCAN_get_FlexDebug 4 2 depends (HAL_ENABLE_DRONECAN_DRIVERS==1)
|
||||
|
||||
include ../Tools/AP_Periph/AP_Periph.h depends defined(HAL_BUILD_AP_PERIPH)
|
||||
singleton AP_Periph_FW depends defined(HAL_BUILD_AP_PERIPH)
|
||||
singleton AP_Periph_FW rename periph
|
||||
|
|
|
@ -1237,4 +1237,34 @@ int lua_GCS_command_int(lua_State *L)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if HAL_ENABLE_DRONECAN_DRIVERS
|
||||
/*
|
||||
get FlexDebug from a DroneCAN node
|
||||
*/
|
||||
int lua_DroneCAN_get_FlexDebug(lua_State *L)
|
||||
{
|
||||
binding_argcheck(L, 4);
|
||||
|
||||
const uint8_t bus = get_uint8_t(L, 1);
|
||||
const uint8_t node_id = get_uint8_t(L, 2);
|
||||
const uint16_t msg_id = get_uint16_t(L, 3);
|
||||
uint32_t tstamp_us = get_uint32(L, 4, 0, UINT32_MAX);
|
||||
|
||||
const auto *dc = AP_DroneCAN::get_dronecan(bus);
|
||||
if (dc == nullptr) {
|
||||
return 0;
|
||||
}
|
||||
dronecan_protocol_FlexDebug msg;
|
||||
|
||||
if (!dc->get_FlexDebug(node_id, msg_id, tstamp_us, msg)) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
*new_uint32_t(L) = tstamp_us;
|
||||
lua_pushlstring(L, (const char *)msg.u8.data, msg.u8.len);
|
||||
|
||||
return 2;
|
||||
}
|
||||
#endif // HAL_ENABLE_DRONECAN_DRIVERS
|
||||
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
|
|
@ -34,3 +34,4 @@ int lua_mavlink_block_command(lua_State *L);
|
|||
int lua_print(lua_State *L);
|
||||
int lua_range_finder_handle_script_msg(lua_State *L);
|
||||
int lua_GCS_command_int(lua_State *L);
|
||||
int lua_DroneCAN_get_FlexDebug(lua_State *L);
|
||||
|
|
Loading…
Reference in New Issue