Commit 840b425c authored by Don Gagne's avatar Don Gagne

Add MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES support

parent 1deab759
...@@ -803,6 +803,10 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg) ...@@ -803,6 +803,10 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg)
case MAV_CMD_PREFLIGHT_STORAGE: case MAV_CMD_PREFLIGHT_STORAGE:
commandResult = MAV_RESULT_ACCEPTED; commandResult = MAV_RESULT_ACCEPTED;
break; break;
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
commandResult = MAV_RESULT_ACCEPTED;
_respondWithAutopilotVersion();
break;
} }
mavlink_message_t commandAck; mavlink_message_t commandAck;
...@@ -814,6 +818,31 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg) ...@@ -814,6 +818,31 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg)
respondWithMavlinkMessage(commandAck); respondWithMavlinkMessage(commandAck);
} }
void MockLink::_respondWithAutopilotVersion(void)
{
mavlink_message_t msg;
uint8_t customVersion[8];
memset(customVersion, 0, sizeof(customVersion));
// Only flight_sw_version is supported a this point
mavlink_msg_autopilot_version_pack(_vehicleSystemId,
_vehicleComponentId,
&msg,
0, // capabilities,
(1 << (8*3)) | FIRMWARE_VERSION_TYPE_DEV, // flight_sw_version,
0, // middleware_sw_version,
0, // os_sw_version,
0, // board_version,
(uint8_t *)&customVersion, // flight_custom_version,
(uint8_t *)&customVersion, // middleware_custom_version,
(uint8_t *)&customVersion, // os_custom_version,
0, // vendor_id,
0, // product_id,
0); // uid
respondWithMavlinkMessage(msg);
}
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode) void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
{ {
_missionItemHandler.setMissionItemFailureMode(failureMode); _missionItemHandler.setMissionItemFailureMode(failureMode);
......
...@@ -185,6 +185,7 @@ private: ...@@ -185,6 +185,7 @@ private:
void _sendGpsRawInt(void); void _sendGpsRawInt(void);
void _sendVibration(void); void _sendVibration(void);
void _sendStatusTextMessages(void); void _sendStatusTextMessages(void);
void _respondWithAutopilotVersion(void);
static MockLink* _startMockLink(MockConfiguration* mockConfig); static MockLink* _startMockLink(MockConfiguration* mockConfig);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment