Copter: move handling of MAG_CAL command longs up

This commit is contained in:
Peter Barker 2017-07-17 10:47:24 +10:00 committed by Francisco Ferreira
parent 663d454119
commit fe16691c6e
2 changed files with 6 additions and 7 deletions

View File

@ -1349,13 +1349,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
break;
}
case MAV_CMD_DO_START_MAG_CAL:
case MAV_CMD_DO_ACCEPT_MAG_CAL:
case MAV_CMD_DO_CANCEL_MAG_CAL:
result = copter.compass.handle_mag_cal_command(packet);
break;
case MAV_CMD_DO_SEND_BANNER: {
result = MAV_RESULT_ACCEPTED;
@ -1948,6 +1941,11 @@ AP_Mission *GCS_MAVLINK_Copter::get_mission()
return &copter.mission;
}
Compass *GCS_MAVLINK_Copter::get_compass() const
{
return &copter.compass;
}
AP_ServoRelayEvents *GCS_MAVLINK_Copter::get_servorelayevents() const
{
return &copter.ServoRelayEvents;

View File

@ -20,6 +20,7 @@ protected:
AP_Mission *get_mission() override;
AP_Rally *get_rally() const override;
Compass *get_compass() const override;
AP_ServoRelayEvents *get_servorelayevents() const override;
uint8_t sysid_my_gcs() const override;