mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: move control_mode_t into being Mode::Number enum class
Fixes this compiler error: In file included from ../../ArduCopter/sensors.cpp:1: In file included from ../../ArduCopter/Copter.h:195: ../../ArduCopter/mode.h:1291:9: fatal error: declaration shadows a variable in the global namespace [-Wshadow] AUTO, // after A and B defined, pilot toggle the switch from one side to the other, vehicle flies autonomously ^ ../../ArduCopter/defines.h:38:5: note: previous declaration is here AUTO = 3, // fully automatic waypoint control using mission commands ^ 1 error generated.
This commit is contained in:
parent
6193d6cf69
commit
b4537bebd8
@ -509,7 +509,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
control_mode_t control_mode = copter.control_mode;
|
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)) {
|
||||||
@ -576,7 +576,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 == GUIDED || control_mode == GUIDED_NOGPS))) {
|
if (!(method == AP_Arming::Method::MAVLINK && (control_mode == Mode::Number::GUIDED || control_mode == 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);
|
||||||
@ -584,7 +584,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 == DRIFT) && copter.channel_throttle->get_control_in() > 0) {
|
if ((copter.flightmode->has_manual_throttle() || control_mode == 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;
|
||||||
}
|
}
|
||||||
@ -698,7 +698,7 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_
|
|||||||
AP::logger().Write_Event(DATA_ARMED);
|
AP::logger().Write_Event(DATA_ARMED);
|
||||||
|
|
||||||
// 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(copter.control_mode, copter.control_mode_reason);
|
AP::logger().Write_Mode((uint8_t)copter.control_mode, copter.control_mode_reason);
|
||||||
|
|
||||||
// re-enable failsafe
|
// re-enable failsafe
|
||||||
copter.failsafe_enable();
|
copter.failsafe_enable();
|
||||||
|
@ -43,7 +43,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 == DRIFT)) {
|
if (flightmode->has_manual_throttle() || (control_mode == Mode::Number::DRIFT)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -587,7 +587,7 @@ void Copter::publish_osd_info()
|
|||||||
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(STABILIZE),
|
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),
|
||||||
|
@ -83,6 +83,18 @@
|
|||||||
#include "defines.h"
|
#include "defines.h"
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
|
|
||||||
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
#define AC_AttitudeControl_t AC_AttitudeControl_Heli
|
||||||
|
#else
|
||||||
|
#define AC_AttitudeControl_t AC_AttitudeControl_Multi
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
#define MOTOR_CLASS AP_MotorsHeli
|
||||||
|
#else
|
||||||
|
#define MOTOR_CLASS AP_MotorsMulticopter
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "RC_Channel.h" // RC Channel Library
|
#include "RC_Channel.h" // RC Channel Library
|
||||||
|
|
||||||
#include "GCS_Mavlink.h"
|
#include "GCS_Mavlink.h"
|
||||||
@ -180,18 +192,6 @@
|
|||||||
#include <SITL/SITL.h>
|
#include <SITL/SITL.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
|
||||||
#define AC_AttitudeControl_t AC_AttitudeControl_Heli
|
|
||||||
#else
|
|
||||||
#define AC_AttitudeControl_t AC_AttitudeControl_Multi
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
|
||||||
#define MOTOR_CLASS AP_MotorsHeli
|
|
||||||
#else
|
|
||||||
#define MOTOR_CLASS AP_MotorsMulticopter
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include "mode.h"
|
#include "mode.h"
|
||||||
|
|
||||||
class Copter : public AP_HAL::HAL::Callbacks {
|
class Copter : public AP_HAL::HAL::Callbacks {
|
||||||
@ -387,10 +387,10 @@ 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,
|
||||||
control_mode_t control_mode;
|
Mode::Number control_mode;
|
||||||
mode_reason_t control_mode_reason = MODE_REASON_UNKNOWN;
|
mode_reason_t control_mode_reason = MODE_REASON_UNKNOWN;
|
||||||
|
|
||||||
control_mode_t prev_control_mode;
|
Mode::Number prev_control_mode;
|
||||||
mode_reason_t prev_control_mode_reason = MODE_REASON_UNKNOWN;
|
mode_reason_t prev_control_mode_reason = MODE_REASON_UNKNOWN;
|
||||||
|
|
||||||
RCMapper rcmap;
|
RCMapper rcmap;
|
||||||
@ -777,7 +777,7 @@ private:
|
|||||||
void log_init(void);
|
void log_init(void);
|
||||||
|
|
||||||
// mode.cpp
|
// mode.cpp
|
||||||
bool set_mode(control_mode_t mode, mode_reason_t reason);
|
bool set_mode(Mode::Number mode, mode_reason_t reason);
|
||||||
void update_flight_mode();
|
void update_flight_mode();
|
||||||
void notify_flight_mode();
|
void notify_flight_mode();
|
||||||
|
|
||||||
@ -959,7 +959,7 @@ private:
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
// mode.cpp
|
// mode.cpp
|
||||||
Mode *mode_from_mode_num(const uint8_t mode);
|
Mode *mode_from_mode_num(const Mode::Number mode);
|
||||||
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);
|
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
@ -81,25 +81,25 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
|
|||||||
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.control_mode) {
|
||||||
case AUTO:
|
case Mode::Number::AUTO:
|
||||||
case AVOID_ADSB:
|
case Mode::Number::AVOID_ADSB:
|
||||||
case GUIDED:
|
case Mode::Number::GUIDED:
|
||||||
case LOITER:
|
case Mode::Number::LOITER:
|
||||||
case RTL:
|
case Mode::Number::RTL:
|
||||||
case CIRCLE:
|
case Mode::Number::CIRCLE:
|
||||||
case LAND:
|
case Mode::Number::LAND:
|
||||||
case POSHOLD:
|
case Mode::Number::POSHOLD:
|
||||||
case BRAKE:
|
case Mode::Number::BRAKE:
|
||||||
case THROW:
|
case Mode::Number::THROW:
|
||||||
case SMART_RTL:
|
case Mode::Number::SMART_RTL:
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
|
||||||
break;
|
break;
|
||||||
case ALT_HOLD:
|
case Mode::Number::ALT_HOLD:
|
||||||
case GUIDED_NOGPS:
|
case Mode::Number::GUIDED_NOGPS:
|
||||||
case SPORT:
|
case Mode::Number::SPORT:
|
||||||
case AUTOTUNE:
|
case Mode::Number::AUTOTUNE:
|
||||||
case FLOWHOLD:
|
case Mode::Number::FLOWHOLD:
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
@ -29,16 +29,16 @@ MAV_MODE GCS_MAVLINK_Copter::base_mode() const
|
|||||||
// 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.control_mode) {
|
||||||
case AUTO:
|
case Mode::Number::AUTO:
|
||||||
case RTL:
|
case Mode::Number::RTL:
|
||||||
case LOITER:
|
case Mode::Number::LOITER:
|
||||||
case AVOID_ADSB:
|
case Mode::Number::AVOID_ADSB:
|
||||||
case FOLLOW:
|
case Mode::Number::FOLLOW:
|
||||||
case GUIDED:
|
case Mode::Number::GUIDED:
|
||||||
case CIRCLE:
|
case Mode::Number::CIRCLE:
|
||||||
case POSHOLD:
|
case Mode::Number::POSHOLD:
|
||||||
case BRAKE:
|
case Mode::Number::BRAKE:
|
||||||
case SMART_RTL:
|
case Mode::Number::SMART_RTL:
|
||||||
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
|
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
|
||||||
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
|
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
|
||||||
// APM does in any mode, as that is defined as "system finds its own goal
|
// APM does in any mode, as that is defined as "system finds its own goal
|
||||||
@ -69,7 +69,7 @@ MAV_MODE GCS_MAVLINK_Copter::base_mode() const
|
|||||||
|
|
||||||
uint32_t GCS_Copter::custom_mode() const
|
uint32_t GCS_Copter::custom_mode() const
|
||||||
{
|
{
|
||||||
return copter.control_mode;
|
return (uint32_t)copter.control_mode;
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_STATE GCS_MAVLINK_Copter::system_status() const
|
MAV_STATE GCS_MAVLINK_Copter::system_status() const
|
||||||
@ -628,19 +628,19 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
|||||||
}
|
}
|
||||||
|
|
||||||
case MAV_CMD_NAV_LOITER_UNLIM:
|
case MAV_CMD_NAV_LOITER_UNLIM:
|
||||||
if (!copter.set_mode(LOITER, MODE_REASON_GCS_COMMAND)) {
|
if (!copter.set_mode(Mode::Number::LOITER, MODE_REASON_GCS_COMMAND)) {
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
|
||||||
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
||||||
if (!copter.set_mode(RTL, MODE_REASON_GCS_COMMAND)) {
|
if (!copter.set_mode(Mode::Number::RTL, MODE_REASON_GCS_COMMAND)) {
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
|
||||||
case MAV_CMD_NAV_LAND:
|
case MAV_CMD_NAV_LAND:
|
||||||
if (!copter.set_mode(LAND, MODE_REASON_GCS_COMMAND)) {
|
if (!copter.set_mode(Mode::Number::LAND, MODE_REASON_GCS_COMMAND)) {
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
@ -691,7 +691,8 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
|||||||
|
|
||||||
#if MODE_AUTO_ENABLED == ENABLED
|
#if MODE_AUTO_ENABLED == ENABLED
|
||||||
case MAV_CMD_MISSION_START:
|
case MAV_CMD_MISSION_START:
|
||||||
if (copter.motors->armed() && copter.set_mode(AUTO, MODE_REASON_GCS_COMMAND)) {
|
if (copter.motors->armed() &&
|
||||||
|
copter.set_mode(Mode::Number::AUTO, MODE_REASON_GCS_COMMAND)) {
|
||||||
copter.set_auto_armed(true);
|
copter.set_auto_armed(true);
|
||||||
if (copter.mode_auto.mission.state() != AP_Mission::MISSION_RUNNING) {
|
if (copter.mode_auto.mission.state() != AP_Mission::MISSION_RUNNING) {
|
||||||
copter.mode_auto.mission.start_or_resume();
|
copter.mode_auto.mission.start_or_resume();
|
||||||
@ -787,8 +788,8 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
|||||||
}
|
}
|
||||||
|
|
||||||
// set mode to Loiter or fall back to AltHold
|
// set mode to Loiter or fall back to AltHold
|
||||||
if (!copter.set_mode(LOITER, MODE_REASON_GCS_COMMAND)) {
|
if (!copter.set_mode(Mode::Number::LOITER, MODE_REASON_GCS_COMMAND)) {
|
||||||
copter.set_mode(ALT_HOLD, MODE_REASON_GCS_COMMAND);
|
copter.set_mode(Mode::Number::ALT_HOLD, MODE_REASON_GCS_COMMAND);
|
||||||
}
|
}
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
@ -804,12 +805,12 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
|||||||
copter.arming.arm(AP_Arming::Method::MAVLINK);
|
copter.arming.arm(AP_Arming::Method::MAVLINK);
|
||||||
} else if (copter.ap.land_complete) {
|
} else if (copter.ap.land_complete) {
|
||||||
// if armed and landed, takeoff
|
// if armed and landed, takeoff
|
||||||
if (copter.set_mode(LOITER, MODE_REASON_GCS_COMMAND)) {
|
if (copter.set_mode(Mode::Number::LOITER, MODE_REASON_GCS_COMMAND)) {
|
||||||
copter.flightmode->do_user_takeoff(packet.param1*100, true);
|
copter.flightmode->do_user_takeoff(packet.param1*100, true);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// if flying, land
|
// if flying, land
|
||||||
copter.set_mode(LAND, MODE_REASON_GCS_COMMAND);
|
copter.set_mode(Mode::Number::LAND, MODE_REASON_GCS_COMMAND);
|
||||||
}
|
}
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
@ -827,17 +828,17 @@ 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 == GUIDED || copter.control_mode == GUIDED_NOGPS));
|
bool shot_mode = (!is_zero(packet.param1) && (copter.control_mode == Mode::Number::GUIDED || copter.control_mode == Mode::Number::GUIDED_NOGPS));
|
||||||
|
|
||||||
if (!shot_mode) {
|
if (!shot_mode) {
|
||||||
#if MODE_BRAKE_ENABLED == ENABLED
|
#if MODE_BRAKE_ENABLED == ENABLED
|
||||||
if (copter.set_mode(BRAKE, MODE_REASON_GCS_COMMAND)) {
|
if (copter.set_mode(Mode::Number::BRAKE, MODE_REASON_GCS_COMMAND)) {
|
||||||
copter.mode_brake.timeout_to_loiter_ms(2500);
|
copter.mode_brake.timeout_to_loiter_ms(2500);
|
||||||
} else {
|
} else {
|
||||||
copter.set_mode(ALT_HOLD, MODE_REASON_GCS_COMMAND);
|
copter.set_mode(Mode::Number::ALT_HOLD, MODE_REASON_GCS_COMMAND);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
copter.set_mode(ALT_HOLD, MODE_REASON_GCS_COMMAND);
|
copter.set_mode(Mode::Number::ALT_HOLD, MODE_REASON_GCS_COMMAND);
|
||||||
#endif
|
#endif
|
||||||
} else {
|
} else {
|
||||||
// SoloLink is expected to handle pause in shots
|
// SoloLink is expected to handle pause in shots
|
||||||
@ -1312,7 +1313,7 @@ bool GCS_MAVLINK_Copter::set_mode(const uint8_t mode)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
return copter.set_mode((control_mode_t)mode, MODE_REASON_GCS_COMMAND);
|
return copter.set_mode((Mode::Number)mode, MODE_REASON_GCS_COMMAND);
|
||||||
}
|
}
|
||||||
|
|
||||||
float GCS_MAVLINK_Copter::vfr_hud_alt() const
|
float GCS_MAVLINK_Copter::vfr_hud_alt() const
|
||||||
|
@ -415,7 +415,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", get_frame_string());
|
logger.Write_MessageF("Frame: %s", get_frame_string());
|
||||||
logger.Write_Mode(control_mode, control_mode_reason);
|
logger.Write_Mode((uint8_t)control_mode, 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();
|
||||||
}
|
}
|
||||||
|
@ -264,42 +264,42 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
// @Description: Flight mode when Channel 5 pwm is <= 1230
|
// @Description: Flight mode when Channel 5 pwm is <= 1230
|
||||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
|
GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1),
|
||||||
|
|
||||||
// @Param: FLTMODE2
|
// @Param: FLTMODE2
|
||||||
// @DisplayName: Flight Mode 2
|
// @DisplayName: Flight Mode 2
|
||||||
// @Description: Flight mode when Channel 5 pwm is >1230, <= 1360
|
// @Description: Flight mode when Channel 5 pwm is >1230, <= 1360
|
||||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
|
GSCALAR(flight_mode2, "FLTMODE2", (uint8_t)FLIGHT_MODE_2),
|
||||||
|
|
||||||
// @Param: FLTMODE3
|
// @Param: FLTMODE3
|
||||||
// @DisplayName: Flight Mode 3
|
// @DisplayName: Flight Mode 3
|
||||||
// @Description: Flight mode when Channel 5 pwm is >1360, <= 1490
|
// @Description: Flight mode when Channel 5 pwm is >1360, <= 1490
|
||||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
|
GSCALAR(flight_mode3, "FLTMODE3", (uint8_t)FLIGHT_MODE_3),
|
||||||
|
|
||||||
// @Param: FLTMODE4
|
// @Param: FLTMODE4
|
||||||
// @DisplayName: Flight Mode 4
|
// @DisplayName: Flight Mode 4
|
||||||
// @Description: Flight mode when Channel 5 pwm is >1490, <= 1620
|
// @Description: Flight mode when Channel 5 pwm is >1490, <= 1620
|
||||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
|
GSCALAR(flight_mode4, "FLTMODE4", (uint8_t)FLIGHT_MODE_4),
|
||||||
|
|
||||||
// @Param: FLTMODE5
|
// @Param: FLTMODE5
|
||||||
// @DisplayName: Flight Mode 5
|
// @DisplayName: Flight Mode 5
|
||||||
// @Description: Flight mode when Channel 5 pwm is >1620, <= 1749
|
// @Description: Flight mode when Channel 5 pwm is >1620, <= 1749
|
||||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
|
GSCALAR(flight_mode5, "FLTMODE5", (uint8_t)FLIGHT_MODE_5),
|
||||||
|
|
||||||
// @Param: FLTMODE6
|
// @Param: FLTMODE6
|
||||||
// @DisplayName: Flight Mode 6
|
// @DisplayName: Flight Mode 6
|
||||||
// @Description: Flight mode when Channel 5 pwm is >=1750
|
// @Description: Flight mode when Channel 5 pwm is >=1750
|
||||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
|
GSCALAR(flight_mode6, "FLTMODE6", (uint8_t)FLIGHT_MODE_6),
|
||||||
|
|
||||||
// @Param: FLTMODE_CH
|
// @Param: FLTMODE_CH
|
||||||
// @DisplayName: Flightmode channel
|
// @DisplayName: Flightmode channel
|
||||||
|
@ -1,6 +1,7 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
|
#include "RC_Channel.h"
|
||||||
|
|
||||||
#if GRIPPER_ENABLED == ENABLED
|
#if GRIPPER_ENABLED == ENABLED
|
||||||
# include <AP_Gripper/AP_Gripper.h>
|
# include <AP_Gripper/AP_Gripper.h>
|
||||||
|
@ -20,7 +20,7 @@ void RC_Channel_Copter::mode_switch_changed(modeswitch_pos_t new_pos)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!copter.set_mode((control_mode_t)copter.flight_modes[new_pos].get(), MODE_REASON_TX_COMMAND)) {
|
if (!copter.set_mode((Mode::Number)copter.flight_modes[new_pos].get(), MODE_REASON_TX_COMMAND)) {
|
||||||
// alert user to mode change failure
|
// alert user to mode change failure
|
||||||
if (copter.ap.initialised) {
|
if (copter.ap.initialised) {
|
||||||
AP_Notify::events.user_mode_change_failed = 1;
|
AP_Notify::events.user_mode_change_failed = 1;
|
||||||
@ -117,7 +117,7 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const aux_
|
|||||||
|
|
||||||
// do_aux_function_change_mode - change mode based on an aux switch
|
// do_aux_function_change_mode - change mode based on an aux switch
|
||||||
// being moved
|
// being moved
|
||||||
void RC_Channel_Copter::do_aux_function_change_mode(const control_mode_t mode,
|
void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode,
|
||||||
const aux_switch_pos_t ch_flag)
|
const aux_switch_pos_t ch_flag)
|
||||||
{
|
{
|
||||||
switch(ch_flag) {
|
switch(ch_flag) {
|
||||||
@ -149,7 +149,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
|||||||
case AUX_FUNC::FLIP:
|
case AUX_FUNC::FLIP:
|
||||||
// flip if switch is on, positive throttle and we're actually flying
|
// flip if switch is on, positive throttle and we're actually flying
|
||||||
if (ch_flag == aux_switch_pos_t::HIGH) {
|
if (ch_flag == aux_switch_pos_t::HIGH) {
|
||||||
copter.set_mode(control_mode_t::FLIP, MODE_REASON_TX_COMMAND);
|
copter.set_mode(Mode::Number::FLIP, MODE_REASON_TX_COMMAND);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -165,12 +165,12 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
|||||||
|
|
||||||
case AUX_FUNC::RTL:
|
case AUX_FUNC::RTL:
|
||||||
#if MODE_RTL_ENABLED == ENABLED
|
#if MODE_RTL_ENABLED == ENABLED
|
||||||
do_aux_function_change_mode(control_mode_t::RTL, ch_flag);
|
do_aux_function_change_mode(Mode::Number::RTL, ch_flag);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::SAVE_TRIM:
|
case AUX_FUNC::SAVE_TRIM:
|
||||||
if ((ch_flag == HIGH) && (copter.control_mode <= control_mode_t::ACRO) && (copter.channel_throttle->get_control_in() == 0)) {
|
if ((ch_flag == HIGH) && (copter.control_mode <= Mode::Number::ACRO) && (copter.channel_throttle->get_control_in() == 0)) {
|
||||||
copter.save_trim();
|
copter.save_trim();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
@ -181,7 +181,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
|||||||
if (ch_flag == HIGH) {
|
if (ch_flag == 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 == control_mode_t::AUTO || !copter.motors->armed()) {
|
if (copter.control_mode == Mode::Number::AUTO || !copter.motors->armed()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -229,7 +229,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
|||||||
|
|
||||||
case AUX_FUNC::AUTO:
|
case AUX_FUNC::AUTO:
|
||||||
#if MODE_AUTO_ENABLED == ENABLED
|
#if MODE_AUTO_ENABLED == ENABLED
|
||||||
do_aux_function_change_mode(control_mode_t::AUTO, ch_flag);
|
do_aux_function_change_mode(Mode::Number::AUTO, ch_flag);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -265,24 +265,24 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
|||||||
|
|
||||||
case AUX_FUNC::AUTOTUNE:
|
case AUX_FUNC::AUTOTUNE:
|
||||||
#if AUTOTUNE_ENABLED == ENABLED
|
#if AUTOTUNE_ENABLED == ENABLED
|
||||||
do_aux_function_change_mode(control_mode_t::AUTOTUNE, ch_flag);
|
do_aux_function_change_mode(Mode::Number::AUTOTUNE, ch_flag);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::LAND:
|
case AUX_FUNC::LAND:
|
||||||
do_aux_function_change_mode(control_mode_t::LAND, ch_flag);
|
do_aux_function_change_mode(Mode::Number::LAND, ch_flag);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::GUIDED:
|
case AUX_FUNC::GUIDED:
|
||||||
do_aux_function_change_mode(control_mode_t::GUIDED, ch_flag);
|
do_aux_function_change_mode(Mode::Number::GUIDED, ch_flag);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::LOITER:
|
case AUX_FUNC::LOITER:
|
||||||
do_aux_function_change_mode(control_mode_t::LOITER, ch_flag);
|
do_aux_function_change_mode(Mode::Number::LOITER, ch_flag);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::FOLLOW:
|
case AUX_FUNC::FOLLOW:
|
||||||
do_aux_function_change_mode(control_mode_t::FOLLOW, ch_flag);
|
do_aux_function_change_mode(Mode::Number::FOLLOW, ch_flag);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::PARACHUTE_ENABLE:
|
case AUX_FUNC::PARACHUTE_ENABLE:
|
||||||
@ -354,13 +354,13 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
|||||||
|
|
||||||
case AUX_FUNC::BRAKE:
|
case AUX_FUNC::BRAKE:
|
||||||
#if MODE_BRAKE_ENABLED == ENABLED
|
#if MODE_BRAKE_ENABLED == ENABLED
|
||||||
do_aux_function_change_mode(control_mode_t::BRAKE, ch_flag);
|
do_aux_function_change_mode(Mode::Number::BRAKE, ch_flag);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::THROW:
|
case AUX_FUNC::THROW:
|
||||||
#if MODE_THROW_ENABLED == ENABLED
|
#if MODE_THROW_ENABLED == ENABLED
|
||||||
do_aux_function_change_mode(control_mode_t::THROW, ch_flag);
|
do_aux_function_change_mode(Mode::Number::THROW, ch_flag);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -412,7 +412,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
|||||||
|
|
||||||
case AUX_FUNC::SMART_RTL:
|
case AUX_FUNC::SMART_RTL:
|
||||||
#if MODE_SMARTRTL_ENABLED == ENABLED
|
#if MODE_SMARTRTL_ENABLED == ENABLED
|
||||||
do_aux_function_change_mode(control_mode_t::SMART_RTL, ch_flag);
|
do_aux_function_change_mode(Mode::Number::SMART_RTL, ch_flag);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -487,7 +487,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
|||||||
|
|
||||||
case AUX_FUNC::ZIGZAG:
|
case AUX_FUNC::ZIGZAG:
|
||||||
#if MODE_ZIGZAG_ENABLED == ENABLED
|
#if MODE_ZIGZAG_ENABLED == ENABLED
|
||||||
do_aux_function_change_mode(control_mode_t::ZIGZAG, ch_flag);
|
do_aux_function_change_mode(Mode::Number::ZIGZAG, ch_flag);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -510,34 +510,34 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::STABILIZE:
|
case AUX_FUNC::STABILIZE:
|
||||||
do_aux_function_change_mode(control_mode_t::STABILIZE, ch_flag);
|
do_aux_function_change_mode(Mode::Number::STABILIZE, ch_flag);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::POSHOLD:
|
case AUX_FUNC::POSHOLD:
|
||||||
#if MODE_POSHOLD_ENABLED == ENABLED
|
#if MODE_POSHOLD_ENABLED == ENABLED
|
||||||
do_aux_function_change_mode(control_mode_t::POSHOLD, ch_flag);
|
do_aux_function_change_mode(Mode::Number::POSHOLD, ch_flag);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::ALTHOLD:
|
case AUX_FUNC::ALTHOLD:
|
||||||
do_aux_function_change_mode(control_mode_t::ALT_HOLD, ch_flag);
|
do_aux_function_change_mode(Mode::Number::ALT_HOLD, ch_flag);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::FLOWHOLD:
|
case AUX_FUNC::FLOWHOLD:
|
||||||
#if OPTFLOW == ENABLED
|
#if OPTFLOW == ENABLED
|
||||||
do_aux_function_change_mode(control_mode_t::FLOWHOLD, ch_flag);
|
do_aux_function_change_mode(Mode::Number::FLOWHOLD, ch_flag);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::CIRCLE:
|
case AUX_FUNC::CIRCLE:
|
||||||
#if MODE_CIRCLE_ENABLED == ENABLED
|
#if MODE_CIRCLE_ENABLED == ENABLED
|
||||||
do_aux_function_change_mode(control_mode_t::CIRCLE, ch_flag);
|
do_aux_function_change_mode(Mode::Number::CIRCLE, ch_flag);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::DRIFT:
|
case AUX_FUNC::DRIFT:
|
||||||
#if MODE_DRIFT_ENABLED == ENABLED
|
#if MODE_DRIFT_ENABLED == ENABLED
|
||||||
do_aux_function_change_mode(control_mode_t::DRIFT, ch_flag);
|
do_aux_function_change_mode(Mode::Number::DRIFT, ch_flag);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -1,7 +1,7 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <RC_Channel/RC_Channel.h>
|
#include <RC_Channel/RC_Channel.h>
|
||||||
#include "Copter.h"
|
#include "mode.h"
|
||||||
|
|
||||||
class RC_Channel_Copter : public RC_Channel
|
class RC_Channel_Copter : public RC_Channel
|
||||||
{
|
{
|
||||||
@ -15,7 +15,7 @@ protected:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
void do_aux_function_change_mode(const control_mode_t mode,
|
void do_aux_function_change_mode(const Mode::Number mode,
|
||||||
const aux_switch_pos_t ch_flag);
|
const aux_switch_pos_t ch_flag);
|
||||||
|
|
||||||
// called when the mode switch changes position:
|
// called when the mode switch changes position:
|
||||||
|
@ -24,11 +24,11 @@ MAV_COLLISION_ACTION AP_Avoidance_Copter::handle_avoidance(const AP_Avoidance::O
|
|||||||
}
|
}
|
||||||
|
|
||||||
// take no action in some flight modes
|
// take no action in some flight modes
|
||||||
if (copter.control_mode == LAND ||
|
if (copter.control_mode == Mode::Number::LAND ||
|
||||||
#if MODE_THROW_ENABLED == ENABLED
|
#if MODE_THROW_ENABLED == ENABLED
|
||||||
copter.control_mode == THROW ||
|
copter.control_mode == Mode::Number::THROW ||
|
||||||
#endif
|
#endif
|
||||||
copter.control_mode == FLIP) {
|
copter.control_mode == Mode::Number::FLIP) {
|
||||||
actual_action = MAV_COLLISION_ACTION_NONE;
|
actual_action = MAV_COLLISION_ACTION_NONE;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -44,7 +44,7 @@ MAV_COLLISION_ACTION AP_Avoidance_Copter::handle_avoidance(const AP_Avoidance::O
|
|||||||
case MAV_COLLISION_ACTION_RTL:
|
case MAV_COLLISION_ACTION_RTL:
|
||||||
// attempt to switch to RTL, if this fails (i.e. flying in manual mode with bad position) do nothing
|
// attempt to switch to RTL, if this fails (i.e. flying in manual mode with bad position) do nothing
|
||||||
if (failsafe_state_change) {
|
if (failsafe_state_change) {
|
||||||
if (!copter.set_mode(RTL, MODE_REASON_AVOIDANCE)) {
|
if (!copter.set_mode(Mode::Number::RTL, MODE_REASON_AVOIDANCE)) {
|
||||||
actual_action = MAV_COLLISION_ACTION_NONE;
|
actual_action = MAV_COLLISION_ACTION_NONE;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -53,7 +53,7 @@ MAV_COLLISION_ACTION AP_Avoidance_Copter::handle_avoidance(const AP_Avoidance::O
|
|||||||
case MAV_COLLISION_ACTION_HOVER:
|
case MAV_COLLISION_ACTION_HOVER:
|
||||||
// attempt to switch to Loiter, if this fails (i.e. flying in manual mode with bad position) do nothing
|
// attempt to switch to Loiter, if this fails (i.e. flying in manual mode with bad position) do nothing
|
||||||
if (failsafe_state_change) {
|
if (failsafe_state_change) {
|
||||||
if (!copter.set_mode(LOITER, MODE_REASON_AVOIDANCE)) {
|
if (!copter.set_mode(Mode::Number::LOITER, MODE_REASON_AVOIDANCE)) {
|
||||||
actual_action = MAV_COLLISION_ACTION_NONE;
|
actual_action = MAV_COLLISION_ACTION_NONE;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -118,12 +118,12 @@ void AP_Avoidance_Copter::handle_recovery(uint8_t recovery_action)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case AP_AVOIDANCE_RECOVERY_RTL:
|
case AP_AVOIDANCE_RECOVERY_RTL:
|
||||||
set_mode_else_try_RTL_else_LAND(RTL);
|
set_mode_else_try_RTL_else_LAND(Mode::Number::RTL);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AP_AVOIDANCE_RECOVERY_RESUME_IF_AUTO_ELSE_LOITER:
|
case AP_AVOIDANCE_RECOVERY_RESUME_IF_AUTO_ELSE_LOITER:
|
||||||
if (prev_control_mode == AUTO) {
|
if (prev_control_mode == Mode::Number::AUTO) {
|
||||||
set_mode_else_try_RTL_else_LAND(AUTO);
|
set_mode_else_try_RTL_else_LAND(Mode::Number::AUTO);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -134,12 +134,12 @@ void AP_Avoidance_Copter::handle_recovery(uint8_t recovery_action)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Avoidance_Copter::set_mode_else_try_RTL_else_LAND(control_mode_t mode)
|
void AP_Avoidance_Copter::set_mode_else_try_RTL_else_LAND(Mode::Number mode)
|
||||||
{
|
{
|
||||||
if (!copter.set_mode(mode, MODE_REASON_AVOIDANCE_RECOVERY)) {
|
if (!copter.set_mode(mode, MODE_REASON_AVOIDANCE_RECOVERY)) {
|
||||||
// on failure RTL or LAND
|
// on failure RTL or LAND
|
||||||
if (!copter.set_mode(RTL, MODE_REASON_AVOIDANCE_RECOVERY)) {
|
if (!copter.set_mode(Mode::Number::RTL, MODE_REASON_AVOIDANCE_RECOVERY)) {
|
||||||
copter.set_mode(LAND, MODE_REASON_AVOIDANCE_RECOVERY);
|
copter.set_mode(Mode::Number::LAND, MODE_REASON_AVOIDANCE_RECOVERY);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -148,15 +148,15 @@ void AP_Avoidance_Copter::set_mode_else_try_RTL_else_LAND(control_mode_t mode)
|
|||||||
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 != AVOID_ADSB) {
|
if (allow_mode_change && copter.control_mode != Mode::Number::AVOID_ADSB) {
|
||||||
if (!copter.set_mode(AVOID_ADSB, MODE_REASON_AVOIDANCE)) {
|
if (!copter.set_mode(Mode::Number::AVOID_ADSB, MODE_REASON_AVOIDANCE)) {
|
||||||
// failed to set mode so exit immediately
|
// failed to set mode so exit immediately
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// check flight mode
|
// check flight mode
|
||||||
return (copter.control_mode == AVOID_ADSB);
|
return (copter.control_mode == 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)
|
||||||
|
@ -17,7 +17,7 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
// helper function to set modes and always succeed
|
// helper function to set modes and always succeed
|
||||||
void set_mode_else_try_RTL_else_LAND(control_mode_t mode);
|
void set_mode_else_try_RTL_else_LAND(Mode::Number mode);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
// override avoidance handler
|
// override avoidance handler
|
||||||
@ -39,5 +39,5 @@ protected:
|
|||||||
bool handle_avoidance_perpendicular(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change);
|
bool handle_avoidance_perpendicular(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change);
|
||||||
|
|
||||||
// control mode before avoidance began
|
// control mode before avoidance began
|
||||||
control_mode_t prev_control_mode = RTL;
|
Mode::Number prev_control_mode = Mode::Number::RTL;
|
||||||
};
|
};
|
||||||
|
@ -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() || optflow_position_ok()) && xy_speed_cms <= 125.0f;
|
bool xy_speed_low = (position_ok() || optflow_position_ok()) && 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 == ALT_HOLD && small_angle_request);
|
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 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;
|
||||||
|
@ -382,22 +382,22 @@
|
|||||||
//
|
//
|
||||||
|
|
||||||
#ifndef FLIGHT_MODE_1
|
#ifndef FLIGHT_MODE_1
|
||||||
# define FLIGHT_MODE_1 STABILIZE
|
# define FLIGHT_MODE_1 Mode::Number::STABILIZE
|
||||||
#endif
|
#endif
|
||||||
#ifndef FLIGHT_MODE_2
|
#ifndef FLIGHT_MODE_2
|
||||||
# define FLIGHT_MODE_2 STABILIZE
|
# define FLIGHT_MODE_2 Mode::Number::STABILIZE
|
||||||
#endif
|
#endif
|
||||||
#ifndef FLIGHT_MODE_3
|
#ifndef FLIGHT_MODE_3
|
||||||
# define FLIGHT_MODE_3 STABILIZE
|
# define FLIGHT_MODE_3 Mode::Number::STABILIZE
|
||||||
#endif
|
#endif
|
||||||
#ifndef FLIGHT_MODE_4
|
#ifndef FLIGHT_MODE_4
|
||||||
# define FLIGHT_MODE_4 STABILIZE
|
# define FLIGHT_MODE_4 Mode::Number::STABILIZE
|
||||||
#endif
|
#endif
|
||||||
#ifndef FLIGHT_MODE_5
|
#ifndef FLIGHT_MODE_5
|
||||||
# define FLIGHT_MODE_5 STABILIZE
|
# define FLIGHT_MODE_5 Mode::Number::STABILIZE
|
||||||
#endif
|
#endif
|
||||||
#ifndef FLIGHT_MODE_6
|
#ifndef FLIGHT_MODE_6
|
||||||
# define FLIGHT_MODE_6 STABILIZE
|
# define FLIGHT_MODE_6 Mode::Number::STABILIZE
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
@ -24,7 +24,7 @@ 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 == ACRO || control_mode == FLIP) {
|
if (control_mode == Mode::Number::ACRO || control_mode == Mode::Number::FLIP) {
|
||||||
crash_counter = 0;
|
crash_counter = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -152,7 +152,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 == ACRO || control_mode == FLIP) {
|
if (control_mode == Mode::Number::ACRO || control_mode == Mode::Number::FLIP) {
|
||||||
control_loss_count = 0;
|
control_loss_count = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -30,32 +30,6 @@ enum autopilot_yaw_mode {
|
|||||||
#define HIL_MODE_DISABLED 0
|
#define HIL_MODE_DISABLED 0
|
||||||
#define HIL_MODE_SENSORS 1
|
#define HIL_MODE_SENSORS 1
|
||||||
|
|
||||||
// Auto Pilot Modes enumeration
|
|
||||||
enum control_mode_t {
|
|
||||||
STABILIZE = 0, // manual airframe angle with manual throttle
|
|
||||||
ACRO = 1, // manual body-frame angular rate with manual throttle
|
|
||||||
ALT_HOLD = 2, // manual airframe angle with automatic throttle
|
|
||||||
AUTO = 3, // fully automatic waypoint control using mission commands
|
|
||||||
GUIDED = 4, // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
|
|
||||||
LOITER = 5, // automatic horizontal acceleration with automatic throttle
|
|
||||||
RTL = 6, // automatic return to launching point
|
|
||||||
CIRCLE = 7, // automatic circular flight with automatic throttle
|
|
||||||
LAND = 9, // automatic landing with horizontal position control
|
|
||||||
DRIFT = 11, // semi-automous position, yaw and throttle control
|
|
||||||
SPORT = 13, // manual earth-frame angular rate control with manual throttle
|
|
||||||
FLIP = 14, // automatically flip the vehicle on the roll axis
|
|
||||||
AUTOTUNE = 15, // automatically tune the vehicle's roll and pitch gains
|
|
||||||
POSHOLD = 16, // automatic position hold with manual override, with automatic throttle
|
|
||||||
BRAKE = 17, // full-brake using inertial/GPS system, no pilot input
|
|
||||||
THROW = 18, // throw to launch mode using inertial/GPS system, no pilot input
|
|
||||||
AVOID_ADSB = 19, // automatic avoidance of obstacles in the macro scale - e.g. full-sized aircraft
|
|
||||||
GUIDED_NOGPS = 20, // guided mode but only accepts attitude and altitude
|
|
||||||
SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps
|
|
||||||
FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder
|
|
||||||
FOLLOW = 23, // follow attempts to follow another vehicle or ground station
|
|
||||||
ZIGZAG = 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B
|
|
||||||
};
|
|
||||||
|
|
||||||
enum mode_reason_t {
|
enum mode_reason_t {
|
||||||
MODE_REASON_UNKNOWN=0,
|
MODE_REASON_UNKNOWN=0,
|
||||||
MODE_REASON_TX_COMMAND,
|
MODE_REASON_TX_COMMAND,
|
||||||
|
@ -144,7 +144,7 @@ void Copter::failsafe_ekf_event()
|
|||||||
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED);
|
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED);
|
||||||
|
|
||||||
// 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 == LAND && landing_with_GPS()) {
|
if (control_mode == Mode::Number::LAND && landing_with_GPS()) {
|
||||||
mode_land.do_not_use_GPS();
|
mode_land.do_not_use_GPS();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -158,7 +158,7 @@ void Copter::failsafe_ekf_event()
|
|||||||
switch (g.fs_ekf_action) {
|
switch (g.fs_ekf_action) {
|
||||||
case FS_EKF_ACTION_ALTHOLD:
|
case FS_EKF_ACTION_ALTHOLD:
|
||||||
// AltHold
|
// AltHold
|
||||||
if (failsafe.radio || !set_mode(ALT_HOLD, MODE_REASON_EKF_FAILSAFE)) {
|
if (failsafe.radio || !set_mode(Mode::Number::ALT_HOLD, MODE_REASON_EKF_FAILSAFE)) {
|
||||||
set_mode_land_with_pause(MODE_REASON_EKF_FAILSAFE);
|
set_mode_land_with_pause(MODE_REASON_EKF_FAILSAFE);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -14,9 +14,9 @@ void Copter::failsafe_radio_on_event()
|
|||||||
if (should_disarm_on_failsafe()) {
|
if (should_disarm_on_failsafe()) {
|
||||||
arming.disarm();
|
arming.disarm();
|
||||||
} else {
|
} else {
|
||||||
if (control_mode == AUTO && g.failsafe_throttle == FS_THR_ENABLED_CONTINUE_MISSION) {
|
if (control_mode == Mode::Number::AUTO && g.failsafe_throttle == FS_THR_ENABLED_CONTINUE_MISSION) {
|
||||||
// continue mission
|
// continue mission
|
||||||
} else if (control_mode == LAND &&
|
} else if (flightmode->is_landing() &&
|
||||||
battery.has_failsafed() &&
|
battery.has_failsafed() &&
|
||||||
battery.get_highest_failsafe_priority() <= FAILSAFE_LAND_PRIORITY) {
|
battery.get_highest_failsafe_priority() <= FAILSAFE_LAND_PRIORITY) {
|
||||||
// continue landing or other high priority failsafes
|
// continue landing or other high priority failsafes
|
||||||
@ -98,7 +98,8 @@ void Copter::failsafe_gcs_check()
|
|||||||
return;
|
return;
|
||||||
} else if (RC_Channels::has_active_overrides()) {
|
} else if (RC_Channels::has_active_overrides()) {
|
||||||
// GCS is currently telling us what to do!
|
// GCS is currently telling us what to do!
|
||||||
} else if (control_mode == GUIDED || control_mode == GUIDED_NOGPS) {
|
} else if (control_mode == Mode::Number::GUIDED ||
|
||||||
|
control_mode == Mode::Number::GUIDED_NOGPS) {
|
||||||
// GCS is currently telling us what to do!
|
// GCS is currently telling us what to do!
|
||||||
} else {
|
} else {
|
||||||
return;
|
return;
|
||||||
@ -133,7 +134,8 @@ void Copter::failsafe_gcs_check()
|
|||||||
if (should_disarm_on_failsafe()) {
|
if (should_disarm_on_failsafe()) {
|
||||||
arming.disarm();
|
arming.disarm();
|
||||||
} else {
|
} else {
|
||||||
if (control_mode == AUTO && g.failsafe_gcs == FS_GCS_ENABLED_CONTINUE_MISSION) {
|
if (control_mode == Mode::Number::AUTO &&
|
||||||
|
g.failsafe_gcs == FS_GCS_ENABLED_CONTINUE_MISSION) {
|
||||||
// continue mission
|
// continue mission
|
||||||
} else if (g.failsafe_gcs == FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL) {
|
} else if (g.failsafe_gcs == FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL) {
|
||||||
set_mode_SmartRTL_or_RTL(MODE_REASON_GCS_FAILSAFE);
|
set_mode_SmartRTL_or_RTL(MODE_REASON_GCS_FAILSAFE);
|
||||||
@ -156,7 +158,10 @@ void Copter::failsafe_gcs_off_event(void)
|
|||||||
void Copter::failsafe_terrain_check()
|
void Copter::failsafe_terrain_check()
|
||||||
{
|
{
|
||||||
// trigger with 5 seconds of failures while in AUTO mode
|
// trigger with 5 seconds of failures while in AUTO mode
|
||||||
bool valid_mode = (control_mode == AUTO || control_mode == GUIDED || control_mode == GUIDED_NOGPS || control_mode == RTL);
|
bool valid_mode = (control_mode == Mode::Number::AUTO ||
|
||||||
|
control_mode == Mode::Number::GUIDED ||
|
||||||
|
control_mode == Mode::Number::GUIDED_NOGPS ||
|
||||||
|
control_mode == Mode::Number::RTL);
|
||||||
bool timeout = (failsafe.terrain_last_failure_ms - failsafe.terrain_first_failure_ms) > FS_TERRAIN_TIMEOUT_MS;
|
bool timeout = (failsafe.terrain_last_failure_ms - failsafe.terrain_first_failure_ms) > FS_TERRAIN_TIMEOUT_MS;
|
||||||
bool trigger_event = valid_mode && timeout;
|
bool trigger_event = valid_mode && timeout;
|
||||||
|
|
||||||
@ -201,7 +206,7 @@ void Copter::failsafe_terrain_on_event()
|
|||||||
if (should_disarm_on_failsafe()) {
|
if (should_disarm_on_failsafe()) {
|
||||||
arming.disarm();
|
arming.disarm();
|
||||||
#if MODE_RTL_ENABLED == ENABLED
|
#if MODE_RTL_ENABLED == ENABLED
|
||||||
} else if (control_mode == RTL) {
|
} else if (control_mode == Mode::Number::RTL) {
|
||||||
mode_rtl.restart_without_terrain();
|
mode_rtl.restart_without_terrain();
|
||||||
#endif
|
#endif
|
||||||
} else {
|
} else {
|
||||||
@ -234,7 +239,7 @@ void Copter::gpsglitch_check()
|
|||||||
void Copter::set_mode_RTL_or_land_with_pause(mode_reason_t reason)
|
void Copter::set_mode_RTL_or_land_with_pause(mode_reason_t reason)
|
||||||
{
|
{
|
||||||
// attempt to switch to RTL, if this fails then switch to Land
|
// attempt to switch to RTL, if this fails then switch to Land
|
||||||
if (!set_mode(RTL, reason)) {
|
if (!set_mode(Mode::Number::RTL, reason)) {
|
||||||
// set mode to land will trigger mode change notification to pilot
|
// set mode to land will trigger mode change notification to pilot
|
||||||
set_mode_land_with_pause(reason);
|
set_mode_land_with_pause(reason);
|
||||||
} else {
|
} else {
|
||||||
@ -248,7 +253,7 @@ void Copter::set_mode_RTL_or_land_with_pause(mode_reason_t reason)
|
|||||||
void Copter::set_mode_SmartRTL_or_land_with_pause(mode_reason_t reason)
|
void Copter::set_mode_SmartRTL_or_land_with_pause(mode_reason_t reason)
|
||||||
{
|
{
|
||||||
// attempt to switch to SMART_RTL, if this failed then switch to Land
|
// attempt to switch to SMART_RTL, if this failed then switch to Land
|
||||||
if (!set_mode(SMART_RTL, reason)) {
|
if (!set_mode(Mode::Number::SMART_RTL, reason)) {
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Using Land Mode");
|
gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Using Land Mode");
|
||||||
set_mode_land_with_pause(reason);
|
set_mode_land_with_pause(reason);
|
||||||
} else {
|
} else {
|
||||||
@ -262,7 +267,7 @@ void Copter::set_mode_SmartRTL_or_RTL(mode_reason_t reason)
|
|||||||
{
|
{
|
||||||
// attempt to switch to SmartRTL, if this failed then attempt to RTL
|
// attempt to switch to SmartRTL, if this failed then attempt to RTL
|
||||||
// if that fails, then land
|
// if that fails, then land
|
||||||
if (!set_mode(SMART_RTL, reason)) {
|
if (!set_mode(Mode::Number::SMART_RTL, reason)) {
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Trying RTL Mode");
|
gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Trying RTL Mode");
|
||||||
set_mode_RTL_or_land_with_pause(reason);
|
set_mode_RTL_or_land_with_pause(reason);
|
||||||
} else {
|
} else {
|
||||||
@ -276,11 +281,11 @@ bool Copter::should_disarm_on_failsafe() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
switch (control_mode) {
|
switch (control_mode) {
|
||||||
case STABILIZE:
|
case Mode::Number::STABILIZE:
|
||||||
case 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
|
||||||
return ap.throttle_zero || ap.land_complete;
|
return ap.throttle_zero || ap.land_complete;
|
||||||
case AUTO:
|
case Mode::Number::AUTO:
|
||||||
// if mission has not started AND vehicle is landed, disarm motors
|
// if mission has not started AND vehicle is landed, disarm motors
|
||||||
return !ap.auto_armed && ap.land_complete;
|
return !ap.auto_armed && ap.land_complete;
|
||||||
default:
|
default:
|
||||||
|
@ -36,32 +36,32 @@ void Copter::fence_check()
|
|||||||
|
|
||||||
// if more than 100m outside the fence just force a land
|
// if more than 100m outside the fence just force a land
|
||||||
if (fence.get_breach_distance(new_breaches) > AC_FENCE_GIVE_UP_DISTANCE) {
|
if (fence.get_breach_distance(new_breaches) > AC_FENCE_GIVE_UP_DISTANCE) {
|
||||||
set_mode(LAND, MODE_REASON_FENCE_BREACH);
|
set_mode(Mode::Number::LAND, MODE_REASON_FENCE_BREACH);
|
||||||
} else {
|
} else {
|
||||||
switch (fence_act) {
|
switch (fence_act) {
|
||||||
case AC_FENCE_ACTION_RTL_AND_LAND:
|
case AC_FENCE_ACTION_RTL_AND_LAND:
|
||||||
default:
|
default:
|
||||||
// switch to RTL, if that fails then Land
|
// switch to RTL, if that fails then Land
|
||||||
if (!set_mode(RTL, MODE_REASON_FENCE_BREACH)) {
|
if (!set_mode(Mode::Number::RTL, MODE_REASON_FENCE_BREACH)) {
|
||||||
set_mode(LAND, MODE_REASON_FENCE_BREACH);
|
set_mode(Mode::Number::LAND, MODE_REASON_FENCE_BREACH);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case AC_FENCE_ACTION_ALWAYS_LAND:
|
case AC_FENCE_ACTION_ALWAYS_LAND:
|
||||||
// if always land option mode is specified, land
|
// if always land option mode is specified, land
|
||||||
set_mode(LAND, MODE_REASON_FENCE_BREACH);
|
set_mode(Mode::Number::LAND, MODE_REASON_FENCE_BREACH);
|
||||||
break;
|
break;
|
||||||
case AC_FENCE_ACTION_SMART_RTL:
|
case AC_FENCE_ACTION_SMART_RTL:
|
||||||
// Try SmartRTL, if that fails, RTL, if that fails Land
|
// Try SmartRTL, if that fails, RTL, if that fails Land
|
||||||
if (!set_mode(SMART_RTL, MODE_REASON_FENCE_BREACH)) {
|
if (!set_mode(Mode::Number::SMART_RTL, MODE_REASON_FENCE_BREACH)) {
|
||||||
if (!set_mode(RTL, MODE_REASON_FENCE_BREACH)) {
|
if (!set_mode(Mode::Number::RTL, MODE_REASON_FENCE_BREACH)) {
|
||||||
set_mode(LAND, MODE_REASON_FENCE_BREACH);
|
set_mode(Mode::Number::LAND, MODE_REASON_FENCE_BREACH);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case AC_FENCE_ACTION_BRAKE:
|
case AC_FENCE_ACTION_BRAKE:
|
||||||
// Try Brake, if that fails Land
|
// Try Brake, if that fails Land
|
||||||
if (!set_mode(BRAKE, MODE_REASON_FENCE_BREACH)) {
|
if (!set_mode(Mode::Number::BRAKE, MODE_REASON_FENCE_BREACH)) {
|
||||||
set_mode(LAND, MODE_REASON_FENCE_BREACH);
|
set_mode(Mode::Number::LAND, MODE_REASON_FENCE_BREACH);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -24,7 +24,7 @@ void Copter::heli_init()
|
|||||||
void Copter::check_dynamic_flight(void)
|
void Copter::check_dynamic_flight(void)
|
||||||
{
|
{
|
||||||
if (motors->get_spool_state() != AP_Motors::SpoolState::THROTTLE_UNLIMITED ||
|
if (motors->get_spool_state() != AP_Motors::SpoolState::THROTTLE_UNLIMITED ||
|
||||||
control_mode == LAND || (control_mode==RTL && mode_rtl.state() == RTL_Land) || (control_mode == AUTO && mode_auto.mode() == Auto_Land)) {
|
control_mode == Mode::Number::LAND || (control_mode==Mode::Number::RTL && mode_rtl.state() == RTL_Land) || (control_mode == Mode::Number::AUTO && mode_auto.mode() == Auto_Land)) {
|
||||||
heli_dynamic_flight_counter = 0;
|
heli_dynamic_flight_counter = 0;
|
||||||
heli_flags.dynamic_flight = false;
|
heli_flags.dynamic_flight = false;
|
||||||
return;
|
return;
|
||||||
@ -94,21 +94,21 @@ void Copter::update_heli_control_dynamics(void)
|
|||||||
void Copter::heli_update_landing_swash()
|
void Copter::heli_update_landing_swash()
|
||||||
{
|
{
|
||||||
switch (control_mode) {
|
switch (control_mode) {
|
||||||
case ACRO:
|
case Mode::Number::ACRO:
|
||||||
case STABILIZE:
|
case Mode::Number::STABILIZE:
|
||||||
case DRIFT:
|
case Mode::Number::DRIFT:
|
||||||
case SPORT:
|
case Mode::Number::SPORT:
|
||||||
// manual modes always uses full swash range
|
// manual modes always uses full swash range
|
||||||
motors->set_collective_for_landing(false);
|
motors->set_collective_for_landing(false);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case LAND:
|
case Mode::Number::LAND:
|
||||||
// landing always uses limit swash range
|
// landing always uses limit swash range
|
||||||
motors->set_collective_for_landing(true);
|
motors->set_collective_for_landing(true);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case RTL:
|
case Mode::Number::RTL:
|
||||||
case SMART_RTL:
|
case Mode::Number::SMART_RTL:
|
||||||
if (mode_rtl.state() == RTL_Land) {
|
if (mode_rtl.state() == RTL_Land) {
|
||||||
motors->set_collective_for_landing(true);
|
motors->set_collective_for_landing(true);
|
||||||
}else{
|
}else{
|
||||||
@ -116,7 +116,7 @@ void Copter::heli_update_landing_swash()
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUTO:
|
case Mode::Number::AUTO:
|
||||||
if (mode_auto.mode() == Auto_Land) {
|
if (mode_auto.mode() == Auto_Land) {
|
||||||
motors->set_collective_for_landing(true);
|
motors->set_collective_for_landing(true);
|
||||||
}else{
|
}else{
|
||||||
|
@ -28,133 +28,133 @@ Mode::Mode(void) :
|
|||||||
float Mode::auto_takeoff_no_nav_alt_cm = 0;
|
float Mode::auto_takeoff_no_nav_alt_cm = 0;
|
||||||
|
|
||||||
// return the static controller object corresponding to supplied mode
|
// return the static controller object corresponding to supplied mode
|
||||||
Mode *Copter::mode_from_mode_num(const uint8_t mode)
|
Mode *Copter::mode_from_mode_num(const Mode::Number mode)
|
||||||
{
|
{
|
||||||
Mode *ret = nullptr;
|
Mode *ret = nullptr;
|
||||||
|
|
||||||
switch (mode) {
|
switch (mode) {
|
||||||
#if MODE_ACRO_ENABLED == ENABLED
|
#if MODE_ACRO_ENABLED == ENABLED
|
||||||
case ACRO:
|
case Mode::Number::ACRO:
|
||||||
ret = &mode_acro;
|
ret = &mode_acro;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case STABILIZE:
|
case Mode::Number::STABILIZE:
|
||||||
ret = &mode_stabilize;
|
ret = &mode_stabilize;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ALT_HOLD:
|
case Mode::Number::ALT_HOLD:
|
||||||
ret = &mode_althold;
|
ret = &mode_althold;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if MODE_AUTO_ENABLED == ENABLED
|
#if MODE_AUTO_ENABLED == ENABLED
|
||||||
case AUTO:
|
case Mode::Number::AUTO:
|
||||||
ret = &mode_auto;
|
ret = &mode_auto;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_CIRCLE_ENABLED == ENABLED
|
#if MODE_CIRCLE_ENABLED == ENABLED
|
||||||
case CIRCLE:
|
case Mode::Number::CIRCLE:
|
||||||
ret = &mode_circle;
|
ret = &mode_circle;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_LOITER_ENABLED == ENABLED
|
#if MODE_LOITER_ENABLED == ENABLED
|
||||||
case LOITER:
|
case Mode::Number::LOITER:
|
||||||
ret = &mode_loiter;
|
ret = &mode_loiter;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_GUIDED_ENABLED == ENABLED
|
#if MODE_GUIDED_ENABLED == ENABLED
|
||||||
case GUIDED:
|
case Mode::Number::GUIDED:
|
||||||
ret = &mode_guided;
|
ret = &mode_guided;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case LAND:
|
case Mode::Number::LAND:
|
||||||
ret = &mode_land;
|
ret = &mode_land;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if MODE_RTL_ENABLED == ENABLED
|
#if MODE_RTL_ENABLED == ENABLED
|
||||||
case RTL:
|
case Mode::Number::RTL:
|
||||||
ret = &mode_rtl;
|
ret = &mode_rtl;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_DRIFT_ENABLED == ENABLED
|
#if MODE_DRIFT_ENABLED == ENABLED
|
||||||
case DRIFT:
|
case Mode::Number::DRIFT:
|
||||||
ret = &mode_drift;
|
ret = &mode_drift;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_SPORT_ENABLED == ENABLED
|
#if MODE_SPORT_ENABLED == ENABLED
|
||||||
case SPORT:
|
case Mode::Number::SPORT:
|
||||||
ret = &mode_sport;
|
ret = &mode_sport;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_FLIP_ENABLED == ENABLED
|
#if MODE_FLIP_ENABLED == ENABLED
|
||||||
case FLIP:
|
case Mode::Number::FLIP:
|
||||||
ret = &mode_flip;
|
ret = &mode_flip;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AUTOTUNE_ENABLED == ENABLED
|
#if AUTOTUNE_ENABLED == ENABLED
|
||||||
case AUTOTUNE:
|
case Mode::Number::AUTOTUNE:
|
||||||
ret = &mode_autotune;
|
ret = &mode_autotune;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_POSHOLD_ENABLED == ENABLED
|
#if MODE_POSHOLD_ENABLED == ENABLED
|
||||||
case POSHOLD:
|
case Mode::Number::POSHOLD:
|
||||||
ret = &mode_poshold;
|
ret = &mode_poshold;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_BRAKE_ENABLED == ENABLED
|
#if MODE_BRAKE_ENABLED == ENABLED
|
||||||
case BRAKE:
|
case Mode::Number::BRAKE:
|
||||||
ret = &mode_brake;
|
ret = &mode_brake;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_THROW_ENABLED == ENABLED
|
#if MODE_THROW_ENABLED == ENABLED
|
||||||
case THROW:
|
case Mode::Number::THROW:
|
||||||
ret = &mode_throw;
|
ret = &mode_throw;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ADSB_ENABLED == ENABLED
|
#if ADSB_ENABLED == ENABLED
|
||||||
case AVOID_ADSB:
|
case Mode::Number::AVOID_ADSB:
|
||||||
ret = &mode_avoid_adsb;
|
ret = &mode_avoid_adsb;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_GUIDED_NOGPS_ENABLED == ENABLED
|
#if MODE_GUIDED_NOGPS_ENABLED == ENABLED
|
||||||
case GUIDED_NOGPS:
|
case Mode::Number::GUIDED_NOGPS:
|
||||||
ret = &mode_guided_nogps;
|
ret = &mode_guided_nogps;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_SMARTRTL_ENABLED == ENABLED
|
#if MODE_SMARTRTL_ENABLED == ENABLED
|
||||||
case SMART_RTL:
|
case Mode::Number::SMART_RTL:
|
||||||
ret = &mode_smartrtl;
|
ret = &mode_smartrtl;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if OPTFLOW == ENABLED
|
#if OPTFLOW == ENABLED
|
||||||
case FLOWHOLD:
|
case Mode::Number::FLOWHOLD:
|
||||||
ret = (Mode *)g2.mode_flowhold_ptr;
|
ret = (Mode *)g2.mode_flowhold_ptr;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_FOLLOW_ENABLED == ENABLED
|
#if MODE_FOLLOW_ENABLED == ENABLED
|
||||||
case FOLLOW:
|
case Mode::Number::FOLLOW:
|
||||||
ret = &mode_follow;
|
ret = &mode_follow;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_ZIGZAG_ENABLED == ENABLED
|
#if MODE_ZIGZAG_ENABLED == ENABLED
|
||||||
case ZIGZAG:
|
case Mode::Number::ZIGZAG:
|
||||||
ret = &mode_zigzag;
|
ret = &mode_zigzag;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
@ -171,7 +171,7 @@ Mode *Copter::mode_from_mode_num(const uint8_t mode)
|
|||||||
// optional force parameter used to force the flight mode change (used only first time mode is set)
|
// optional force parameter used to force the flight mode change (used only first time mode is set)
|
||||||
// returns true if mode was successfully set
|
// returns true if mode was successfully set
|
||||||
// ACRO, STABILIZE, ALTHOLD, LAND, DRIFT and SPORT can always be set successfully but the return state of other flight modes should be checked and the caller should deal with failures appropriately
|
// ACRO, STABILIZE, ALTHOLD, LAND, DRIFT and SPORT can always be set successfully but the return state of other flight modes should be checked and the caller should deal with failures appropriately
|
||||||
bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
|
bool Copter::set_mode(Mode::Number mode, mode_reason_t reason)
|
||||||
{
|
{
|
||||||
|
|
||||||
// return immediately if we are already in the desired mode
|
// return immediately if we are already in the desired mode
|
||||||
@ -180,7 +180,7 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
Mode *new_flightmode = mode_from_mode_num(mode);
|
Mode *new_flightmode = mode_from_mode_num((Mode::Number)mode);
|
||||||
if (new_flightmode == nullptr) {
|
if (new_flightmode == nullptr) {
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING,"No such mode");
|
gcs().send_text(MAV_SEVERITY_WARNING,"No such mode");
|
||||||
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
|
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
|
||||||
@ -242,11 +242,11 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
|
|||||||
flightmode = new_flightmode;
|
flightmode = new_flightmode;
|
||||||
control_mode = mode;
|
control_mode = mode;
|
||||||
control_mode_reason = reason;
|
control_mode_reason = reason;
|
||||||
logger.Write_Mode(control_mode, reason);
|
logger.Write_Mode((uint8_t)control_mode, reason);
|
||||||
gcs().send_message(MSG_HEARTBEAT);
|
gcs().send_message(MSG_HEARTBEAT);
|
||||||
|
|
||||||
#if ADSB_ENABLED == ENABLED
|
#if ADSB_ENABLED == ENABLED
|
||||||
adsb.set_is_auto_mode((mode == AUTO) || (mode == RTL) || (mode == GUIDED));
|
adsb.set_is_auto_mode((mode == Mode::Number::AUTO) || (mode == Mode::Number::RTL) || (mode == Mode::Number::GUIDED));
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
@ -257,7 +257,7 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if CAMERA == ENABLED
|
#if CAMERA == ENABLED
|
||||||
camera.set_is_auto_mode(control_mode == AUTO);
|
camera.set_is_auto_mode(control_mode == Mode::Number::AUTO);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// update notify object
|
// update notify object
|
||||||
@ -337,7 +337,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 = control_mode;
|
AP_Notify::flags.flight_mode = (uint8_t)control_mode;
|
||||||
notify.set_flight_mode_str(flightmode->name4());
|
notify.set_flight_mode_str(flightmode->name4());
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -524,8 +524,8 @@ void Mode::land_run_horizontal_control()
|
|||||||
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
|
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
|
||||||
copter.Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT);
|
copter.Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT);
|
||||||
// exit land if throttle is high
|
// exit land if throttle is high
|
||||||
if (!set_mode(LOITER, MODE_REASON_THROTTLE_LAND_ESCAPE)) {
|
if (!set_mode(Mode::Number::LOITER, MODE_REASON_THROTTLE_LAND_ESCAPE)) {
|
||||||
set_mode(ALT_HOLD, MODE_REASON_THROTTLE_LAND_ESCAPE);
|
set_mode(Mode::Number::ALT_HOLD, MODE_REASON_THROTTLE_LAND_ESCAPE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -720,7 +720,7 @@ void Mode::update_simple_mode(void) {
|
|||||||
copter.update_simple_mode();
|
copter.update_simple_mode();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Mode::set_mode(control_mode_t mode, mode_reason_t reason)
|
bool Mode::set_mode(Mode::Number mode, mode_reason_t reason)
|
||||||
{
|
{
|
||||||
return copter.set_mode(mode, reason);
|
return copter.set_mode(mode, reason);
|
||||||
}
|
}
|
||||||
|
@ -2,10 +2,41 @@
|
|||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
|
class Parameters;
|
||||||
|
class ParametersG2;
|
||||||
|
|
||||||
|
class GCS_Copter;
|
||||||
|
|
||||||
class Mode {
|
class Mode {
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
// Auto Pilot Modes enumeration
|
||||||
|
enum class Number {
|
||||||
|
STABILIZE = 0, // manual airframe angle with manual throttle
|
||||||
|
ACRO = 1, // manual body-frame angular rate with manual throttle
|
||||||
|
ALT_HOLD = 2, // manual airframe angle with automatic throttle
|
||||||
|
AUTO = 3, // fully automatic waypoint control using mission commands
|
||||||
|
GUIDED = 4, // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
|
||||||
|
LOITER = 5, // automatic horizontal acceleration with automatic throttle
|
||||||
|
RTL = 6, // automatic return to launching point
|
||||||
|
CIRCLE = 7, // automatic circular flight with automatic throttle
|
||||||
|
LAND = 9, // automatic landing with horizontal position control
|
||||||
|
DRIFT = 11, // semi-automous position, yaw and throttle control
|
||||||
|
SPORT = 13, // manual earth-frame angular rate control with manual throttle
|
||||||
|
FLIP = 14, // automatically flip the vehicle on the roll axis
|
||||||
|
AUTOTUNE = 15, // automatically tune the vehicle's roll and pitch gains
|
||||||
|
POSHOLD = 16, // automatic position hold with manual override, with automatic throttle
|
||||||
|
BRAKE = 17, // full-brake using inertial/GPS system, no pilot input
|
||||||
|
THROW = 18, // throw to launch mode using inertial/GPS system, no pilot input
|
||||||
|
AVOID_ADSB = 19, // automatic avoidance of obstacles in the macro scale - e.g. full-sized aircraft
|
||||||
|
GUIDED_NOGPS = 20, // guided mode but only accepts attitude and altitude
|
||||||
|
SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps
|
||||||
|
FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder
|
||||||
|
FOLLOW = 23, // follow attempts to follow another vehicle or ground station
|
||||||
|
ZIGZAG = 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B
|
||||||
|
};
|
||||||
|
|
||||||
// constructor
|
// constructor
|
||||||
Mode(void);
|
Mode(void);
|
||||||
|
|
||||||
@ -205,7 +236,7 @@ public:
|
|||||||
float get_pilot_desired_climb_rate(float throttle_control);
|
float get_pilot_desired_climb_rate(float throttle_control);
|
||||||
float get_non_takeoff_throttle(void);
|
float get_non_takeoff_throttle(void);
|
||||||
void update_simple_mode(void);
|
void update_simple_mode(void);
|
||||||
bool set_mode(control_mode_t mode, mode_reason_t reason);
|
bool set_mode(Mode::Number mode, mode_reason_t reason);
|
||||||
void set_land_complete(bool b);
|
void set_land_complete(bool b);
|
||||||
GCS_Copter &gcs();
|
GCS_Copter &gcs();
|
||||||
void Log_Write_Event(Log_Event id);
|
void Log_Write_Event(Log_Event id);
|
||||||
@ -238,12 +269,7 @@ protected:
|
|||||||
|
|
||||||
void get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int16_t yaw_in, float &roll_out, float &pitch_out, float &yaw_out);
|
void get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int16_t yaw_in, float &roll_out, float &pitch_out, float &yaw_out);
|
||||||
|
|
||||||
float throttle_hover() const override {
|
float throttle_hover() const override;
|
||||||
if (g2.acro_thr_mid > 0) {
|
|
||||||
return g2.acro_thr_mid;
|
|
||||||
}
|
|
||||||
return Mode::throttle_hover();
|
|
||||||
}
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
@ -630,7 +656,7 @@ private:
|
|||||||
Abandon
|
Abandon
|
||||||
};
|
};
|
||||||
FlipState _state; // current state of flip
|
FlipState _state; // current state of flip
|
||||||
control_mode_t orig_control_mode; // flight mode when flip was initated
|
Mode::Number orig_control_mode; // flight mode when flip was initated
|
||||||
uint32_t start_time_ms; // time since flip began
|
uint32_t start_time_ms; // time since flip began
|
||||||
int8_t roll_dir; // roll direction (-1 = roll left, 1 = roll right)
|
int8_t roll_dir; // roll direction (-1 = roll left, 1 = roll right)
|
||||||
int8_t pitch_dir; // pitch direction (-1 = pitch forward, 1 = pitch back)
|
int8_t pitch_dir; // pitch direction (-1 = pitch forward, 1 = pitch back)
|
||||||
|
@ -56,6 +56,13 @@ void ModeAcro::run()
|
|||||||
copter.g.throttle_filt);
|
copter.g.throttle_filt);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
float ModeAcro::throttle_hover() const
|
||||||
|
{
|
||||||
|
if (g2.acro_thr_mid > 0) {
|
||||||
|
return g2.acro_thr_mid;
|
||||||
|
}
|
||||||
|
return Mode::throttle_hover();
|
||||||
|
}
|
||||||
|
|
||||||
// get_pilot_desired_angle_rates - transform pilot's roll pitch and yaw input into a desired lean angle rates
|
// get_pilot_desired_angle_rates - transform pilot's roll pitch and yaw input into a desired lean angle rates
|
||||||
// returns desired angle rates in centi-degrees-per-second
|
// returns desired angle rates in centi-degrees-per-second
|
||||||
|
@ -539,7 +539,7 @@ void ModeAuto::exit_mission()
|
|||||||
if (!copter.ap.land_complete) {
|
if (!copter.ap.land_complete) {
|
||||||
// try to enter loiter but if that fails land
|
// try to enter loiter but if that fails land
|
||||||
if (!loiter_start()) {
|
if (!loiter_start()) {
|
||||||
set_mode(LAND, MODE_REASON_MISSION_END);
|
set_mode(Mode::Number::LAND, MODE_REASON_MISSION_END);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// if we've landed it's safe to disarm
|
// if we've landed it's safe to disarm
|
||||||
@ -551,7 +551,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 != GUIDED && !(copter.control_mode == AUTO && mode() == Auto_NavGuided)) {
|
if (copter.control_mode != Mode::Number::GUIDED && !(copter.control_mode == Mode::Number::AUTO && mode() == Auto_NavGuided)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -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 == LOITER || copter.control_mode == POSHOLD);
|
bool position_hold = (copter.control_mode == Mode::Number::LOITER || copter.control_mode == Mode::Number::POSHOLD);
|
||||||
|
|
||||||
return init_internals(position_hold,
|
return init_internals(position_hold,
|
||||||
copter.attitude_control,
|
copter.attitude_control,
|
||||||
@ -24,8 +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 != STABILIZE && copter.control_mode != ALT_HOLD &&
|
if (copter.control_mode != Mode::Number::STABILIZE &&
|
||||||
copter.control_mode != LOITER && copter.control_mode != POSHOLD) {
|
copter.control_mode != Mode::Number::ALT_HOLD &&
|
||||||
|
copter.control_mode != Mode::Number::LOITER &&
|
||||||
|
copter.control_mode != Mode::Number::POSHOLD) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -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 != AVOID_ADSB) {
|
if (copter.control_mode != Mode::Number::AVOID_ADSB) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -63,8 +63,8 @@ void ModeBrake::run()
|
|||||||
pos_control->update_z_controller();
|
pos_control->update_z_controller();
|
||||||
|
|
||||||
if (_timeout_ms != 0 && millis()-_timeout_start >= _timeout_ms) {
|
if (_timeout_ms != 0 && millis()-_timeout_start >= _timeout_ms) {
|
||||||
if (!copter.set_mode(LOITER, MODE_REASON_BRAKE_TIMEOUT)) {
|
if (!copter.set_mode(Mode::Number::LOITER, MODE_REASON_BRAKE_TIMEOUT)) {
|
||||||
copter.set_mode(ALT_HOLD, MODE_REASON_BRAKE_TIMEOUT);
|
copter.set_mode(Mode::Number::ALT_HOLD, MODE_REASON_BRAKE_TIMEOUT);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -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 != ACRO &&
|
if (copter.control_mode != Mode::Number::ACRO &&
|
||||||
copter.control_mode != STABILIZE &&
|
copter.control_mode != Mode::Number::STABILIZE &&
|
||||||
copter.control_mode != ALT_HOLD &&
|
copter.control_mode != Mode::Number::ALT_HOLD &&
|
||||||
copter.control_mode != FLOWHOLD) {
|
copter.control_mode != Mode::Number::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 == ACRO || copter.control_mode == STABILIZE)) {
|
if (copter.ap.throttle_zero && (copter.control_mode == Mode::Number::ACRO || copter.control_mode == Mode::Number::STABILIZE)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -194,7 +194,7 @@ void ModeFlip::run()
|
|||||||
// restore original flight mode
|
// restore original flight mode
|
||||||
if (!copter.set_mode(orig_control_mode, MODE_REASON_FLIP_COMPLETE)) {
|
if (!copter.set_mode(orig_control_mode, MODE_REASON_FLIP_COMPLETE)) {
|
||||||
// this should never happen but just in case
|
// this should never happen but just in case
|
||||||
copter.set_mode(STABILIZE, MODE_REASON_UNKNOWN);
|
copter.set_mode(Mode::Number::STABILIZE, MODE_REASON_UNKNOWN);
|
||||||
}
|
}
|
||||||
// log successful completion
|
// log successful completion
|
||||||
Log_Write_Event(DATA_FLIP_END);
|
Log_Write_Event(DATA_FLIP_END);
|
||||||
@ -205,7 +205,7 @@ void ModeFlip::run()
|
|||||||
// restore original flight mode
|
// restore original flight mode
|
||||||
if (!copter.set_mode(orig_control_mode, MODE_REASON_FLIP_COMPLETE)) {
|
if (!copter.set_mode(orig_control_mode, MODE_REASON_FLIP_COMPLETE)) {
|
||||||
// this should never happen but just in case
|
// this should never happen but just in case
|
||||||
copter.set_mode(STABILIZE, MODE_REASON_UNKNOWN);
|
copter.set_mode(Mode::Number::STABILIZE, MODE_REASON_UNKNOWN);
|
||||||
}
|
}
|
||||||
// log abandoning flip
|
// log abandoning flip
|
||||||
AP::logger().Write_Error(LogErrorSubsystem::FLIP, LogErrorCode::FLIP_ABANDONED);
|
AP::logger().Write_Error(LogErrorSubsystem::FLIP, LogErrorCode::FLIP_ABANDONED);
|
||||||
|
@ -93,7 +93,7 @@ void ModeLand::nogps_run()
|
|||||||
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
|
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
|
||||||
Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT);
|
Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT);
|
||||||
// exit land if throttle is high
|
// exit land if throttle is high
|
||||||
copter.set_mode(ALT_HOLD, MODE_REASON_THROTTLE_LAND_ESCAPE);
|
copter.set_mode(Mode::Number::ALT_HOLD, MODE_REASON_THROTTLE_LAND_ESCAPE);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (g.land_repositioning) {
|
if (g.land_repositioning) {
|
||||||
@ -147,7 +147,7 @@ void ModeLand::do_not_use_GPS()
|
|||||||
// this is always called from a failsafe so we trigger notification to pilot
|
// this is always called from a failsafe so we trigger notification to pilot
|
||||||
void Copter::set_mode_land_with_pause(mode_reason_t reason)
|
void Copter::set_mode_land_with_pause(mode_reason_t reason)
|
||||||
{
|
{
|
||||||
set_mode(LAND, reason);
|
set_mode(Mode::Number::LAND, reason);
|
||||||
land_pause = true;
|
land_pause = true;
|
||||||
|
|
||||||
// alert pilot to mode change
|
// alert pilot to mode change
|
||||||
@ -157,5 +157,5 @@ void Copter::set_mode_land_with_pause(mode_reason_t 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 == LAND && land_with_gps);
|
return (control_mode == Mode::Number::LAND && land_with_gps);
|
||||||
}
|
}
|
||||||
|
@ -119,7 +119,7 @@ void ModeRTL::climb_start()
|
|||||||
if (!wp_nav->set_wp_destination(rtl_path.climb_target)) {
|
if (!wp_nav->set_wp_destination(rtl_path.climb_target)) {
|
||||||
// this should not happen because rtl_build_path will have checked terrain data was available
|
// this should not happen because rtl_build_path will have checked terrain data was available
|
||||||
AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION);
|
AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION);
|
||||||
copter.set_mode(LAND, MODE_REASON_TERRAIN_FAILSAFE);
|
copter.set_mode(Mode::Number::LAND, MODE_REASON_TERRAIN_FAILSAFE);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
wp_nav->set_fast_waypoint(true);
|
wp_nav->set_fast_waypoint(true);
|
||||||
@ -287,8 +287,8 @@ void ModeRTL::descent_run()
|
|||||||
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
|
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
|
||||||
Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT);
|
Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT);
|
||||||
// exit land if throttle is high
|
// exit land if throttle is high
|
||||||
if (!copter.set_mode(LOITER, MODE_REASON_THROTTLE_LAND_ESCAPE)) {
|
if (!copter.set_mode(Mode::Number::LOITER, MODE_REASON_THROTTLE_LAND_ESCAPE)) {
|
||||||
copter.set_mode(ALT_HOLD, MODE_REASON_THROTTLE_LAND_ESCAPE);
|
copter.set_mode(Mode::Number::ALT_HOLD, MODE_REASON_THROTTLE_LAND_ESCAPE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -144,7 +144,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 != SMART_RTL);
|
const bool should_save_position = motors->armed() && (copter.control_mode != 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);
|
||||||
}
|
}
|
||||||
|
@ -85,14 +85,14 @@ void ModeThrow::run()
|
|||||||
copter.set_auto_armed(true);
|
copter.set_auto_armed(true);
|
||||||
} else if (stage == Throw_PosHold && throw_position_good()) {
|
} else if (stage == Throw_PosHold && throw_position_good()) {
|
||||||
if (!nextmode_attempted) {
|
if (!nextmode_attempted) {
|
||||||
switch (g2.throw_nextmode) {
|
switch ((Mode::Number)g2.throw_nextmode.get()) {
|
||||||
case AUTO:
|
case Mode::Number::AUTO:
|
||||||
case GUIDED:
|
case Mode::Number::GUIDED:
|
||||||
case RTL:
|
case Mode::Number::RTL:
|
||||||
case LAND:
|
case Mode::Number::LAND:
|
||||||
case BRAKE:
|
case Mode::Number::BRAKE:
|
||||||
case LOITER:
|
case Mode::Number::LOITER:
|
||||||
set_mode((control_mode_t)g2.throw_nextmode.get(), MODE_REASON_THROW_COMPLETE);
|
set_mode((Mode::Number)g2.throw_nextmode.get(), MODE_REASON_THROW_COMPLETE);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
// do nothing
|
// do nothing
|
||||||
|
@ -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 == STABILIZE) {
|
if (arming_counter == AUTO_TRIM_DELAY && motors->armed() && control_mode == Mode::Number::STABILIZE) {
|
||||||
auto_trim_counter = 250;
|
auto_trim_counter = 250;
|
||||||
// ensure auto-disarm doesn't trigger immediately
|
// ensure auto-disarm doesn't trigger immediately
|
||||||
auto_disarm_begin = millis();
|
auto_disarm_begin = millis();
|
||||||
@ -88,7 +88,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 == THROW) {
|
if (!motors->armed() || disarm_delay_ms == 0 || control_mode == Mode::Number::THROW) {
|
||||||
auto_disarm_begin = tnow_ms;
|
auto_disarm_begin = tnow_ms;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -146,7 +146,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 == THROW)) {
|
if (ap.in_arming_delay && (!motors->armed() || millis()-arm_time_ms > ARMING_DELAY_SEC*1.0e3f || control_mode == Mode::Number::THROW)) {
|
||||||
ap.in_arming_delay = false;
|
ap.in_arming_delay = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -382,7 +382,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 == THROW) {
|
if(!ap.throttle_zero || control_mode == Mode::Number::THROW) {
|
||||||
set_auto_armed(true);
|
set_auto_armed(true);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -31,14 +31,14 @@ const AP_Param::GroupInfo ToyMode::var_info[] = {
|
|||||||
// @Description: This is the initial mode when the vehicle is first turned on. This mode is assumed to not require GPS
|
// @Description: This is the initial mode when the vehicle is first turned on. This mode is assumed to not require GPS
|
||||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:FlowHold
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:FlowHold
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_MODE1", 2, ToyMode, primary_mode[0], ALT_HOLD),
|
AP_GROUPINFO("_MODE1", 2, ToyMode, primary_mode[0], (float)Mode::Number::ALT_HOLD),
|
||||||
|
|
||||||
// @Param: _MODE2
|
// @Param: _MODE2
|
||||||
// @DisplayName: Tmode second mode
|
// @DisplayName: Tmode second mode
|
||||||
// @Description: This is the secondary mode. This mode is assumed to require GPS
|
// @Description: This is the secondary mode. This mode is assumed to require GPS
|
||||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:FlowHold
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:FlowHold
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_MODE2", 3, ToyMode, primary_mode[1], LOITER),
|
AP_GROUPINFO("_MODE2", 3, ToyMode, primary_mode[1], (float)Mode::Number::LOITER),
|
||||||
|
|
||||||
// @Param: _ACTION1
|
// @Param: _ACTION1
|
||||||
// @DisplayName: Tmode action 1
|
// @DisplayName: Tmode action 1
|
||||||
@ -205,7 +205,7 @@ void ToyMode::update()
|
|||||||
|
|
||||||
if (!done_first_update) {
|
if (!done_first_update) {
|
||||||
done_first_update = true;
|
done_first_update = true;
|
||||||
copter.set_mode(control_mode_t(primary_mode[0].get()), MODE_REASON_TMODE);
|
copter.set_mode(Mode::Number(primary_mode[0].get()), MODE_REASON_TMODE);
|
||||||
copter.motors->set_thrust_compensation_callback(FUNCTOR_BIND_MEMBER(&ToyMode::thrust_limiting, void, float *, uint8_t));
|
copter.motors->set_thrust_compensation_callback(FUNCTOR_BIND_MEMBER(&ToyMode::thrust_limiting, void, float *, uint8_t));
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -424,11 +424,11 @@ 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 == LOITER) {
|
if (!copter.arming.arm(AP_Arming::Method::MAVLINK) && (flags & FLAG_UPGRADE_LOITER) && copter.control_mode == 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
|
||||||
*/
|
*/
|
||||||
if (set_and_remember_mode(ALT_HOLD, MODE_REASON_TMODE)) {
|
if (set_and_remember_mode(Mode::Number::ALT_HOLD, MODE_REASON_TMODE)) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Tmode: ALT_HOLD update arm");
|
gcs().send_text(MAV_SEVERITY_INFO, "Tmode: ALT_HOLD update arm");
|
||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
copter.fence.enable(false);
|
copter.fence.enable(false);
|
||||||
@ -436,7 +436,7 @@ void ToyMode::update()
|
|||||||
if (!copter.arming.arm(AP_Arming::Method::MAVLINK)) {
|
if (!copter.arming.arm(AP_Arming::Method::MAVLINK)) {
|
||||||
// go back to LOITER
|
// go back to LOITER
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: ALT_HOLD arm failed");
|
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: ALT_HOLD arm failed");
|
||||||
set_and_remember_mode(LOITER, MODE_REASON_TMODE);
|
set_and_remember_mode(Mode::Number::LOITER, MODE_REASON_TMODE);
|
||||||
} else {
|
} else {
|
||||||
upgrade_to_loiter = true;
|
upgrade_to_loiter = true;
|
||||||
#if 0
|
#if 0
|
||||||
@ -453,12 +453,12 @@ void ToyMode::update()
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (upgrade_to_loiter) {
|
if (upgrade_to_loiter) {
|
||||||
if (!copter.motors->armed() || copter.control_mode != ALT_HOLD) {
|
if (!copter.motors->armed() || copter.control_mode != 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;
|
||||||
#endif
|
#endif
|
||||||
} else if (copter.position_ok() && set_and_remember_mode(LOITER, MODE_REASON_TMODE)) {
|
} else if (copter.position_ok() && set_and_remember_mode(Mode::Number::LOITER, MODE_REASON_TMODE)) {
|
||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
copter.fence.enable(true);
|
copter.fence.enable(true);
|
||||||
#endif
|
#endif
|
||||||
@ -466,13 +466,13 @@ void ToyMode::update()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (copter.control_mode == RTL && (flags & FLAG_RTL_CANCEL) && throttle_near_max) {
|
if (copter.control_mode == 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(LOITER, MODE_REASON_TMODE);
|
set_and_remember_mode(Mode::Number::LOITER, MODE_REASON_TMODE);
|
||||||
}
|
}
|
||||||
|
|
||||||
enum control_mode_t old_mode = copter.control_mode;
|
enum Mode::Number old_mode = copter.control_mode;
|
||||||
enum control_mode_t new_mode = old_mode;
|
enum Mode::Number new_mode = old_mode;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
implement actions
|
implement actions
|
||||||
@ -491,78 +491,78 @@ void ToyMode::update()
|
|||||||
|
|
||||||
case ACTION_MODE_ACRO:
|
case ACTION_MODE_ACRO:
|
||||||
#if MODE_ACRO_ENABLED == ENABLED
|
#if MODE_ACRO_ENABLED == ENABLED
|
||||||
new_mode = ACRO;
|
new_mode = Mode::Number::ACRO;
|
||||||
#else
|
#else
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: ACRO is disabled");
|
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: ACRO is disabled");
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_ALTHOLD:
|
case ACTION_MODE_ALTHOLD:
|
||||||
new_mode = ALT_HOLD;
|
new_mode = Mode::Number::ALT_HOLD;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_AUTO:
|
case ACTION_MODE_AUTO:
|
||||||
new_mode = AUTO;
|
new_mode = Mode::Number::AUTO;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_LOITER:
|
case ACTION_MODE_LOITER:
|
||||||
new_mode = LOITER;
|
new_mode = Mode::Number::LOITER;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_RTL:
|
case ACTION_MODE_RTL:
|
||||||
new_mode = RTL;
|
new_mode = Mode::Number::RTL;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_CIRCLE:
|
case ACTION_MODE_CIRCLE:
|
||||||
new_mode = CIRCLE;
|
new_mode = Mode::Number::CIRCLE;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_LAND:
|
case ACTION_MODE_LAND:
|
||||||
new_mode = LAND;
|
new_mode = Mode::Number::LAND;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_DRIFT:
|
case ACTION_MODE_DRIFT:
|
||||||
new_mode = DRIFT;
|
new_mode = Mode::Number::DRIFT;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_SPORT:
|
case ACTION_MODE_SPORT:
|
||||||
new_mode = SPORT;
|
new_mode = Mode::Number::SPORT;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_AUTOTUNE:
|
case ACTION_MODE_AUTOTUNE:
|
||||||
new_mode = AUTOTUNE;
|
new_mode = Mode::Number::AUTOTUNE;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_POSHOLD:
|
case ACTION_MODE_POSHOLD:
|
||||||
new_mode = POSHOLD;
|
new_mode = Mode::Number::POSHOLD;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_BRAKE:
|
case ACTION_MODE_BRAKE:
|
||||||
new_mode = BRAKE;
|
new_mode = Mode::Number::BRAKE;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_THROW:
|
case ACTION_MODE_THROW:
|
||||||
#if MODE_THROW_ENABLED == ENABLED
|
#if MODE_THROW_ENABLED == ENABLED
|
||||||
new_mode = THROW;
|
new_mode = Mode::Number::THROW;
|
||||||
#else
|
#else
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: THROW is disabled");
|
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: THROW is disabled");
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_FLIP:
|
case ACTION_MODE_FLIP:
|
||||||
new_mode = FLIP;
|
new_mode = Mode::Number::FLIP;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_STAB:
|
case ACTION_MODE_STAB:
|
||||||
new_mode = STABILIZE;
|
new_mode = Mode::Number::STABILIZE;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_MODE_FLOW:
|
case ACTION_MODE_FLOW:
|
||||||
// toggle flow hold
|
// toggle flow hold
|
||||||
if (old_mode != FLOWHOLD) {
|
if (old_mode != Mode::Number::FLOWHOLD) {
|
||||||
new_mode = FLOWHOLD;
|
new_mode = Mode::Number::FLOWHOLD;
|
||||||
} else {
|
} else {
|
||||||
new_mode = ALT_HOLD;
|
new_mode = Mode::Number::ALT_HOLD;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -575,7 +575,7 @@ void ToyMode::update()
|
|||||||
|
|
||||||
case ACTION_TOGGLE_MODE:
|
case ACTION_TOGGLE_MODE:
|
||||||
last_mode_choice = (last_mode_choice+1) % 2;
|
last_mode_choice = (last_mode_choice+1) % 2;
|
||||||
new_mode = control_mode_t(primary_mode[last_mode_choice].get());
|
new_mode = Mode::Number(primary_mode[last_mode_choice].get());
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ACTION_TOGGLE_SIMPLE:
|
case ACTION_TOGGLE_SIMPLE:
|
||||||
@ -589,24 +589,24 @@ void ToyMode::update()
|
|||||||
case ACTION_ARM_LAND_RTL:
|
case ACTION_ARM_LAND_RTL:
|
||||||
if (!copter.motors->armed()) {
|
if (!copter.motors->armed()) {
|
||||||
action_arm();
|
action_arm();
|
||||||
} else if (old_mode == RTL) {
|
} else if (old_mode == Mode::Number::RTL) {
|
||||||
// switch between RTL and LOITER when in GPS modes
|
// switch between RTL and LOITER when in GPS modes
|
||||||
new_mode = LOITER;
|
new_mode = Mode::Number::LOITER;
|
||||||
} else if (old_mode == LAND) {
|
} else if (old_mode == Mode::Number::LAND) {
|
||||||
if (last_set_mode == LAND || !copter.position_ok()) {
|
if (last_set_mode == Mode::Number::LAND || !copter.position_ok()) {
|
||||||
// this is a land that we asked for, or we don't have good positioning
|
// this is a land that we asked for, or we don't have good positioning
|
||||||
new_mode = ALT_HOLD;
|
new_mode = Mode::Number::ALT_HOLD;
|
||||||
} else if (copter.landing_with_GPS()) {
|
} else if (copter.landing_with_GPS()) {
|
||||||
new_mode = LOITER;
|
new_mode = Mode::Number::LOITER;
|
||||||
} else {
|
} else {
|
||||||
new_mode = ALT_HOLD;
|
new_mode = Mode::Number::ALT_HOLD;
|
||||||
}
|
}
|
||||||
} else if (copter.flightmode->requires_GPS()) {
|
} else if (copter.flightmode->requires_GPS()) {
|
||||||
// if we're in a GPS mode, then RTL
|
// if we're in a GPS mode, then RTL
|
||||||
new_mode = RTL;
|
new_mode = Mode::Number::RTL;
|
||||||
} else {
|
} else {
|
||||||
// if we're in a non-GPS mode, then LAND
|
// if we're in a non-GPS mode, then LAND
|
||||||
new_mode = LAND;
|
new_mode = Mode::Number::LAND;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -619,9 +619,9 @@ void ToyMode::update()
|
|||||||
load_test.running = false;
|
load_test.running = false;
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Tmode: load_test off");
|
gcs().send_text(MAV_SEVERITY_INFO, "Tmode: load_test off");
|
||||||
copter.init_disarm_motors();
|
copter.init_disarm_motors();
|
||||||
copter.set_mode(ALT_HOLD, MODE_REASON_TMODE);
|
copter.set_mode(Mode::Number::ALT_HOLD, MODE_REASON_TMODE);
|
||||||
} else {
|
} else {
|
||||||
copter.set_mode(ALT_HOLD, MODE_REASON_TMODE);
|
copter.set_mode(Mode::Number::ALT_HOLD, MODE_REASON_TMODE);
|
||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
copter.fence.enable(false);
|
copter.fence.enable(false);
|
||||||
#endif
|
#endif
|
||||||
@ -636,9 +636,9 @@ void ToyMode::update()
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!copter.motors->armed() && (copter.control_mode == LAND || copter.control_mode == RTL)) {
|
if (!copter.motors->armed() && (copter.control_mode == Mode::Number::LAND || copter.control_mode == 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 = control_mode_t(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.control_mode) {
|
||||||
@ -656,10 +656,10 @@ void ToyMode::update()
|
|||||||
#endif
|
#endif
|
||||||
} else {
|
} else {
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: %u FAILED", (unsigned)new_mode);
|
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: %u FAILED", (unsigned)new_mode);
|
||||||
if (new_mode == RTL) {
|
if (new_mode == Mode::Number::RTL) {
|
||||||
// if we can't RTL then land
|
// if we can't RTL then land
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: LANDING");
|
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: LANDING");
|
||||||
set_and_remember_mode(LAND, MODE_REASON_TMODE);
|
set_and_remember_mode(Mode::Number::LAND, MODE_REASON_TMODE);
|
||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
if (copter.landing_with_GPS()) {
|
if (copter.landing_with_GPS()) {
|
||||||
copter.fence.enable(true);
|
copter.fence.enable(true);
|
||||||
@ -674,7 +674,7 @@ void ToyMode::update()
|
|||||||
/*
|
/*
|
||||||
set a mode, remembering what mode we set, and the previous mode we were in
|
set a mode, remembering what mode we set, and the previous mode we were in
|
||||||
*/
|
*/
|
||||||
bool ToyMode::set_and_remember_mode(control_mode_t mode, mode_reason_t reason)
|
bool ToyMode::set_and_remember_mode(Mode::Number mode, mode_reason_t reason)
|
||||||
{
|
{
|
||||||
if (copter.control_mode == mode) {
|
if (copter.control_mode == mode) {
|
||||||
return true;
|
return true;
|
||||||
|
@ -38,7 +38,7 @@ private:
|
|||||||
void action_arm(void);
|
void action_arm(void);
|
||||||
void blink_update(void);
|
void blink_update(void);
|
||||||
void send_named_int(const char *name, int32_t value);
|
void send_named_int(const char *name, int32_t value);
|
||||||
bool set_and_remember_mode(control_mode_t mode, mode_reason_t reason);
|
bool set_and_remember_mode(Mode::Number mode, mode_reason_t reason);
|
||||||
|
|
||||||
void thrust_limiting(float *thrust, uint8_t num_motors);
|
void thrust_limiting(float *thrust, uint8_t num_motors);
|
||||||
void arm_check_compass(void);
|
void arm_check_compass(void);
|
||||||
@ -156,7 +156,7 @@ private:
|
|||||||
uint8_t motor_log_counter;
|
uint8_t motor_log_counter;
|
||||||
|
|
||||||
// remember the last mode we set
|
// remember the last mode we set
|
||||||
control_mode_t last_set_mode = LOITER;
|
Mode::Number last_set_mode = Mode::Number::LOITER;
|
||||||
|
|
||||||
struct load_data {
|
struct load_data {
|
||||||
uint16_t m[4];
|
uint16_t m[4];
|
||||||
|
Loading…
Reference in New Issue
Block a user