Copter: change from control_mode to flightmode

This commit is contained in:
Tatsuya Yamaguchi 2020-01-30 16:29:36 +09:00 committed by Peter Barker
parent 1dccc0ceb3
commit 0cce5699b2
25 changed files with 63 additions and 68 deletions

View File

@ -652,8 +652,6 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
} }
#endif #endif
Mode::Number control_mode = copter.control_mode;
// always check if the current mode allows arming // always check if the current mode allows arming
if (!copter.flightmode->allows_arming(method == AP_Arming::Method::MAVLINK)) { if (!copter.flightmode->allows_arming(method == AP_Arming::Method::MAVLINK)) {
check_failed(true, "Mode not armable"); check_failed(true, "Mode not armable");
@ -719,7 +717,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
} }
// check throttle is not too high - skips checks if arming from GCS in Guided // check throttle is not too high - skips checks if arming from GCS in Guided
if (!(method == AP_Arming::Method::MAVLINK && (control_mode == Mode::Number::GUIDED || control_mode == Mode::Number::GUIDED_NOGPS))) { if (!(method == AP_Arming::Method::MAVLINK && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS))) {
// above top of deadband is too always high // above top of deadband is too always high
if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) { if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item); check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
@ -727,7 +725,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
} }
// in manual modes throttle must be at zero // in manual modes throttle must be at zero
#if FRAME_CONFIG != HELI_FRAME #if FRAME_CONFIG != HELI_FRAME
if ((copter.flightmode->has_manual_throttle() || control_mode == Mode::Number::DRIFT) && copter.channel_throttle->get_control_in() > 0) { if ((copter.flightmode->has_manual_throttle() || copter.flightmode->mode_number() == Mode::Number::DRIFT) && copter.channel_throttle->get_control_in() > 0) {
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item); check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
return false; return false;
} }
@ -854,7 +852,7 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_
copter.motors->armed(true); copter.motors->armed(true);
// log flight mode in case it was changed while vehicle was disarmed // log flight mode in case it was changed while vehicle was disarmed
AP::logger().Write_Mode((uint8_t)copter.control_mode, copter.control_mode_reason); AP::logger().Write_Mode((uint8_t)copter.flightmode->mode_number(), copter.control_mode_reason);
// re-enable failsafe // re-enable failsafe
copter.failsafe_enable(); copter.failsafe_enable();

View File

@ -44,7 +44,7 @@ void Copter::update_throttle_hover()
} }
// do not update in manual throttle modes or Drift // do not update in manual throttle modes or Drift
if (flightmode->has_manual_throttle() || (control_mode == Mode::Number::DRIFT)) { if (flightmode->has_manual_throttle() || (copter.flightmode->mode_number() == Mode::Number::DRIFT)) {
return; return;
} }

View File

@ -650,7 +650,6 @@ bool Copter::get_wp_crosstrack_error_m(float &xtrack_error) const
Copter::Copter(void) Copter::Copter(void)
: logger(g.log_bitmask), : logger(g.log_bitmask),
flight_modes(&g.flight_mode1), flight_modes(&g.flight_mode1),
control_mode(Mode::Number::STABILIZE),
simple_cos_yaw(1.0f), simple_cos_yaw(1.0f),
super_simple_cos_yaw(1.0), super_simple_cos_yaw(1.0),
land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF), land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF),

View File

@ -378,7 +378,7 @@ private:
// This is the state of the flight control system // This is the state of the flight control system
// There are multiple states defined such as STABILIZE, ACRO, // There are multiple states defined such as STABILIZE, ACRO,
Mode::Number control_mode; Mode *flightmode;
Mode::Number prev_control_mode; Mode::Number prev_control_mode;
RCMapper rcmap; RCMapper rcmap;
@ -806,7 +806,7 @@ private:
// mode.cpp // mode.cpp
bool set_mode(Mode::Number mode, ModeReason reason); bool set_mode(Mode::Number mode, ModeReason reason);
bool set_mode(const uint8_t new_mode, const ModeReason reason) override; bool set_mode(const uint8_t new_mode, const ModeReason reason) override;
uint8_t get_mode() const override { return (uint8_t)control_mode; } uint8_t get_mode() const override { return (uint8_t)flightmode->mode_number(); }
void update_flight_mode(); void update_flight_mode();
void notify_flight_mode(); void notify_flight_mode();
@ -909,7 +909,6 @@ private:
bool get_wp_bearing_deg(float &bearing) const override; bool get_wp_bearing_deg(float &bearing) const override;
bool get_wp_crosstrack_error_m(float &xtrack_error) const override; bool get_wp_crosstrack_error_m(float &xtrack_error) const override;
Mode *flightmode;
#if MODE_ACRO_ENABLED == ENABLED #if MODE_ACRO_ENABLED == ENABLED
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
ModeAcro_Heli mode_acro; ModeAcro_Heli mode_acro;

