GCS_MAVLink: move send_autopilot_request calls up to GCS base class

This commit is contained in:
Peter Barker 2017-08-19 09:07:42 +10:00 committed by Francisco Ferreira
parent d98c427514
commit add1743c12
4 changed files with 54 additions and 0 deletions

View File

@ -20,6 +20,7 @@
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#include <AP_Camera/AP_Camera.h>
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
#include <AP_Common/AP_FWVersion.h>
// check if a message will fit in the payload space available
#define HAVE_PAYLOAD_SPACE(chan, id) (comm_get_txspace(chan) >= GCS_MAVLINK::packet_overhead_chan(chan)+MAVLINK_MSG_ID_ ## id ## _LEN)
@ -232,6 +233,7 @@ protected:
virtual AP_GPS *get_gps() const = 0;
virtual AP_AdvancedFailsafe *get_advanced_failsafe() const { return nullptr; };
virtual bool set_mode(uint8_t mode) = 0;
virtual const AP_FWVersion &get_fwver() const = 0;
bool waypoint_receiving; // currently receiving
// the following two variables are only here because of Tracker
@ -276,6 +278,9 @@ protected:
MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet);
virtual MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet);
void handle_send_autopilot_version(const mavlink_message_t *msg);
MAV_RESULT handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet);
void handle_device_op_read(mavlink_message_t *msg);
void handle_device_op_write(mavlink_message_t *msg);

View File

@ -1820,6 +1820,10 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
handle_set_mode(msg);
break;
case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
handle_send_autopilot_version(msg);
break;
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
/* fall through */
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
@ -1943,6 +1947,14 @@ void GCS_MAVLINK::handle_common_mission_message(mavlink_message_t *msg)
}
}
void GCS_MAVLINK::handle_send_autopilot_version(const mavlink_message_t *msg)
{
const AP_FWVersion &fwver = get_fwver();
send_autopilot_version(fwver.major, fwver.minor, fwver.patch, fwver.fw_type);
}
MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
{
Compass *compass = get_compass();
@ -1974,6 +1986,17 @@ MAV_RESULT GCS_MAVLINK::handle_command_mag_cal(const mavlink_command_long_t &pac
return compass->handle_mag_cal_command(packet);
}
MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet)
{
if (!is_equal(packet.param1,1.0f)) {
return MAV_RESULT_FAILED;
}
const AP_FWVersion &fwver = get_fwver();
send_autopilot_version(fwver.major, fwver.minor, fwver.patch, fwver.fw_type);
return MAV_RESULT_ACCEPTED;
}
MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &packet)
{
MAV_RESULT result = MAV_RESULT_FAILED;
@ -1999,6 +2022,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &pack
result = handle_command_camera(packet);
break;
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: {
result = handle_command_request_autopilot_capabilities(packet);
break;
}
case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS: {
result = handle_command_preflight_set_sensor_offsets(packet);
break;

View File

@ -1,5 +1,14 @@
#include "GCS.h"
const AP_FWVersion fwver
{
major: 3,
minor: 1,
patch: 4,
fw_type: FIRMWARE_VERSION_TYPE_DEV,
fw_string: "Dummy GCS"
};
/*
* GCS backend used for many examples and tools
*/
@ -20,6 +29,7 @@ protected:
AP_GPS *get_gps() const override { return nullptr; };
AP_Camera *get_camera() const override { return nullptr; };
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
const AP_FWVersion &get_fwver() const override { return fwver; }
uint8_t sysid_my_gcs() const override { return 1; }
bool set_mode(uint8_t mode) override { return false; };

View File

@ -11,6 +11,16 @@ void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
const AP_FWVersion fwver
{
major: 3,
minor: 1,
patch: 4,
fw_type: FIRMWARE_VERSION_TYPE_DEV,
fw_string: "routing example"
};
class GCS_MAVLINK_routing : public GCS_MAVLINK
{
@ -29,6 +39,7 @@ protected:
AP_Camera *get_camera() const override { return nullptr; };
uint8_t sysid_my_gcs() const override { return 1; }
bool set_mode(uint8_t mode) override { return false; };
const AP_FWVersion &get_fwver() const override { return fwver; }
private: