GCS_MAVLink: move handling of MAG_CAL command longs up
This commit is contained in:
parent
6b53b5b5f3
commit
bd28bdd907
@ -220,6 +220,7 @@ protected:
|
|||||||
virtual bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) { return true; }
|
virtual bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) { return true; }
|
||||||
virtual AP_Mission *get_mission() = 0;
|
virtual AP_Mission *get_mission() = 0;
|
||||||
virtual AP_Rally *get_rally() const = 0;
|
virtual AP_Rally *get_rally() const = 0;
|
||||||
|
virtual Compass *get_compass() const = 0;
|
||||||
virtual AP_ServoRelayEvents *get_servorelayevents() const = 0;
|
virtual AP_ServoRelayEvents *get_servorelayevents() const = 0;
|
||||||
|
|
||||||
bool waypoint_receiving; // currently receiving
|
bool waypoint_receiving; // currently receiving
|
||||||
@ -275,6 +276,7 @@ protected:
|
|||||||
bool telemetry_delayed() const;
|
bool telemetry_delayed() const;
|
||||||
virtual uint32_t telem_delay() const = 0;
|
virtual uint32_t telem_delay() const = 0;
|
||||||
|
|
||||||
|
MAV_RESULT handle_command_mag_cal(const mavlink_command_long_t &packet);
|
||||||
MAV_RESULT handle_command_long_message(mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_long_message(mavlink_command_long_t &packet);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
@ -1835,12 +1835,28 @@ void GCS_MAVLINK::handle_common_mission_message(mavlink_message_t *msg)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
MAV_RESULT GCS_MAVLINK::handle_command_mag_cal(const mavlink_command_long_t &packet)
|
||||||
|
{
|
||||||
|
Compass *compass = get_compass();
|
||||||
|
if (compass == nullptr) {
|
||||||
|
return MAV_RESULT_UNSUPPORTED;
|
||||||
|
}
|
||||||
|
return compass->handle_mag_cal_command(packet);
|
||||||
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &packet)
|
||||||
{
|
{
|
||||||
MAV_RESULT result = MAV_RESULT_FAILED;
|
MAV_RESULT result = MAV_RESULT_FAILED;
|
||||||
|
|
||||||
switch (packet.command) {
|
switch (packet.command) {
|
||||||
|
|
||||||
|
case MAV_CMD_DO_START_MAG_CAL:
|
||||||
|
case MAV_CMD_DO_ACCEPT_MAG_CAL:
|
||||||
|
case MAV_CMD_DO_CANCEL_MAG_CAL: {
|
||||||
|
result = handle_command_mag_cal(packet);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
case MAV_CMD_START_RX_PAIR:
|
case MAV_CMD_START_RX_PAIR:
|
||||||
result = handle_rc_bind(packet);
|
result = handle_rc_bind(packet);
|
||||||
break;
|
break;
|
||||||
|
@ -14,6 +14,7 @@ class GCS_MAVLINK_Dummy : public GCS_MAVLINK
|
|||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
Compass *get_compass() const override { return nullptr; };
|
||||||
AP_Mission *get_mission() override { return nullptr; }
|
AP_Mission *get_mission() override { return nullptr; }
|
||||||
AP_Rally *get_rally() const override { return nullptr; };
|
AP_Rally *get_rally() const override { return nullptr; };
|
||||||
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
||||||
|
@ -21,6 +21,7 @@ public:
|
|||||||
protected:
|
protected:
|
||||||
|
|
||||||
uint32_t telem_delay() const override { return 0; }
|
uint32_t telem_delay() const override { return 0; }
|
||||||
|
Compass *get_compass() const override { return nullptr; };
|
||||||
AP_Mission *get_mission() override { return nullptr; }
|
AP_Mission *get_mission() override { return nullptr; }
|
||||||
AP_Rally *get_rally() const override { return nullptr; }
|
AP_Rally *get_rally() const override { return nullptr; }
|
||||||
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
||||||
|
Loading…
Reference in New Issue
Block a user