From 1d627a23ed8233131701351a21f4ff7b93aa9f46 Mon Sep 17 00:00:00 2001 From: Rustom Jehangir Date: Wed, 10 Feb 2016 16:24:19 -0800 Subject: [PATCH] Sub: Added COMMAND_INT message type --- ArduSub/GCS_Mavlink.cpp | 38 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 38 insertions(+) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index f693ab93da..94b74bfcd8 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -1149,6 +1149,44 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; } + + case MAVLINK_MSG_ID_COMMAND_INT: + { + // decode packet + mavlink_command_int_t packet; + mavlink_msg_command_int_decode(msg, &packet); + switch(packet.command) + { + case MAV_CMD_DO_SET_ROI: { + // param1 : /* Region of interest mode (not used)*/ + // param2 : /* MISSION index/ target ID (not used)*/ + // param3 : /* ROI index (not used)*/ + // param4 : /* empty */ + // x : lat + // y : lon + // z : alt + // sanity check location + if (labs(packet.x) >= 900000000l || labs(packet.y) >= 1800000000l) { + break; + } + Location roi_loc; + roi_loc.lat = packet.x; + roi_loc.lng = packet.y; + roi_loc.alt = (int32_t)(packet.z * 100.0f); + copter.set_auto_yaw_roi(roi_loc); + result = MAV_RESULT_ACCEPTED; + break; + } + default: + result = MAV_RESULT_UNSUPPORTED; + break; + } + + // send ACK or NAK + mavlink_msg_command_ack_send_buf(msg, chan, packet.command, result); + break; + } + // Pre-Flight calibration requests case MAVLINK_MSG_ID_COMMAND_LONG: // MAV ID: 76 {