forked from Archive/PX4-Autopilot
drivers/uavcan: remove MAVLINK header dependency
This commit is contained in:
parent
35073d093f
commit
f7cf1ffc41
|
@ -1,10 +1,22 @@
|
|||
# UAVCAN-MAVLink parameter bridge request type
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint8 message_type # MAVLink message type: PARAM_REQUEST_READ, PARAM_REQUEST_LIST, PARAM_SET
|
||||
|
||||
uint8 MESSAGE_TYPE_PARAM_REQUEST_READ = 20 # MAVLINK_MSG_ID_PARAM_REQUEST_READ
|
||||
uint8 MESSAGE_TYPE_PARAM_REQUEST_LIST = 21 # MAVLINK_MSG_ID_PARAM_REQUEST_LIST
|
||||
uint8 MESSAGE_TYPE_PARAM_SET = 23 # MAVLINK_MSG_ID_PARAM_SET
|
||||
uint8 message_type # MAVLink message type: PARAM_REQUEST_READ, PARAM_REQUEST_LIST, PARAM_SET
|
||||
|
||||
uint8 NODE_ID_ALL = 0 # MAV_COMP_ID_ALL
|
||||
uint8 node_id # UAVCAN node ID mapped from MAVLink component ID
|
||||
|
||||
char[17] param_id # MAVLink/UAVCAN parameter name
|
||||
int16 param_index # -1 if the param_id field should be used as identifier
|
||||
|
||||
uint8 PARAM_TYPE_UINT8 = 1 # MAV_PARAM_TYPE_UINT8
|
||||
uint8 PARAM_TYPE_INT64 = 8 # MAV_PARAM_TYPE_INT64
|
||||
uint8 PARAM_TYPE_REAL32 = 9 # MAV_PARAM_TYPE_REAL32
|
||||
uint8 param_type # MAVLink parameter type
|
||||
|
||||
int64 int_value # current value if param_type is int-like
|
||||
float32 real_value # current value if param_type is float-like
|
||||
|
||||
|
|
|
@ -102,7 +102,6 @@ px4_add_module(
|
|||
MAIN uavcan
|
||||
INCLUDES
|
||||
${DSDLC_OUTPUT}
|
||||
${PX4_SOURCE_DIR}/mavlink/include/mavlink
|
||||
libuavcan/libuavcan/include
|
||||
libuavcan/libuavcan/include/dsdlc_generated
|
||||
libuavcan/libuavcan_drivers/posix/include
|
||||
|
|
|
@ -60,8 +60,6 @@
|
|||
#include <uORB/topics/vehicle_command_ack.h>
|
||||
#include <uORB/topics/uavcan_parameter_request.h>
|
||||
|
||||
#include <v2.0/common/mavlink.h>
|
||||
|
||||
/**
|
||||
* @file uavcan_servers.cpp
|
||||
*
|
||||
|
@ -334,7 +332,7 @@ UavcanServers::run(pthread_addr_t)
|
|||
* We know how many parameters are exposed by this node, so
|
||||
* process the request.
|
||||
*/
|
||||
if (request.message_type == MAVLINK_MSG_ID_PARAM_REQUEST_READ) {
|
||||
if (request.message_type == uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ) {
|
||||
uavcan::protocol::param::GetSet::Request req;
|
||||
|
||||
if (request.param_index >= 0) {
|
||||
|
@ -354,7 +352,7 @@ UavcanServers::run(pthread_addr_t)
|
|||
_param_index = request.param_index;
|
||||
}
|
||||
|
||||
} else if (request.message_type == MAVLINK_MSG_ID_PARAM_SET) {
|
||||
} else if (request.message_type == uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_SET) {
|
||||
uavcan::protocol::param::GetSet::Request req;
|
||||
|
||||
if (request.param_index >= 0) {
|
||||
|
@ -364,10 +362,10 @@ UavcanServers::run(pthread_addr_t)
|
|||
req.name = (char *)request.param_id;
|
||||
}
|
||||
|
||||
if (request.param_type == MAV_PARAM_TYPE_REAL32) {
|
||||
if (request.param_type == uavcan_parameter_request_s::PARAM_TYPE_REAL32) {
|
||||
req.value.to<uavcan::protocol::param::Value::Tag::real_value>() = request.real_value;
|
||||
|
||||
} else if (request.param_type == MAV_PARAM_TYPE_UINT8) {
|
||||
} else if (request.param_type == uavcan_parameter_request_s::PARAM_TYPE_UINT8) {
|
||||
req.value.to<uavcan::protocol::param::Value::Tag::boolean_value>() = request.int_value;
|
||||
|
||||
} else {
|
||||
|
@ -387,7 +385,7 @@ UavcanServers::run(pthread_addr_t)
|
|||
_param_index = request.param_index;
|
||||
}
|
||||
|
||||
} else if (request.message_type == MAVLINK_MSG_ID_PARAM_REQUEST_LIST) {
|
||||
} else if (request.message_type == uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
|
||||
// This triggers the _param_list_in_progress case below.
|
||||
_param_index = 0;
|
||||
_param_list_in_progress = true;
|
||||
|
@ -397,8 +395,8 @@ UavcanServers::run(pthread_addr_t)
|
|||
PX4_INFO("UAVCAN command bridge: starting component-specific param list");
|
||||
}
|
||||
|
||||
} else if (request.node_id == MAV_COMP_ID_ALL) {
|
||||
if (request.message_type == MAVLINK_MSG_ID_PARAM_REQUEST_LIST) {
|
||||
} else if (request.node_id == uavcan_parameter_request_s::NODE_ID_ALL) {
|
||||
if (request.message_type == uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
|
||||
/*
|
||||
* This triggers the _param_list_in_progress case below,
|
||||
* but additionally iterates over all active nodes.
|
||||
|
@ -644,15 +642,15 @@ UavcanServers::cb_getset(const uavcan::ServiceCallResult<uavcan::protocol::param
|
|||
response.param_count = _param_counts[response.node_id];
|
||||
|
||||
if (param.value.is(uavcan::protocol::param::Value::Tag::integer_value)) {
|
||||
response.param_type = MAV_PARAM_TYPE_INT64;
|
||||
response.param_type = uavcan_parameter_request_s::PARAM_TYPE_INT64;
|
||||
response.int_value = param.value.to<uavcan::protocol::param::Value::Tag::integer_value>();
|
||||
|
||||
} else if (param.value.is(uavcan::protocol::param::Value::Tag::real_value)) {
|
||||
response.param_type = MAV_PARAM_TYPE_REAL32;
|
||||
response.param_type = uavcan_parameter_request_s::PARAM_TYPE_REAL32;
|
||||
response.real_value = param.value.to<uavcan::protocol::param::Value::Tag::real_value>();
|
||||
|
||||
} else if (param.value.is(uavcan::protocol::param::Value::Tag::boolean_value)) {
|
||||
response.param_type = MAV_PARAM_TYPE_UINT8;
|
||||
response.param_type = uavcan_parameter_request_s::PARAM_TYPE_UINT8;
|
||||
response.int_value = param.value.to<uavcan::protocol::param::Value::Tag::boolean_value>();
|
||||
}
|
||||
|
||||
|
|
|
@ -79,11 +79,11 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
|
|||
if (req_list.target_system == mavlink_system.sysid && req_list.target_component < 127 &&
|
||||
(req_list.target_component != mavlink_system.compid || req_list.target_component == MAV_COMP_ID_ALL)) {
|
||||
// publish list request to UAVCAN driver via uORB.
|
||||
uavcan_parameter_request_s req;
|
||||
uavcan_parameter_request_s req{};
|
||||
req.message_type = msg->msgid;
|
||||
req.node_id = req_list.target_component;
|
||||
req.param_index = 0;
|
||||
|
||||
req.timestamp = hrt_absolute_time();
|
||||
_uavcan_parameter_request_pub.publish(req);
|
||||
}
|
||||
|
||||
|
@ -139,7 +139,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
|
|||
if (set.target_system == mavlink_system.sysid && set.target_component < 127 &&
|
||||
(set.target_component != mavlink_system.compid || set.target_component == MAV_COMP_ID_ALL)) {
|
||||
// publish set request to UAVCAN driver via uORB.
|
||||
uavcan_parameter_request_s req;
|
||||
uavcan_parameter_request_s req{};
|
||||
req.message_type = msg->msgid;
|
||||
req.node_id = set.target_component;
|
||||
req.param_index = -1;
|
||||
|
@ -157,6 +157,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
|
|||
req.int_value = val;
|
||||
}
|
||||
|
||||
req.timestamp = hrt_absolute_time();
|
||||
_uavcan_parameter_request_pub.publish(req);
|
||||
}
|
||||
|
||||
|
@ -217,7 +218,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
|
|||
if (req_read.target_system == mavlink_system.sysid && req_read.target_component < 127 &&
|
||||
(req_read.target_component != mavlink_system.compid || req_read.target_component == MAV_COMP_ID_ALL)) {
|
||||
// publish set request to UAVCAN driver via uORB.
|
||||
uavcan_parameter_request_s req = {};
|
||||
uavcan_parameter_request_s req{};
|
||||
req.timestamp = hrt_absolute_time();
|
||||
req.message_type = msg->msgid;
|
||||
req.node_id = req_read.target_component;
|
||||
|
|
|
@ -130,6 +130,21 @@ protected:
|
|||
rc_parameter_map_s _rc_param_map{};
|
||||
|
||||
uORB::PublicationQueued<uavcan_parameter_request_s> _uavcan_parameter_request_pub{ORB_ID(uavcan_parameter_request)};
|
||||
// enforce ORB_ID(uavcan_parameter_request) constants that map to MAVLINK defines
|
||||
static_assert(uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ == MAVLINK_MSG_ID_PARAM_REQUEST_READ,
|
||||
"uavcan_parameter_request_s MAVLINK_MSG_ID_PARAM_REQUEST_READ constant mismatch");
|
||||
static_assert(uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_SET == MAVLINK_MSG_ID_PARAM_SET,
|
||||
"uavcan_parameter_request_s MAVLINK_MSG_ID_PARAM_SET constant mismatch");
|
||||
static_assert(uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST == MAVLINK_MSG_ID_PARAM_REQUEST_LIST,
|
||||
"uavcan_parameter_request_s MAVLINK_MSG_ID_PARAM_REQUEST_LIST constant mismatch");
|
||||
static_assert(uavcan_parameter_request_s::NODE_ID_ALL == MAV_COMP_ID_ALL,
|
||||
"uavcan_parameter_request_s MAV_COMP_ID_ALL constant mismatch");
|
||||
static_assert(uavcan_parameter_request_s::PARAM_TYPE_UINT8 == MAV_PARAM_TYPE_UINT8,
|
||||
"uavcan_parameter_request_s MAV_PARAM_TYPE_UINT8 constant mismatch");
|
||||
static_assert(uavcan_parameter_request_s::PARAM_TYPE_REAL32 == MAV_PARAM_TYPE_REAL32,
|
||||
"uavcan_parameter_request_s MAV_PARAM_TYPE_REAL32 constant mismatch");
|
||||
static_assert(uavcan_parameter_request_s::PARAM_TYPE_INT64 == MAV_PARAM_TYPE_INT64,
|
||||
"uavcan_parameter_request_s MAV_PARAM_TYPE_INT64 constant mismatch");
|
||||
|
||||
uORB::Subscription _uavcan_parameter_value_sub{ORB_ID(uavcan_parameter_value)};
|
||||
|
||||
|
|
Loading…
Reference in New Issue