2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
2018-11-25 19:47:55 -04:00
|
|
|
#if MODE_FLIP_ENABLED == ENABLED
|
|
|
|
|
2014-01-31 00:54:42 -04:00
|
|
|
/*
|
2016-07-25 15:45:29 -03:00
|
|
|
* Init and run calls for flip flight mode
|
2014-01-31 00:54:42 -04:00
|
|
|
* original implementation in 2010 by Jose Julio
|
|
|
|
* Adapted and updated for AC2 in 2011 by Jason Short
|
|
|
|
*
|
|
|
|
* Controls:
|
2018-06-04 00:06:32 -03:00
|
|
|
* RC7_OPTION - RC12_OPTION parameter must be set to "Flip" (AUXSW_FLIP) which is "2"
|
2014-01-31 00:54:42 -04:00
|
|
|
* Pilot switches to Stabilize, Acro or AltHold flight mode and puts ch7/ch8 switch to ON position
|
2014-04-23 05:08:33 -03:00
|
|
|
* Vehicle will Roll right by default but if roll or pitch stick is held slightly left, forward or back it will flip in that direction
|
2014-01-31 00:54:42 -04:00
|
|
|
* Vehicle should complete the roll within 2.5sec and will then return to the original flight mode it was in before flip was triggered
|
|
|
|
* Pilot may manually exit flip by switching off ch7/ch8 or by moving roll stick to >40deg left or right
|
|
|
|
*
|
|
|
|
* State machine approach:
|
2019-04-08 00:20:47 -03:00
|
|
|
* FlipState::Start (while copter is leaning <45deg) : roll right at 400deg/sec, increase throttle
|
|
|
|
* FlipState::Roll (while copter is between +45deg ~ -90) : roll right at 400deg/sec, reduce throttle
|
|
|
|
* FlipState::Recover (while copter is between -90deg and original target angle) : use earth frame angle controller to return vehicle to original attitude
|
2014-01-31 00:54:42 -04:00
|
|
|
*/
|
|
|
|
|
2019-04-08 00:20:47 -03:00
|
|
|
#define FLIP_THR_INC 0.20f // throttle increase during FlipState::Start stage (under 45deg lean angle)
|
|
|
|
#define FLIP_THR_DEC 0.24f // throttle decrease during FlipState::Roll stage (between 45deg ~ -90deg roll)
|
2014-04-23 02:32:03 -03:00
|
|
|
#define FLIP_ROTATION_RATE 40000 // rotation rate request in centi-degrees / sec (i.e. 400 deg/sec)
|
2014-01-31 00:54:42 -04:00
|
|
|
#define FLIP_TIMEOUT_MS 2500 // timeout after 2.5sec. Vehicle will switch back to original flight mode
|
|
|
|
#define FLIP_RECOVERY_ANGLE 500 // consider successful recovery when roll is back within 5 degrees of original
|
|
|
|
|
|
|
|
#define FLIP_ROLL_RIGHT 1 // used to set flip_dir
|
|
|
|
#define FLIP_ROLL_LEFT -1 // used to set flip_dir
|
|
|
|
|
2014-04-23 02:32:03 -03:00
|
|
|
#define FLIP_PITCH_BACK 1 // used to set flip_dir
|
|
|
|
#define FLIP_PITCH_FORWARD -1 // used to set flip_dir
|
|
|
|
|
2014-01-31 00:54:42 -04:00
|
|
|
// flip_init - initialise flip controller
|
2019-05-09 23:18:49 -03:00
|
|
|
bool ModeFlip::init(bool ignore_checks)
|
2014-01-31 00:54:42 -04:00
|
|
|
{
|
2020-02-10 22:17:19 -04:00
|
|
|
// only allow flip from some flight modes, for example ACRO, Stabilize, AltHold or FlowHold flight modes
|
|
|
|
if (!copter.flightmode->allows_flip()) {
|
2014-01-31 00:54:42 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// if in acro or stabilize ensure throttle is above zero
|
2020-01-30 03:29:36 -04:00
|
|
|
if (copter.ap.throttle_zero && (copter.flightmode->mode_number() == Mode::Number::ACRO || copter.flightmode->mode_number() == Mode::Number::STABILIZE)) {
|
2014-01-31 00:54:42 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// ensure roll input is less than 40deg
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
if (abs(channel_roll->get_control_in()) >= 4000) {
|
2014-01-31 00:54:42 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// only allow flip when flying
|
2019-05-09 23:18:49 -03:00
|
|
|
if (!motors->armed() || copter.ap.land_complete) {
|
2014-01-31 00:54:42 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// capture original flight mode so that we can return to it after completion
|
2020-01-30 03:29:36 -04:00
|
|
|
orig_control_mode = copter.flightmode->mode_number();
|
2014-01-31 00:54:42 -04:00
|
|
|
|
|
|
|
// initialise state
|
2019-04-08 00:20:47 -03:00
|
|
|
_state = FlipState::Start;
|
2019-02-02 00:19:03 -04:00
|
|
|
start_time_ms = millis();
|
2014-04-23 05:08:33 -03:00
|
|
|
|
2019-02-02 00:19:03 -04:00
|
|
|
roll_dir = pitch_dir = 0;
|
2014-04-23 02:32:03 -03:00
|
|
|
|
|
|
|
// choose direction based on pilot's roll and pitch sticks
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
if (channel_pitch->get_control_in() > 300) {
|
2019-02-02 00:19:03 -04:00
|
|
|
pitch_dir = FLIP_PITCH_BACK;
|
2018-03-21 08:16:18 -03:00
|
|
|
} else if (channel_pitch->get_control_in() < -300) {
|
2019-02-02 00:19:03 -04:00
|
|
|
pitch_dir = FLIP_PITCH_FORWARD;
|
2018-03-21 08:16:18 -03:00
|
|
|
} else if (channel_roll->get_control_in() >= 0) {
|
2019-02-02 00:19:03 -04:00
|
|
|
roll_dir = FLIP_ROLL_RIGHT;
|
2018-03-21 08:16:18 -03:00
|
|
|
} else {
|
2019-02-02 00:19:03 -04:00
|
|
|
roll_dir = FLIP_ROLL_LEFT;
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// log start of flip
|
2019-10-25 03:06:05 -03:00
|
|
|
AP::logger().Write_Event(LogEvent::FLIP_START);
|
2014-01-31 00:54:42 -04:00
|
|
|
|
2019-04-08 00:20:47 -03:00
|
|
|
// capture current attitude which will be used during the FlipState::Recovery stage
|
2019-02-02 00:19:03 -04:00
|
|
|
const float angle_max = copter.aparm.angle_max;
|
|
|
|
orig_attitude.x = constrain_float(ahrs.roll_sensor, -angle_max, angle_max);
|
|
|
|
orig_attitude.y = constrain_float(ahrs.pitch_sensor, -angle_max, angle_max);
|
|
|
|
orig_attitude.z = ahrs.yaw_sensor;
|
2014-01-31 00:54:42 -04:00
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2019-02-02 00:19:03 -04:00
|
|
|
// run - runs the flip controller
|
2014-01-31 00:54:42 -04:00
|
|
|
// should be called at 100hz or more
|
2019-05-09 23:18:49 -03:00
|
|
|
void ModeFlip::run()
|
2014-01-31 00:54:42 -04:00
|
|
|
{
|
|
|
|
// if pilot inputs roll > 40deg or timeout occurs abandon flip
|
2019-02-02 00:19:03 -04:00
|
|
|
if (!motors->armed() || (abs(channel_roll->get_control_in()) >= 4000) || (abs(channel_pitch->get_control_in()) >= 4000) || ((millis() - start_time_ms) > FLIP_TIMEOUT_MS)) {
|
2019-04-08 00:20:47 -03:00
|
|
|
_state = FlipState::Abandon;
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// get pilot's desired throttle
|
2019-03-06 02:36:32 -04:00
|
|
|
float throttle_out = get_pilot_desired_throttle();
|
2014-01-31 00:54:42 -04:00
|
|
|
|
2019-02-28 05:03:23 -04:00
|
|
|
// set motors to full range
|
2019-04-09 09:16:58 -03:00
|
|
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
2019-02-28 05:03:23 -04:00
|
|
|
|
2014-04-23 02:32:03 -03:00
|
|
|
// get corrected angle based on direction and axis of rotation
|
|
|
|
// we flip the sign of flip_angle to minimize the code repetition
|
|
|
|
int32_t flip_angle;
|
|
|
|
|
2019-02-02 00:19:03 -04:00
|
|
|
if (roll_dir != 0) {
|
|
|
|
flip_angle = ahrs.roll_sensor * roll_dir;
|
2014-04-23 02:32:03 -03:00
|
|
|
} else {
|
2019-02-02 00:19:03 -04:00
|
|
|
flip_angle = ahrs.pitch_sensor * pitch_dir;
|
2014-04-23 02:32:03 -03:00
|
|
|
}
|
2014-01-31 00:54:42 -04:00
|
|
|
|
|
|
|
// state machine
|
2019-02-02 00:19:03 -04:00
|
|
|
switch (_state) {
|
2014-01-31 00:54:42 -04:00
|
|
|
|
2019-04-08 00:20:47 -03:00
|
|
|
case FlipState::Start:
|
2014-04-23 02:32:03 -03:00
|
|
|
// under 45 degrees request 400deg/sec roll or pitch
|
2019-02-02 00:19:03 -04:00
|
|
|
attitude_control->input_rate_bf_roll_pitch_yaw(FLIP_ROTATION_RATE * roll_dir, FLIP_ROTATION_RATE * pitch_dir, 0.0);
|
2014-04-23 02:32:03 -03:00
|
|
|
|
2014-01-31 00:54:42 -04:00
|
|
|
// increase throttle
|
|
|
|
throttle_out += FLIP_THR_INC;
|
2014-04-23 02:32:03 -03:00
|
|
|
|
2014-01-31 00:54:42 -04:00
|
|
|
// beyond 45deg lean angle move to next stage
|
2014-04-23 02:32:03 -03:00
|
|
|
if (flip_angle >= 4500) {
|
2019-02-02 00:19:03 -04:00
|
|
|
if (roll_dir != 0) {
|
2014-04-23 02:32:03 -03:00
|
|
|
// we are rolling
|
2019-04-08 00:20:47 -03:00
|
|
|
_state = FlipState::Roll;
|
2014-04-23 02:32:03 -03:00
|
|
|
} else {
|
|
|
|
// we are pitching
|
2019-04-08 00:20:47 -03:00
|
|
|
_state = FlipState::Pitch_A;
|
2014-04-23 02:32:03 -03:00
|
|
|
}
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2019-04-08 00:20:47 -03:00
|
|
|
case FlipState::Roll:
|
2014-01-31 00:54:42 -04:00
|
|
|
// between 45deg ~ -90deg request 400deg/sec roll
|
2019-02-02 00:19:03 -04:00
|
|
|
attitude_control->input_rate_bf_roll_pitch_yaw(FLIP_ROTATION_RATE * roll_dir, 0.0, 0.0);
|
2014-01-31 00:54:42 -04:00
|
|
|
// decrease throttle
|
2016-05-23 03:35:13 -03:00
|
|
|
throttle_out = MAX(throttle_out - FLIP_THR_DEC, 0.0f);
|
2014-04-23 02:32:03 -03:00
|
|
|
|
2014-01-31 00:54:42 -04:00
|
|
|
// beyond -90deg move on to recovery
|
2014-04-23 02:32:03 -03:00
|
|
|
if ((flip_angle < 4500) && (flip_angle > -9000)) {
|
2019-04-08 00:20:47 -03:00
|
|
|
_state = FlipState::Recover;
|
2014-04-23 02:32:03 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2019-04-08 00:20:47 -03:00
|
|
|
case FlipState::Pitch_A:
|
2014-04-23 02:32:03 -03:00
|
|
|
// between 45deg ~ -90deg request 400deg/sec pitch
|
2019-02-02 00:19:03 -04:00
|
|
|
attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, FLIP_ROTATION_RATE * pitch_dir, 0.0);
|
2014-04-23 02:32:03 -03:00
|
|
|
// decrease throttle
|
2016-05-23 03:35:13 -03:00
|
|
|
throttle_out = MAX(throttle_out - FLIP_THR_DEC, 0.0f);
|
2014-04-23 02:32:03 -03:00
|
|
|
|
|
|
|
// check roll for inversion
|
|
|
|
if ((labs(ahrs.roll_sensor) > 9000) && (flip_angle > 4500)) {
|
2019-04-08 00:20:47 -03:00
|
|
|
_state = FlipState::Pitch_B;
|
2014-04-23 02:32:03 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2019-04-08 00:20:47 -03:00
|
|
|
case FlipState::Pitch_B:
|
2014-04-23 02:32:03 -03:00
|
|
|
// between 45deg ~ -90deg request 400deg/sec pitch
|
2019-02-02 00:19:03 -04:00
|
|
|
attitude_control->input_rate_bf_roll_pitch_yaw(0.0, FLIP_ROTATION_RATE * pitch_dir, 0.0);
|
2014-04-23 02:32:03 -03:00
|
|
|
// decrease throttle
|
2016-05-23 03:35:13 -03:00
|
|
|
throttle_out = MAX(throttle_out - FLIP_THR_DEC, 0.0f);
|
2014-04-23 02:32:03 -03:00
|
|
|
|
|
|
|
// check roll for inversion
|
|
|
|
if ((labs(ahrs.roll_sensor) < 9000) && (flip_angle > -4500)) {
|
2019-04-08 00:20:47 -03:00
|
|
|
_state = FlipState::Recover;
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2019-04-08 00:20:47 -03:00
|
|
|
case FlipState::Recover: {
|
2014-01-31 00:54:42 -04:00
|
|
|
// use originally captured earth-frame angle targets to recover
|
2019-02-02 00:19:03 -04:00
|
|
|
attitude_control->input_euler_angle_roll_pitch_yaw(orig_attitude.x, orig_attitude.y, orig_attitude.z, false);
|
2014-01-31 00:54:42 -04:00
|
|
|
|
2014-04-23 02:32:03 -03:00
|
|
|
// increase throttle to gain any lost altitude
|
2014-01-31 00:54:42 -04:00
|
|
|
throttle_out += FLIP_THR_INC;
|
|
|
|
|
2019-02-02 00:19:03 -04:00
|
|
|
float recovery_angle;
|
|
|
|
if (roll_dir != 0) {
|
2014-04-23 02:32:03 -03:00
|
|
|
// we are rolling
|
2019-02-02 00:19:03 -04:00
|
|
|
recovery_angle = fabsf(orig_attitude.x - (float)ahrs.roll_sensor);
|
2014-04-23 02:32:03 -03:00
|
|
|
} else {
|
|
|
|
// we are pitching
|
2019-02-02 00:19:03 -04:00
|
|
|
recovery_angle = fabsf(orig_attitude.y - (float)ahrs.pitch_sensor);
|
2014-04-23 02:32:03 -03:00
|
|
|
}
|
|
|
|
|
2014-01-31 00:54:42 -04:00
|
|
|
// check for successful recovery
|
2015-05-08 15:40:08 -03:00
|
|
|
if (fabsf(recovery_angle) <= FLIP_RECOVERY_ANGLE) {
|
2014-01-31 00:54:42 -04:00
|
|
|
// restore original flight mode
|
2019-10-17 00:49:22 -03:00
|
|
|
if (!copter.set_mode(orig_control_mode, ModeReason::FLIP_COMPLETE)) {
|
2014-01-31 00:54:42 -04:00
|
|
|
// this should never happen but just in case
|
2019-10-17 00:49:22 -03:00
|
|
|
copter.set_mode(Mode::Number::STABILIZE, ModeReason::UNKNOWN);
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|
|
|
|
// log successful completion
|
2019-10-25 03:06:05 -03:00
|
|
|
AP::logger().Write_Event(LogEvent::FLIP_END);
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|
|
|
|
break;
|
2019-11-03 22:54:47 -04:00
|
|
|
|
2019-02-02 00:19:03 -04:00
|
|
|
}
|
2019-04-08 00:20:47 -03:00
|
|
|
case FlipState::Abandon:
|
2014-01-31 00:54:42 -04:00
|
|
|
// restore original flight mode
|
2019-10-17 00:49:22 -03:00
|
|
|
if (!copter.set_mode(orig_control_mode, ModeReason::FLIP_COMPLETE)) {
|
2014-01-31 00:54:42 -04:00
|
|
|
// this should never happen but just in case
|
2019-10-17 00:49:22 -03:00
|
|
|
copter.set_mode(Mode::Number::STABILIZE, ModeReason::UNKNOWN);
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|
|
|
|
// log abandoning flip
|
2019-03-24 22:31:46 -03:00
|
|
|
AP::logger().Write_Error(LogErrorSubsystem::FLIP, LogErrorCode::FLIP_ABANDONED);
|
2014-01-31 00:54:42 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// output pilot's throttle without angle boost
|
2017-01-09 03:31:26 -04:00
|
|
|
attitude_control->set_throttle_out(throttle_out, false, g.throttle_filt);
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|
2018-11-25 19:47:55 -04:00
|
|
|
|
|
|
|
#endif
|