diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index c26bc1ad8a..c53aebb9d0 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -354,11 +354,12 @@ protected: virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet); virtual MAV_RESULT _handle_command_preflight_calibration_baro(); + void handle_command_long(mavlink_message_t* msg); MAV_RESULT handle_command_mag_cal(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_long_message(mavlink_command_long_t &packet); + virtual MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet); MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet); MAV_RESULT handle_command_do_send_banner(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_do_gripper(mavlink_command_long_t &packet); + MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet); MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet); MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet); @@ -392,7 +393,7 @@ private: virtual void handleMessage(mavlink_message_t * msg) = 0; - MAV_RESULT handle_servorelay_message(mavlink_command_long_t &packet); + MAV_RESULT handle_servorelay_message(const mavlink_command_long_t &packet); bool calibrate_gyros(); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 22068e7297..1c00185922 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -2318,6 +2318,10 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg) handle_common_mission_message(msg); break; + case MAVLINK_MSG_ID_COMMAND_LONG: + handle_command_long(msg); + break; + case MAVLINK_MSG_ID_COMMAND_INT: handle_command_int(msg); break; @@ -2653,7 +2657,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_get_home_position(const mavlink_command_l return MAV_RESULT_ACCEPTED; } -MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(const mavlink_command_long_t &packet) { AP_Gripper *gripper = AP::gripper(); if (gripper == nullptr) { @@ -2685,7 +2689,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(mavlink_command_long_t &packet return result; } -MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t &packet) { MAV_RESULT result = MAV_RESULT_FAILED; @@ -2773,6 +2777,18 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &pack return result; } +void GCS_MAVLINK::handle_command_long(mavlink_message_t *msg) +{ + // decode packet + mavlink_command_long_t packet; + mavlink_msg_command_long_decode(msg, &packet); + + const MAV_RESULT result = handle_command_long_packet(packet); + + // send ACK or NAK + mavlink_msg_command_ack_send_buf(msg, chan, packet.command, result); +} + MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &packet) { return MAV_RESULT_UNSUPPORTED; diff --git a/libraries/GCS_MAVLink/GCS_ServoRelay.cpp b/libraries/GCS_MAVLink/GCS_ServoRelay.cpp index 466e905c61..e2e8a24a1d 100644 --- a/libraries/GCS_MAVLink/GCS_ServoRelay.cpp +++ b/libraries/GCS_MAVLink/GCS_ServoRelay.cpp @@ -2,7 +2,7 @@ #include "AP_ServoRelayEvents/AP_ServoRelayEvents.h" -MAV_RESULT GCS_MAVLINK::handle_servorelay_message(mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t &packet) { AP_ServoRelayEvents *handler = AP::servorelayevents(); if (handler == nullptr) {