2014-01-31 00:54:42 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
2014-01-31 00:54:42 -04:00
|
|
|
/*
|
|
|
|
* control_flip.pde - init and run calls for flip flight mode
|
|
|
|
* original implementation in 2010 by Jose Julio
|
|
|
|
* Adapted and updated for AC2 in 2011 by Jason Short
|
|
|
|
*
|
|
|
|
* Controls:
|
2015-03-10 17:32:25 -03:00
|
|
|
* CH7_OPT - CH12_OPT 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:
|
|
|
|
* Flip_Start (while copter is leaning <45deg) : roll right at 400deg/sec, increase throttle
|
|
|
|
* Flip_Roll (while copter is between +45deg ~ -90) : roll right at 400deg/sec, reduce throttle
|
|
|
|
* Flip_Recover (while copter is between -90deg and original target angle) : use earth frame angle controller to return vehicle to original attitude
|
|
|
|
*/
|
|
|
|
|
2016-05-23 03:35:13 -03:00
|
|
|
#define FLIP_THR_INC 0.20f // throttle increase during Flip_Start stage (under 45deg lean angle)
|
|
|
|
#define FLIP_THR_DEC 0.24f // throttle decrease during Flip_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
|
|
|
FlipState flip_state; // current state of flip
|
2016-01-25 17:26:20 -04:00
|
|
|
control_mode_t flip_orig_control_mode; // flight mode when flip was initated
|
2014-01-31 00:54:42 -04:00
|
|
|
uint32_t flip_start_time; // time since flip began
|
2014-04-23 02:32:03 -03:00
|
|
|
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)
|
2014-01-31 00:54:42 -04:00
|
|
|
|
|
|
|
// flip_init - initialise flip controller
|
2015-05-29 23:12:49 -03:00
|
|
|
bool Copter::flip_init(bool ignore_checks)
|
2014-01-31 00:54:42 -04:00
|
|
|
{
|
|
|
|
// only allow flip from ACRO, Stabilize, AltHold or Drift flight modes
|
|
|
|
if (control_mode != ACRO && control_mode != STABILIZE && control_mode != ALT_HOLD) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// if in acro or stabilize ensure throttle is above zero
|
2015-03-13 16:38:23 -03:00
|
|
|
if (ap.throttle_zero && (control_mode == ACRO || control_mode == 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
|
|
|
|
if (!motors.armed() || ap.land_complete) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// capture original flight mode so that we can return to it after completion
|
|
|
|
flip_orig_control_mode = control_mode;
|
|
|
|
|
|
|
|
// initialise state
|
|
|
|
flip_state = Flip_Start;
|
|
|
|
flip_start_time = millis();
|
2014-04-23 05:08:33 -03:00
|
|
|
|
2014-04-23 02:32:03 -03:00
|
|
|
flip_roll_dir = flip_pitch_dir = 0;
|
|
|
|
|
|
|
|
// 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) {
|
2014-04-23 02:32:03 -03:00
|
|
|
flip_pitch_dir = FLIP_PITCH_BACK;
|
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
|
|
|
}else if(channel_pitch->get_control_in() < -300) {
|
2014-04-23 02:32:03 -03:00
|
|
|
flip_pitch_dir = FLIP_PITCH_FORWARD;
|
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
|
|
|
}else if (channel_roll->get_control_in() >= 0) {
|
2014-04-23 05:08:33 -03:00
|
|
|
flip_roll_dir = FLIP_ROLL_RIGHT;
|
2014-04-23 02:32:03 -03:00
|
|
|
}else{
|
2014-04-23 05:08:33 -03:00
|
|
|
flip_roll_dir = FLIP_ROLL_LEFT;
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// log start of flip
|
|
|
|
Log_Write_Event(DATA_FLIP_START);
|
|
|
|
|
2014-06-06 00:07:23 -03:00
|
|
|
// capture current attitude which will be used during the Flip_Recovery stage
|
|
|
|
flip_orig_attitude.x = constrain_float(ahrs.roll_sensor, -aparm.angle_max, aparm.angle_max);
|
|
|
|
flip_orig_attitude.y = constrain_float(ahrs.pitch_sensor, -aparm.angle_max, aparm.angle_max);
|
|
|
|
flip_orig_attitude.z = ahrs.yaw_sensor;
|
2014-01-31 00:54:42 -04:00
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// flip_run - runs the flip controller
|
|
|
|
// should be called at 100hz or more
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::flip_run()
|
2014-01-31 00:54:42 -04:00
|
|
|
{
|
2016-01-18 01:36:56 -04:00
|
|
|
float throttle_out;
|
2014-04-23 02:32:03 -03:00
|
|
|
float recovery_angle;
|
2014-01-31 00:54:42 -04:00
|
|
|
|
|
|
|
// if pilot inputs roll > 40deg or timeout occurs abandon flip
|
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 (!motors.armed() || (abs(channel_roll->get_control_in()) >= 4000) || (abs(channel_pitch->get_control_in()) >= 4000) || ((millis() - flip_start_time) > FLIP_TIMEOUT_MS)) {
|
2014-01-31 00:54:42 -04:00
|
|
|
flip_state = Flip_Abandon;
|
|
|
|
}
|
|
|
|
|
|
|
|
// get pilot's desired throttle
|
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
|
|
|
throttle_out = get_pilot_desired_throttle(channel_throttle->get_control_in());
|
2014-01-31 00:54:42 -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;
|
|
|
|
|
|
|
|
if (flip_roll_dir != 0) {
|
|
|
|
flip_angle = ahrs.roll_sensor * flip_roll_dir;
|
|
|
|
} else {
|
|
|
|
flip_angle = ahrs.pitch_sensor * flip_pitch_dir;
|
|
|
|
}
|
2014-01-31 00:54:42 -04:00
|
|
|
|
|
|
|
// state machine
|
|
|
|
switch (flip_state) {
|
|
|
|
|
|
|
|
case Flip_Start:
|
2014-04-23 02:32:03 -03:00
|
|
|
// under 45 degrees request 400deg/sec roll or pitch
|
2015-11-28 13:57:14 -04:00
|
|
|
attitude_control.input_rate_bf_roll_pitch_yaw(FLIP_ROTATION_RATE * flip_roll_dir, FLIP_ROTATION_RATE * flip_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) {
|
|
|
|
if (flip_roll_dir != 0) {
|
|
|
|
// we are rolling
|
2014-01-31 00:54:42 -04:00
|
|
|
flip_state = Flip_Roll;
|
2014-04-23 02:32:03 -03:00
|
|
|
} else {
|
|
|
|
// we are pitching
|
|
|
|
flip_state = Flip_Pitch_A;
|
|
|
|
}
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case Flip_Roll:
|
|
|
|
// between 45deg ~ -90deg request 400deg/sec roll
|
2015-11-28 13:57:14 -04:00
|
|
|
attitude_control.input_rate_bf_roll_pitch_yaw(FLIP_ROTATION_RATE * flip_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)) {
|
|
|
|
flip_state = Flip_Recover;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case Flip_Pitch_A:
|
|
|
|
// between 45deg ~ -90deg request 400deg/sec pitch
|
2016-05-23 03:35:13 -03:00
|
|
|
attitude_control.input_rate_bf_roll_pitch_yaw(0.0f, FLIP_ROTATION_RATE * flip_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)) {
|
|
|
|
flip_state = Flip_Pitch_B;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case Flip_Pitch_B:
|
|
|
|
// between 45deg ~ -90deg request 400deg/sec pitch
|
2015-11-28 13:57:14 -04:00
|
|
|
attitude_control.input_rate_bf_roll_pitch_yaw(0.0, FLIP_ROTATION_RATE * flip_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)) {
|
2014-01-31 00:54:42 -04:00
|
|
|
flip_state = Flip_Recover;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case Flip_Recover:
|
|
|
|
// use originally captured earth-frame angle targets to recover
|
2016-06-16 23:47:59 -03:00
|
|
|
attitude_control.input_euler_angle_roll_pitch_yaw(flip_orig_attitude.x, flip_orig_attitude.y, flip_orig_attitude.z, false, get_smoothing_gain());
|
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;
|
|
|
|
|
2014-04-23 02:32:03 -03:00
|
|
|
if (flip_roll_dir != 0) {
|
|
|
|
// we are rolling
|
2015-05-08 15:40:08 -03:00
|
|
|
recovery_angle = fabsf(flip_orig_attitude.x - (float)ahrs.roll_sensor);
|
2014-04-23 02:32:03 -03:00
|
|
|
} else {
|
|
|
|
// we are pitching
|
2015-05-08 15:40:08 -03:00
|
|
|
recovery_angle = fabsf(flip_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
|
2016-05-25 04:15:18 -03:00
|
|
|
if (!set_mode(flip_orig_control_mode, MODE_REASON_FLIP_COMPLETE)) {
|
2014-01-31 00:54:42 -04:00
|
|
|
// this should never happen but just in case
|
2016-01-25 19:40:41 -04:00
|
|
|
set_mode(STABILIZE, MODE_REASON_UNKNOWN);
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|
|
|
|
// log successful completion
|
|
|
|
Log_Write_Event(DATA_FLIP_END);
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case Flip_Abandon:
|
|
|
|
// restore original flight mode
|
2016-05-25 04:15:18 -03:00
|
|
|
if (!set_mode(flip_orig_control_mode, MODE_REASON_FLIP_COMPLETE)) {
|
2014-01-31 00:54:42 -04:00
|
|
|
// this should never happen but just in case
|
2016-01-25 19:40:41 -04:00
|
|
|
set_mode(STABILIZE, MODE_REASON_UNKNOWN);
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|
|
|
|
// log abandoning flip
|
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_FLIP,ERROR_CODE_FLIP_ABANDONED);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2016-01-18 01:36:56 -04:00
|
|
|
// set motors to full range
|
2016-02-02 08:19:05 -04:00
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
2016-01-18 01:36:56 -04:00
|
|
|
|
2014-01-31 00:54:42 -04:00
|
|
|
// output pilot's throttle without angle boost
|
2016-05-23 03:35:13 -03:00
|
|
|
attitude_control.set_throttle_out(throttle_out, false, g.throttle_filt);
|
2014-01-31 00:54:42 -04:00
|
|
|
}
|