Browse Source

mavlink: set correct param capability

PX4 supports int32 parameter types by interpreting the 32 bits in
the float field as an int32 field. To signal this behaviour, it should
set the bit which is described as PARAM_ENCODE_BYTEWISE.

PX4 had always handled parameters this way but never actually sent the
capability (which back then was called PARAM_UNION), however, it should
have. This came up recently in the MAVLink devcall when these flags were
discussed. The takeaway was to remove the flags to make it clearer and
to make sure the projects (like PX4) send them out correctly.
v1.13.0-BW
Julian Oes 3 years ago committed by Lorenz Meier
parent
commit
a5bd65b923
  1. 1
      src/modules/mavlink/mavlink_main.cpp

1
src/modules/mavlink/mavlink_main.cpp

@ -1056,6 +1056,7 @@ Mavlink::send_autopilot_capabilities() @@ -1056,6 +1056,7 @@ Mavlink::send_autopilot_capabilities()
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_INT;
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT;
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_COMMAND_INT;
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE;
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_FTP;
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET;
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED;

Loading…
Cancel
Save