View File

@ -76,7 +76,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
control_sensors_present |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; control_sensors_present |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
control_sensors_present |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; control_sensors_present |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
switch (copter.control_mode) { switch (copter.flightmode->mode_number()) {
case Mode::Number::AUTO: case Mode::Number::AUTO:
case Mode::Number::AVOID_ADSB: case Mode::Number::AVOID_ADSB:
case Mode::Number::GUIDED: case Mode::Number::GUIDED:

View File

@ -31,7 +31,7 @@ MAV_MODE GCS_MAVLINK_Copter::base_mode() const
// only get useful information from the custom_mode, which maps to // only get useful information from the custom_mode, which maps to
// the APM flight mode and has a well defined meaning in the // the APM flight mode and has a well defined meaning in the
// ArduPlane documentation // ArduPlane documentation
switch (copter.control_mode) { switch (copter.flightmode->mode_number()) {
case Mode::Number::AUTO: case Mode::Number::AUTO:
case Mode::Number::RTL: case Mode::Number::RTL:
case Mode::Number::LOITER: case Mode::Number::LOITER:
@ -72,7 +72,7 @@ MAV_MODE GCS_MAVLINK_Copter::base_mode() const
uint32_t GCS_Copter::custom_mode() const uint32_t GCS_Copter::custom_mode() const
{ {
return (uint32_t)copter.control_mode; return (uint32_t)copter.flightmode->mode_number();
} }
MAV_STATE GCS_MAVLINK_Copter::vehicle_system_status() const MAV_STATE GCS_MAVLINK_Copter::vehicle_system_status() const
@ -928,7 +928,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
} else { } else {
// assume that shots modes are all done in guided. // assume that shots modes are all done in guided.
// NOTE: this may need to change if we add a non-guided shot mode // NOTE: this may need to change if we add a non-guided shot mode
bool shot_mode = (!is_zero(packet.param1) && (copter.control_mode == Mode::Number::GUIDED || copter.control_mode == Mode::Number::GUIDED_NOGPS)); bool shot_mode = (!is_zero(packet.param1) && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS));
if (!shot_mode) { if (!shot_mode) {
#if MODE_BRAKE_ENABLED == ENABLED #if MODE_BRAKE_ENABLED == ENABLED

View File

@ -618,7 +618,7 @@ void Copter::Log_Write_Vehicle_Startup_Messages()
{ {
// only 200(?) bytes are guaranteed by AP_Logger // only 200(?) bytes are guaranteed by AP_Logger
logger.Write_MessageF("Frame: %s/%s", motors->get_frame_string(), motors->get_type_string()); logger.Write_MessageF("Frame: %s/%s", motors->get_frame_string(), motors->get_type_string());
logger.Write_Mode((uint8_t)control_mode, control_mode_reason); logger.Write_Mode((uint8_t)flightmode->mode_number(), control_mode_reason);
ahrs.Log_Write_Home_And_Origin(); ahrs.Log_Write_Home_And_Origin();
gps.Write_AP_Logger_Log_Startup_messages(); gps.Write_AP_Logger_Log_Startup_messages();
} }

View File

@ -145,7 +145,7 @@ void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode,
default: default:
// return to flight mode switch's flight mode if we are currently // return to flight mode switch's flight mode if we are currently
// in this mode // in this mode
if (copter.control_mode == mode) { if (copter.flightmode->mode_number() == mode) {
rc().reset_mode_switch(); rc().reset_mode_switch();
} }
} }
@ -201,7 +201,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi
case AUX_FUNC::SAVE_TRIM: case AUX_FUNC::SAVE_TRIM:
if ((ch_flag == AuxSwitchPos::HIGH) && if ((ch_flag == AuxSwitchPos::HIGH) &&
(copter.control_mode <= Mode::Number::ACRO) && (copter.flightmode->mode_number() <= Mode::Number::ACRO) &&
(copter.channel_throttle->get_control_in() == 0)) { (copter.channel_throttle->get_control_in() == 0)) {
copter.save_trim(); copter.save_trim();
} }
@ -213,7 +213,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi
if (ch_flag == RC_Channel::AuxSwitchPos::HIGH) { if (ch_flag == RC_Channel::AuxSwitchPos::HIGH) {
// do not allow saving new waypoints while we're in auto or disarmed // do not allow saving new waypoints while we're in auto or disarmed
if (copter.control_mode == Mode::Number::AUTO || !copter.motors->armed()) { if (copter.flightmode->mode_number() == Mode::Number::AUTO || !copter.motors->armed()) {
return; return;
} }

View File

@ -61,7 +61,7 @@ void AP_AdvancedFailsafe_Copter::setup_IO_failsafe(void)
*/ */
AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Copter::afs_mode(void) AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Copter::afs_mode(void)
{ {
switch (copter.control_mode) { switch (copter.flightmode->mode_number()) {
case Mode::Number::AUTO: case Mode::Number::AUTO:
case Mode::Number::GUIDED: case Mode::Number::GUIDED:
case Mode::Number::RTL: case Mode::Number::RTL:

View File

@ -20,15 +20,15 @@ MAV_COLLISION_ACTION AP_Avoidance_Copter::handle_avoidance(const AP_Avoidance::O
copter.failsafe.adsb = true; copter.failsafe.adsb = true;
failsafe_state_change = true; failsafe_state_change = true;
// record flight mode in case it's required for the recovery // record flight mode in case it's required for the recovery
prev_control_mode = copter.control_mode; prev_control_mode = copter.flightmode->mode_number();
} }
// take no action in some flight modes // take no action in some flight modes
if (copter.control_mode == Mode::Number::LAND || if (copter.flightmode->mode_number() == Mode::Number::LAND ||
#if MODE_THROW_ENABLED == ENABLED #if MODE_THROW_ENABLED == ENABLED
copter.control_mode == Mode::Number::THROW || copter.flightmode->mode_number() == Mode::Number::THROW ||
#endif #endif
copter.control_mode == Mode::Number::FLIP) { copter.flightmode->mode_number() == Mode::Number::FLIP) {
actual_action = MAV_COLLISION_ACTION_NONE; actual_action = MAV_COLLISION_ACTION_NONE;
} }
@ -158,7 +158,7 @@ int16_t AP_Avoidance_Copter::get_altitude_minimum() const
bool AP_Avoidance_Copter::check_flightmode(bool allow_mode_change) bool AP_Avoidance_Copter::check_flightmode(bool allow_mode_change)
{ {
// ensure copter is in avoid_adsb mode // ensure copter is in avoid_adsb mode
if (allow_mode_change && copter.control_mode != Mode::Number::AVOID_ADSB) { if (allow_mode_change && copter.flightmode->mode_number() != Mode::Number::AVOID_ADSB) {
if (!copter.set_mode(Mode::Number::AVOID_ADSB, ModeReason::AVOIDANCE)) { if (!copter.set_mode(Mode::Number::AVOID_ADSB, ModeReason::AVOIDANCE)) {
// failed to set mode so exit immediately // failed to set mode so exit immediately
return false; return false;
@ -166,7 +166,7 @@ bool AP_Avoidance_Copter::check_flightmode(bool allow_mode_change)
} }
// check flight mode // check flight mode
return (copter.control_mode == Mode::Number::AVOID_ADSB); return (copter.flightmode->mode_number() == Mode::Number::AVOID_ADSB);
} }
bool AP_Avoidance_Copter::handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change) bool AP_Avoidance_Copter::handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change)

View File

@ -54,7 +54,7 @@ void Copter::update_ground_effect_detector(void)
bool small_angle_request = cosf(angle_target_rad.x)*cosf(angle_target_rad.y) > cosf(radians(7.5f)); bool small_angle_request = cosf(angle_target_rad.x)*cosf(angle_target_rad.y) > cosf(radians(7.5f));
bool xy_speed_low = (position_ok() || ekf_has_relative_position()) && xy_speed_cms <= 125.0f; bool xy_speed_low = (position_ok() || ekf_has_relative_position()) && xy_speed_cms <= 125.0f;
bool xy_speed_demand_low = pos_control->is_active_xy() && xy_des_speed_cms <= 125.0f; bool xy_speed_demand_low = pos_control->is_active_xy() && xy_des_speed_cms <= 125.0f;
bool slow_horizontal = xy_speed_demand_low || (xy_speed_low && !pos_control->is_active_xy()) || (control_mode == Mode::Number::ALT_HOLD && small_angle_request); bool slow_horizontal = xy_speed_demand_low || (xy_speed_low && !pos_control->is_active_xy()) || (flightmode->mode_number() == Mode::Number::ALT_HOLD && small_angle_request);
bool descent_demanded = pos_control->is_active_z() && des_climb_rate_cms < 0.0f; bool descent_demanded = pos_control->is_active_z() && des_climb_rate_cms < 0.0f;
bool slow_descent_demanded = descent_demanded && des_climb_rate_cms >= -100.0f; bool slow_descent_demanded = descent_demanded && des_climb_rate_cms >= -100.0f;

View File

@ -37,14 +37,14 @@ void Copter::crash_check()
} }
// return immediately if we are not in an angle stabilize flight mode or we are flipping // return immediately if we are not in an angle stabilize flight mode or we are flipping
if (control_mode == Mode::Number::ACRO || control_mode == Mode::Number::FLIP) { if (flightmode->mode_number() == Mode::Number::ACRO || flightmode->mode_number() == Mode::Number::FLIP) {
crash_counter = 0; crash_counter = 0;
return; return;
} }
#if MODE_AUTOROTATE_ENABLED == ENABLED #if MODE_AUTOROTATE_ENABLED == ENABLED
//return immediately if in autorotation mode //return immediately if in autorotation mode
if (control_mode == Mode::Number::AUTOROTATE) { if (flightmode->mode_number() == Mode::Number::AUTOROTATE) {
crash_counter = 0; crash_counter = 0;
return; return;
} }
@ -266,7 +266,7 @@ void Copter::parachute_check()
} }
// return immediately if we are not in an angle stabilize flight mode or we are flipping // return immediately if we are not in an angle stabilize flight mode or we are flipping
if (control_mode == Mode::Number::ACRO || control_mode == Mode::Number::FLIP) { if (flightmode->mode_number() == Mode::Number::ACRO || flightmode->mode_number() == Mode::Number::FLIP) {
control_loss_count = 0; control_loss_count = 0;
return; return;
} }

View File

@ -167,7 +167,7 @@ void Copter::failsafe_ekf_event()
} }
// sometimes LAND *does* require GPS so ensure we are in non-GPS land // sometimes LAND *does* require GPS so ensure we are in non-GPS land
if (control_mode == Mode::Number::LAND && landing_with_GPS()) { if (flightmode->mode_number() == Mode::Number::LAND && landing_with_GPS()) {
mode_land.do_not_use_GPS(); mode_land.do_not_use_GPS();
return; return;
} }

View File

@ -54,7 +54,7 @@ void Copter::failsafe_radio_on_event()
gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe - Continuing Landing"); gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe - Continuing Landing");
desired_action = Failsafe_Action_Land; desired_action = Failsafe_Action_Land;
} else if (control_mode == Mode::Number::AUTO && failsafe_option(FailsafeOption::RC_CONTINUE_IF_AUTO)) { } else if (flightmode->mode_number() == Mode::Number::AUTO && failsafe_option(FailsafeOption::RC_CONTINUE_IF_AUTO)) {
// Allow mission to continue when FS_OPTIONS is set to continue mission // Allow mission to continue when FS_OPTIONS is set to continue mission
gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe - Continuing Auto Mode"); gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe - Continuing Auto Mode");
desired_action = Failsafe_Action_None; desired_action = Failsafe_Action_None;
@ -190,7 +190,7 @@ void Copter::failsafe_gcs_on_event(void)
gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe - Continuing Landing"); gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe - Continuing Landing");
desired_action = Failsafe_Action_Land; desired_action = Failsafe_Action_Land;
} else if (control_mode == Mode::Number::AUTO && failsafe_option(FailsafeOption::GCS_CONTINUE_IF_AUTO)) { } else if (flightmode->mode_number() == Mode::Number::AUTO && failsafe_option(FailsafeOption::GCS_CONTINUE_IF_AUTO)) {
// Allow mission to continue when FS_OPTIONS is set to continue mission // Allow mission to continue when FS_OPTIONS is set to continue mission
gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe - Continuing Auto Mode"); gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe - Continuing Auto Mode");
desired_action = Failsafe_Action_None; desired_action = Failsafe_Action_None;
@ -262,7 +262,7 @@ void Copter::failsafe_terrain_on_event()
if (should_disarm_on_failsafe()) { if (should_disarm_on_failsafe()) {
arming.disarm(AP_Arming::Method::TERRAINFAILSAFE); arming.disarm(AP_Arming::Method::TERRAINFAILSAFE);
#if MODE_RTL_ENABLED == ENABLED #if MODE_RTL_ENABLED == ENABLED
} else if (control_mode == Mode::Number::RTL) { } else if (flightmode->mode_number() == Mode::Number::RTL) {
mode_rtl.restart_without_terrain(); mode_rtl.restart_without_terrain();
#endif #endif
} else { } else {
@ -336,7 +336,7 @@ bool Copter::should_disarm_on_failsafe() {
return true; return true;
} }
switch (control_mode) { switch (flightmode->mode_number()) {
case Mode::Number::STABILIZE: case Mode::Number::STABILIZE:
case Mode::Number::ACRO: case Mode::Number::ACRO:
// if throttle is zero OR vehicle is landed disarm motors // if throttle is zero OR vehicle is landed disarm motors

View File

@ -104,7 +104,7 @@ void Copter::update_heli_control_dynamics(void)
bool Copter::should_use_landing_swash() const bool Copter::should_use_landing_swash() const
{ {
if (flightmode->has_manual_throttle() || if (flightmode->has_manual_throttle() ||
control_mode == Mode::Number::DRIFT) { flightmode->mode_number() == Mode::Number::DRIFT) {
// manual modes always uses full swash range // manual modes always uses full swash range
return false; return false;
} }

View File

@ -185,7 +185,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
{ {
// return immediately if we are already in the desired mode // return immediately if we are already in the desired mode
if (mode == control_mode) { if (mode == flightmode->mode_number()) {
control_mode_reason = reason; control_mode_reason = reason;
return true; return true;
} }
@ -271,13 +271,12 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
exit_mode(flightmode, new_flightmode); exit_mode(flightmode, new_flightmode);
// store previous flight mode (only used by tradeheli's autorotation) // store previous flight mode (only used by tradeheli's autorotation)
prev_control_mode = control_mode; prev_control_mode = flightmode->mode_number();
// update flight mode // update flight mode
flightmode = new_flightmode; flightmode = new_flightmode;
control_mode = mode;
control_mode_reason = reason; control_mode_reason = reason;
logger.Write_Mode((uint8_t)control_mode, reason); logger.Write_Mode((uint8_t)flightmode->mode_number(), reason);
gcs().send_message(MSG_HEARTBEAT); gcs().send_message(MSG_HEARTBEAT);
#if HAL_ADSB_ENABLED #if HAL_ADSB_ENABLED
@ -292,7 +291,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
#endif #endif
#if CAMERA == ENABLED #if CAMERA == ENABLED
camera.set_is_auto_mode(control_mode == Mode::Number::AUTO); camera.set_is_auto_mode(flightmode->mode_number() == Mode::Number::AUTO);
#endif #endif
// update notify object // update notify object
@ -402,7 +401,7 @@ void Copter::exit_mode(Mode *&old_flightmode,
// notify_flight_mode - sets notify object based on current flight mode. Only used for OreoLED notify device // notify_flight_mode - sets notify object based on current flight mode. Only used for OreoLED notify device
void Copter::notify_flight_mode() { void Copter::notify_flight_mode() {
AP_Notify::flags.autopilot_mode = flightmode->is_autopilot(); AP_Notify::flags.autopilot_mode = flightmode->is_autopilot();
AP_Notify::flags.flight_mode = (uint8_t)control_mode; AP_Notify::flags.flight_mode = (uint8_t)flightmode->mode_number();
notify.set_flight_mode_str(flightmode->name4()); notify.set_flight_mode_str(flightmode->name4());
} }

View File

@ -555,7 +555,7 @@ void ModeAuto::exit_mission()
bool ModeAuto::do_guided(const AP_Mission::Mission_Command& cmd) bool ModeAuto::do_guided(const AP_Mission::Mission_Command& cmd)
{ {
// only process guided waypoint if we are in guided mode // only process guided waypoint if we are in guided mode
if (copter.control_mode != Mode::Number::GUIDED && !(copter.control_mode == Mode::Number::AUTO && mode() == Auto_NavGuided)) { if (copter.flightmode->mode_number() != Mode::Number::GUIDED && !(copter.flightmode->mode_number() == Mode::Number::AUTO && mode() == Auto_NavGuided)) {
return false; return false;
} }

View File

@ -9,7 +9,7 @@
bool AutoTune::init() bool AutoTune::init()
{ {
// use position hold while tuning if we were in QLOITER // use position hold while tuning if we were in QLOITER
bool position_hold = (copter.control_mode == Mode::Number::LOITER || copter.control_mode == Mode::Number::POSHOLD); bool position_hold = (copter.flightmode->mode_number() == Mode::Number::LOITER || copter.flightmode->mode_number() == Mode::Number::POSHOLD);
return init_internals(position_hold, return init_internals(position_hold,
copter.attitude_control, copter.attitude_control,
@ -24,10 +24,10 @@ bool AutoTune::init()
bool AutoTune::start() bool AutoTune::start()
{ {
// only allow flip from Stabilize, AltHold, PosHold or Loiter modes // only allow flip from Stabilize, AltHold, PosHold or Loiter modes
if (copter.control_mode != Mode::Number::STABILIZE && if (copter.flightmode != &copter.mode_stabilize &&
copter.control_mode != Mode::Number::ALT_HOLD && copter.flightmode != &copter.mode_althold &&
copter.control_mode != Mode::Number::LOITER && copter.flightmode != &copter.mode_loiter &&
copter.control_mode != Mode::Number::POSHOLD) { copter.flightmode != &copter.mode_poshold) {
return false; return false;
} }

View File

@ -19,7 +19,7 @@ bool ModeAvoidADSB::init(const bool ignore_checks)
bool ModeAvoidADSB::set_velocity(const Vector3f& velocity_neu) bool ModeAvoidADSB::set_velocity(const Vector3f& velocity_neu)
{ {
// check flight mode // check flight mode
if (copter.control_mode != Mode::Number::AVOID_ADSB) { if (copter.flightmode->mode_number() != Mode::Number::AVOID_ADSB) {
return false; return false;
} }

View File

@ -36,15 +36,15 @@
bool ModeFlip::init(bool ignore_checks) bool ModeFlip::init(bool ignore_checks)
{ {
// only allow flip from ACRO, Stabilize, AltHold or Drift flight modes // only allow flip from ACRO, Stabilize, AltHold or Drift flight modes
if (copter.control_mode != Mode::Number::ACRO && if (copter.flightmode != &copter.mode_acro &&
copter.control_mode != Mode::Number::STABILIZE && copter.flightmode != &copter.mode_stabilize &&
copter.control_mode != Mode::Number::ALT_HOLD && copter.flightmode != &copter.mode_althold &&
copter.control_mode != Mode::Number::FLOWHOLD) { copter.flightmode != &copter.mode_flowhold) {
return false; return false;
} }
// if in acro or stabilize ensure throttle is above zero // if in acro or stabilize ensure throttle is above zero
if (copter.ap.throttle_zero && (copter.control_mode == Mode::Number::ACRO || copter.control_mode == Mode::Number::STABILIZE)) { if (copter.ap.throttle_zero && (copter.flightmode->mode_number() == Mode::Number::ACRO || copter.flightmode->mode_number() == Mode::Number::STABILIZE)) {
return false; return false;
} }
@ -59,7 +59,7 @@ bool ModeFlip::init(bool ignore_checks)
} }
// capture original flight mode so that we can return to it after completion // capture original flight mode so that we can return to it after completion
orig_control_mode = copter.control_mode; orig_control_mode = copter.flightmode->mode_number();
// initialise state // initialise state
_state = FlipState::Start; _state = FlipState::Start;

View File

@ -167,5 +167,5 @@ void Copter::set_mode_land_with_pause(ModeReason reason)
// landing_with_GPS - returns true if vehicle is landing using GPS // landing_with_GPS - returns true if vehicle is landing using GPS
bool Copter::landing_with_GPS() bool Copter::landing_with_GPS()
{ {
return (control_mode == Mode::Number::LAND && land_with_gps); return (flightmode->mode_number() == Mode::Number::LAND && land_with_gps);
} }

View File

@ -163,7 +163,7 @@ void ModeSmartRTL::pre_land_position_run()
// save current position for use by the smart_rtl flight mode // save current position for use by the smart_rtl flight mode
void ModeSmartRTL::save_position() void ModeSmartRTL::save_position()
{ {
const bool should_save_position = motors->armed() && (copter.control_mode != Mode::Number::SMART_RTL); const bool should_save_position = motors->armed() && (copter.flightmode->mode_number() != Mode::Number::SMART_RTL);
copter.g2.smart_rtl.update(copter.position_ok(), should_save_position); copter.g2.smart_rtl.update(copter.position_ok(), should_save_position);
} }

View File

@ -51,7 +51,7 @@ void Copter::arm_motors_check()
} }
// arm the motors and configure for flight // arm the motors and configure for flight
if (arming_counter == AUTO_TRIM_DELAY && motors->armed() && control_mode == Mode::Number::STABILIZE) { if (arming_counter == AUTO_TRIM_DELAY && motors->armed() && flightmode->mode_number() == Mode::Number::STABILIZE) {
gcs().send_text(MAV_SEVERITY_INFO, "AutoTrim start"); gcs().send_text(MAV_SEVERITY_INFO, "AutoTrim start");
auto_trim_counter = 250; auto_trim_counter = 250;
auto_trim_started = false; auto_trim_started = false;
@ -90,7 +90,7 @@ void Copter::auto_disarm_check()
// exit immediately if we are already disarmed, or if auto // exit immediately if we are already disarmed, or if auto
// disarming is disabled // disarming is disabled
if (!motors->armed() || disarm_delay_ms == 0 || control_mode == Mode::Number::THROW) { if (!motors->armed() || disarm_delay_ms == 0 || flightmode->mode_number() == Mode::Number::THROW) {
auto_disarm_begin = tnow_ms; auto_disarm_begin = tnow_ms;
return; return;
} }
@ -148,7 +148,7 @@ void Copter::motors_output()
#endif #endif
// Update arming delay state // Update arming delay state
if (ap.in_arming_delay && (!motors->armed() || millis()-arm_time_ms > ARMING_DELAY_SEC*1.0e3f || control_mode == Mode::Number::THROW)) { if (ap.in_arming_delay && (!motors->armed() || millis()-arm_time_ms > ARMING_DELAY_SEC*1.0e3f || flightmode->mode_number() == Mode::Number::THROW)) {
ap.in_arming_delay = false; ap.in_arming_delay = false;
} }

View File

@ -430,7 +430,7 @@ void Copter::update_auto_armed()
// if motors are armed and throttle is above zero auto_armed should be true // if motors are armed and throttle is above zero auto_armed should be true
// if motors are armed and we are in throw mode, then auto_armed should be true // if motors are armed and we are in throw mode, then auto_armed should be true
} else if (motors->armed() && !ap.using_interlock) { } else if (motors->armed() && !ap.using_interlock) {
if(!ap.throttle_zero || control_mode == Mode::Number::THROW) { if(!ap.throttle_zero || flightmode->mode_number() == Mode::Number::THROW) {
set_auto_armed(true); set_auto_armed(true);
} }
} }

View File

@ -216,7 +216,7 @@ void ToyMode::update()
// set ALT_HOLD as indoors for the EKF (disables GPS vertical velocity fusion) // set ALT_HOLD as indoors for the EKF (disables GPS vertical velocity fusion)
#if 0 #if 0
copter.ahrs.set_indoor_mode(copter.control_mode == ALT_HOLD || copter.control_mode == FLOWHOLD); copter.ahrs.set_indoor_mode(copter.flightmode->mode_number() == ALT_HOLD || copter.flightmode->mode_number() == FLOWHOLD);
#endif #endif
bool left_button = false; bool left_button = false;
@ -424,7 +424,7 @@ void ToyMode::update()
if (throttle_high_counter >= TOY_LAND_ARM_COUNT) { if (throttle_high_counter >= TOY_LAND_ARM_COUNT) {
gcs().send_text(MAV_SEVERITY_INFO, "Tmode: throttle arm"); gcs().send_text(MAV_SEVERITY_INFO, "Tmode: throttle arm");
arm_check_compass(); arm_check_compass();
if (!copter.arming.arm(AP_Arming::Method::MAVLINK) && (flags & FLAG_UPGRADE_LOITER) && copter.control_mode == Mode::Number::LOITER) { if (!copter.arming.arm(AP_Arming::Method::MAVLINK) && (flags & FLAG_UPGRADE_LOITER) && copter.flightmode->mode_number() == Mode::Number::LOITER) {
/* /*
support auto-switching to ALT_HOLD, then upgrade to LOITER once GPS available support auto-switching to ALT_HOLD, then upgrade to LOITER once GPS available
*/ */
@ -453,7 +453,7 @@ void ToyMode::update()
} }
if (upgrade_to_loiter) { if (upgrade_to_loiter) {
if (!copter.motors->armed() || copter.control_mode != Mode::Number::ALT_HOLD) { if (!copter.motors->armed() || copter.flightmode->mode_number() != Mode::Number::ALT_HOLD) {
upgrade_to_loiter = false; upgrade_to_loiter = false;
#if 0 #if 0
AP_Notify::flags.hybrid_loiter = false; AP_Notify::flags.hybrid_loiter = false;
@ -466,12 +466,12 @@ void ToyMode::update()
} }
} }
if (copter.control_mode == Mode::Number::RTL && (flags & FLAG_RTL_CANCEL) && throttle_near_max) { if (copter.flightmode->mode_number() == Mode::Number::RTL && (flags & FLAG_RTL_CANCEL) && throttle_near_max) {
gcs().send_text(MAV_SEVERITY_INFO, "Tmode: RTL cancel"); gcs().send_text(MAV_SEVERITY_INFO, "Tmode: RTL cancel");
set_and_remember_mode(Mode::Number::LOITER, ModeReason::TOY_MODE); set_and_remember_mode(Mode::Number::LOITER, ModeReason::TOY_MODE);
} }
enum Mode::Number old_mode = copter.control_mode; enum Mode::Number old_mode = copter.flightmode->mode_number();
enum Mode::Number new_mode = old_mode; enum Mode::Number new_mode = old_mode;
/* /*
@ -636,12 +636,12 @@ void ToyMode::update()
break; break;
} }
if (!copter.motors->armed() && (copter.control_mode == Mode::Number::LAND || copter.control_mode == Mode::Number::RTL)) { if (!copter.motors->armed() && (copter.flightmode->mode_number() == Mode::Number::LAND || copter.flightmode->mode_number() == Mode::Number::RTL)) {
// revert back to last primary flight mode if disarmed after landing // revert back to last primary flight mode if disarmed after landing
new_mode = Mode::Number(primary_mode[last_mode_choice].get()); new_mode = Mode::Number(primary_mode[last_mode_choice].get());
} }
if (new_mode != copter.control_mode) { if (new_mode != copter.flightmode->mode_number()) {
load_test.running = false; load_test.running = false;
#if AC_FENCE == ENABLED #if AC_FENCE == ENABLED
copter.fence.enable(false); copter.fence.enable(false);
@ -676,7 +676,7 @@ void ToyMode::update()
*/ */
bool ToyMode::set_and_remember_mode(Mode::Number mode, ModeReason reason) bool ToyMode::set_and_remember_mode(Mode::Number mode, ModeReason reason)
{ {
if (copter.control_mode == mode) { if (copter.flightmode->mode_number() == mode) {
return true; return true;
} }
if (!copter.set_mode(mode, reason)) { if (!copter.set_mode(mode, reason)) {