GCS_Common: handle command_long in GCS base class

This commit is contained in:
Peter Barker 2018-07-04 12:16:16 +10:00 committed by Peter Barker
parent aa4ee64af2
commit 4775a67ea0
3 changed files with 23 additions and 6 deletions

View File

@ -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();

View File

@ -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;

View File

@ -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) {