GCS_MAVLink: use compass singleton instead of subclass callback

This commit is contained in:
Peter Barker 2018-08-30 19:57:27 +10:00 committed by Peter Barker
parent 066c26e445
commit d5f6911db7
4 changed files with 6 additions and 19 deletions

View File

@ -254,7 +254,6 @@ protected:
virtual bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) { return true; }
virtual AP_Mission *get_mission() = 0;
virtual AP_Rally *get_rally() const = 0;
virtual Compass *get_compass() const = 0;
virtual class AP_Camera *get_camera() const = 0;
virtual AP_AdvancedFailsafe *get_advanced_failsafe() const { return nullptr; };
virtual AP_VisualOdom *get_visual_odom() const { return nullptr; }

View File

@ -2538,10 +2538,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_flash_bootloader(const mavlink_command_lo
MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
{
Compass *compass = get_compass();
if (compass == nullptr) {
return MAV_RESULT_UNSUPPORTED;
}
Compass &compass = AP::compass();
uint8_t compassNumber = -1;
if (is_equal(packet.param1, 2.0f)) {
@ -2554,7 +2551,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlin
if (compassNumber == (uint8_t) -1) {
return MAV_RESULT_FAILED;
}
compass->set_and_save_offsets(compassNumber, packet.param2, packet.param3, packet.param4);
compass.set_and_save_offsets(compassNumber, packet.param2, packet.param3, packet.param4);
return MAV_RESULT_ACCEPTED;
}
@ -2640,11 +2637,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_calibration(const mavlink_comma
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);
return AP::compass().handle_mag_cal_command(packet);
}
MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet)
@ -2845,18 +2838,15 @@ void GCS_MAVLINK::handle_command_int(mavlink_message_t *msg)
bool GCS_MAVLINK::try_send_compass_message(const enum ap_message id)
{
Compass *compass = get_compass();
if (compass == nullptr) {
return true;
}
Compass &compass = AP::compass();
bool ret = true;
switch (id) {
case MSG_MAG_CAL_PROGRESS:
compass->send_mag_cal_progress(chan);
compass.send_mag_cal_progress(chan);
ret = true;;
break;
case MSG_MAG_CAL_REPORT:
compass->send_mag_cal_report(chan);
compass.send_mag_cal_report(chan);
ret = true;
break;
default:

View File

@ -22,7 +22,6 @@ class GCS_MAVLINK_Dummy : public GCS_MAVLINK
protected:
Compass *get_compass() const override { return nullptr; };
AP_Mission *get_mission() override { return nullptr; }
AP_Rally *get_rally() const override { return nullptr; };
AP_Camera *get_camera() const override { return nullptr; };

View File

@ -28,7 +28,6 @@ public:
protected:
uint32_t telem_delay() const override { return 0; }
Compass *get_compass() const override { return nullptr; };
AP_Mission *get_mission() override { return nullptr; }
AP_Rally *get_rally() const override { return nullptr; }
AP_Camera *get_camera() const override { return nullptr; };