mirror of https://github.com/ArduPilot/ardupilot
Copter: use enum type for control_mode
This commit is contained in:
parent
16b3fe75d1
commit
a0ce8af633
|
@ -246,7 +246,7 @@ private:
|
|||
|
||||
// This is the state of the flight control system
|
||||
// There are multiple states defined such as STABILIZE, ACRO,
|
||||
int8_t control_mode;
|
||||
control_mode_t control_mode;
|
||||
|
||||
// Structure used to detect changes in the flight mode control switch
|
||||
struct {
|
||||
|
@ -852,13 +852,14 @@ private:
|
|||
void failsafe_disable();
|
||||
void fence_check();
|
||||
void fence_send_mavlink_status(mavlink_channel_t chan);
|
||||
bool set_mode(uint8_t mode);
|
||||
bool set_mode(control_mode_t mode);
|
||||
bool gcs_set_mode(uint8_t mode) { return set_mode((control_mode_t)mode); }
|
||||
void update_flight_mode();
|
||||
void exit_mode(uint8_t old_control_mode, uint8_t new_control_mode);
|
||||
bool mode_requires_GPS(uint8_t mode);
|
||||
bool mode_has_manual_throttle(uint8_t mode);
|
||||
bool mode_allows_arming(uint8_t mode, bool arming_from_gcs);
|
||||
void notify_flight_mode(uint8_t mode);
|
||||
void exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode);
|
||||
bool mode_requires_GPS(control_mode_t mode);
|
||||
bool mode_has_manual_throttle(control_mode_t mode);
|
||||
bool mode_allows_arming(control_mode_t mode, bool arming_from_gcs);
|
||||
void notify_flight_mode(control_mode_t mode);
|
||||
void heli_init();
|
||||
void check_dynamic_flight(void);
|
||||
void update_heli_control_dynamics(void);
|
||||
|
|
|
@ -59,6 +59,8 @@ NOINLINE void Copter::send_heartbeat(mavlink_channel_t chan)
|
|||
// APM does in any mode, as that is defined as "system finds its own goal
|
||||
// positions", which APM does not currently do
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
// all modes except INITIALISING have some form of manual
|
||||
|
@ -173,6 +175,8 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
|
|||
case SPORT:
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
// set motors outputs as enabled if safety switch is not disarmed (i.e. either NONE or ARMED)
|
||||
|
@ -1008,13 +1012,13 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
{
|
||||
#ifdef DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE
|
||||
if (!copter.failsafe.radio) {
|
||||
handle_set_mode(msg, FUNCTOR_BIND(&copter, &Copter::set_mode, bool, uint8_t));
|
||||
handle_set_mode(msg, FUNCTOR_BIND(&copter, &Copter::gcs_set_mode, bool, uint8_t));
|
||||
} else {
|
||||
// don't allow mode changes while in radio failsafe
|
||||
mavlink_msg_command_ack_send_buf(msg, chan, MAVLINK_MSG_ID_SET_MODE, MAV_RESULT_FAILED);
|
||||
}
|
||||
#else
|
||||
handle_set_mode(msg, FUNCTOR_BIND(&copter, &Copter::set_mode, bool, uint8_t));
|
||||
handle_set_mode(msg, FUNCTOR_BIND(&copter, &Copter::gcs_set_mode, bool, uint8_t));
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
#define FLIP_PITCH_FORWARD -1 // used to set flip_dir
|
||||
|
||||
FlipState flip_state; // current state of flip
|
||||
uint8_t flip_orig_control_mode; // flight mode when flip was initated
|
||||
control_mode_t flip_orig_control_mode; // flight mode when flip was initated
|
||||
uint32_t flip_start_time; // time since flip began
|
||||
int8_t flip_roll_dir; // roll direction (-1 = roll left, 1 = roll right)
|
||||
int8_t flip_pitch_dir; // pitch direction (-1 = pitch forward, 1 = pitch back)
|
||||
|
|
|
@ -87,7 +87,7 @@ enum aux_sw_func {
|
|||
#define HIL_MODE_SENSORS 1
|
||||
|
||||
// Auto Pilot Modes enumeration
|
||||
enum autopilot_modes {
|
||||
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
|
||||
|
|
|
@ -11,7 +11,7 @@
|
|||
// optional force parameter used to force the flight mode change (used only first time mode is set)
|
||||
// returns true if mode was succesfully 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
|
||||
bool Copter::set_mode(uint8_t mode)
|
||||
bool Copter::set_mode(control_mode_t mode)
|
||||
{
|
||||
// boolean to record if flight mode could be set
|
||||
bool success = false;
|
||||
|
@ -107,8 +107,8 @@ bool Copter::set_mode(uint8_t mode)
|
|||
// update flight mode
|
||||
if (success) {
|
||||
// perform any cleanup required by previous flight mode
|
||||
exit_mode(control_mode, mode);
|
||||
control_mode = mode;
|
||||
exit_mode(control_mode, (control_mode_t)mode);
|
||||
control_mode = (control_mode_t)mode;
|
||||
DataFlash.Log_Write_Mode(control_mode);
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
|
@ -218,7 +218,7 @@ void Copter::update_flight_mode()
|
|||
}
|
||||
|
||||
// exit_mode - high level call to organise cleanup as a flight mode is exited
|
||||
void Copter::exit_mode(uint8_t old_control_mode, uint8_t new_control_mode)
|
||||
void Copter::exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode)
|
||||
{
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
if (old_control_mode == AUTOTUNE) {
|
||||
|
@ -270,7 +270,7 @@ void Copter::exit_mode(uint8_t old_control_mode, uint8_t new_control_mode)
|
|||
}
|
||||
|
||||
// returns true or false whether mode requires GPS
|
||||
bool Copter::mode_requires_GPS(uint8_t mode) {
|
||||
bool Copter::mode_requires_GPS(control_mode_t mode) {
|
||||
switch(mode) {
|
||||
case AUTO:
|
||||
case GUIDED:
|
||||
|
@ -290,7 +290,7 @@ bool Copter::mode_requires_GPS(uint8_t mode) {
|
|||
}
|
||||
|
||||
// mode_has_manual_throttle - returns true if the flight mode has a manual throttle (i.e. pilot directly controls throttle)
|
||||
bool Copter::mode_has_manual_throttle(uint8_t mode) {
|
||||
bool Copter::mode_has_manual_throttle(control_mode_t mode) {
|
||||
switch(mode) {
|
||||
case ACRO:
|
||||
case STABILIZE:
|
||||
|
@ -304,7 +304,7 @@ bool Copter::mode_has_manual_throttle(uint8_t mode) {
|
|||
|
||||
// mode_allows_arming - returns true if vehicle can be armed in the specified mode
|
||||
// arming_from_gcs should be set to true if the arming request comes from the ground station
|
||||
bool Copter::mode_allows_arming(uint8_t mode, bool arming_from_gcs) {
|
||||
bool Copter::mode_allows_arming(control_mode_t mode, bool arming_from_gcs) {
|
||||
if (mode_has_manual_throttle(mode) || mode == LOITER || mode == ALT_HOLD || mode == POSHOLD || mode == DRIFT || mode == SPORT || mode == THROW || (arming_from_gcs && mode == GUIDED)) {
|
||||
return true;
|
||||
}
|
||||
|
@ -312,7 +312,7 @@ bool Copter::mode_allows_arming(uint8_t mode, bool arming_from_gcs) {
|
|||
}
|
||||
|
||||
// notify_flight_mode - sets notify object based on flight mode. Only used for OreoLED notify device
|
||||
void Copter::notify_flight_mode(uint8_t mode) {
|
||||
void Copter::notify_flight_mode(control_mode_t mode) {
|
||||
switch(mode) {
|
||||
case AUTO:
|
||||
case GUIDED:
|
||||
|
|
|
@ -359,7 +359,7 @@ void Copter::report_flight_modes()
|
|||
print_divider();
|
||||
|
||||
for(int16_t i = 0; i < 6; i++ ) {
|
||||
print_switch(i, flight_modes[i], BIT_IS_SET(g.simple_modes, i));
|
||||
print_switch(i, (control_mode_t)flight_modes[i].get(), BIT_IS_SET(g.simple_modes, i));
|
||||
}
|
||||
print_blanks(2);
|
||||
}
|
||||
|
|
|
@ -43,7 +43,7 @@ void Copter::read_control_switch()
|
|||
|
||||
if (control_switch_changed && sufficient_time_elapsed && failsafe_disengaged) {
|
||||
// set flight mode and simple mode setting
|
||||
if (set_mode(flight_modes[switch_position])) {
|
||||
if (set_mode((control_mode_t)flight_modes[switch_position].get())) {
|
||||
// play a tone
|
||||
if (control_switch_state.debounced_switch_position != -1) {
|
||||
// alert user to mode change failure (except if autopilot is just starting up)
|
||||
|
|
|
@ -48,6 +48,8 @@ bool Copter::do_user_takeoff(float takeoff_alt_cm, bool must_navigate)
|
|||
set_auto_armed(true);
|
||||
takeoff_timer_start(takeoff_alt_cm);
|
||||
return true;
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
|
|
Loading…
Reference in New Issue