Plane: use GCS_MAVLINK subclasses to handle set_mode

This commit is contained in:
Peter Barker 2017-08-11 16:11:31 +10:00
parent aa06fc499c
commit 8eeae45300
4 changed files with 34 additions and 38 deletions

View File

@ -1397,12 +1397,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
break;
}
case MAVLINK_MSG_ID_SET_MODE:
{
handle_set_mode(msg, FUNCTOR_BIND(&plane, &Plane::mavlink_set_mode, bool, uint8_t));
break;
}
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
{
// mark the firmware version in the tlog
@ -1909,3 +1903,35 @@ AP_Rally *GCS_MAVLINK_Plane::get_rally() const
{
return &plane.rally;
}
/*
set_mode() wrapper for MAVLink SET_MODE
*/
bool GCS_MAVLINK_Plane::set_mode(const uint8_t mode)
{
switch (mode) {
case MANUAL:
case CIRCLE:
case STABILIZE:
case TRAINING:
case ACRO:
case FLY_BY_WIRE_A:
case AUTOTUNE:
case FLY_BY_WIRE_B:
case CRUISE:
case AVOID_ADSB:
case GUIDED:
case AUTO:
case RTL:
case LOITER:
case QSTABILIZE:
case QHOVER:
case QLOITER:
case QLAND:
case QRTL:
plane.set_mode((enum FlightMode)mode, MODE_REASON_GCS_COMMAND);
return true;
}
return false;
}

View File

@ -30,6 +30,8 @@ protected:
uint8_t sysid_my_gcs() const override;
bool set_mode(uint8_t mode) override;
private:
void handleMessage(mavlink_message_t * msg) override;

View File

@ -963,7 +963,6 @@ private:
void startup_ground(void);
enum FlightMode get_previous_mode();
void set_mode(enum FlightMode mode, mode_reason_t reason);
bool mavlink_set_mode(uint8_t mode);
void exit_mode(enum FlightMode mode);
void check_long_failsafe();
void check_short_failsafe();

View File

@ -462,37 +462,6 @@ void Plane::set_mode(enum FlightMode mode, mode_reason_t reason)
steerController.reset_I();
}
/*
set_mode() wrapper for MAVLink SET_MODE
*/
bool Plane::mavlink_set_mode(uint8_t mode)
{
switch (mode) {
case MANUAL:
case CIRCLE:
case STABILIZE:
case TRAINING:
case ACRO:
case FLY_BY_WIRE_A:
case AUTOTUNE:
case FLY_BY_WIRE_B:
case CRUISE:
case AVOID_ADSB:
case GUIDED:
case AUTO:
case RTL:
case LOITER:
case QSTABILIZE:
case QHOVER:
case QLOITER:
case QLAND:
case QRTL:
set_mode((enum FlightMode)mode, MODE_REASON_GCS_COMMAND);
return true;
}
return false;
}
// exit_mode - perform any cleanup required when leaving a flight mode
void Plane::exit_mode(enum FlightMode mode)
{