mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
Added Jose Julio's Flip code, edited to work with AC2. Never flown or tested!
git-svn-id: https://arducopter.googlecode.com/svn/trunk@3020 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
a78b057cec
commit
10e2eb3571
@ -345,6 +345,11 @@ static float sin_pitch_y, sin_yaw_y, sin_roll_y;
|
|||||||
static bool simple_bearing_is_set = false;
|
static bool simple_bearing_is_set = false;
|
||||||
static long initial_simple_bearing; // used for Simple mode
|
static long initial_simple_bearing; // used for Simple mode
|
||||||
|
|
||||||
|
// Acro
|
||||||
|
#if CH7_OPTION == DO_FLIP
|
||||||
|
static bool do_flip = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
// Airspeed
|
// Airspeed
|
||||||
// --------
|
// --------
|
||||||
static int airspeed; // m/s * 100
|
static int airspeed; // m/s * 100
|
||||||
@ -1086,6 +1091,13 @@ void update_location(void)
|
|||||||
|
|
||||||
void update_current_flight_mode(void)
|
void update_current_flight_mode(void)
|
||||||
{
|
{
|
||||||
|
#if CH7_OPTION == DO_FLIP
|
||||||
|
if (do_flip){
|
||||||
|
roll_flip();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if(control_mode == AUTO){
|
if(control_mode == AUTO){
|
||||||
|
|
||||||
// this is a hack to prevent run up of the throttle I term for alt hold
|
// this is a hack to prevent run up of the throttle I term for alt hold
|
||||||
|
Loading…
Reference in New Issue
Block a user