Rover: move handling of MAG_CAL command longs up

This commit is contained in:
Peter Barker 2017-07-17 10:47:07 +10:00 committed by Francisco Ferreira
parent bd28bdd907
commit 3586f0e8fb
2 changed files with 6 additions and 6 deletions

View File

@ -1029,12 +1029,6 @@ void GCS_MAVLINK_Rover::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 = rover.compass.handle_mag_cal_command(packet);
break;
case MAV_CMD_NAV_SET_YAW_SPEED:
{
// param1 : yaw angle to adjust direction by in centidegress
@ -1538,6 +1532,11 @@ AP_ServoRelayEvents *GCS_MAVLINK_Rover::get_servorelayevents() const
return &rover.ServoRelayEvents;
}
Compass *GCS_MAVLINK_Rover::get_compass() const
{
return &rover.compass;
}
AP_Mission *GCS_MAVLINK_Rover::get_mission()
{
return &rover.mission;

View File

@ -16,6 +16,7 @@ protected:
uint32_t telem_delay() const override;
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) override;
Compass *get_compass() const override;
AP_Mission *get_mission() override;
AP_Rally *get_rally() const override { return nullptr; };
AP_ServoRelayEvents *get_servorelayevents() const override;