mirror of https://github.com/ArduPilot/ardupilot
changed yaw reset to when armed to not use initial_simple_bearing
This commit is contained in:
parent
79bd8b4fd0
commit
4c6d6ea96e
|
@ -535,6 +535,10 @@ static float sin_pitch;
|
|||
// or in SuperSimple mode when the copter leaves a 20m radius from home.
|
||||
static int32_t initial_simple_bearing;
|
||||
|
||||
// Stores initial bearing when armed - initial simple bearing is modified in super simple mode so not suitable
|
||||
static int32_t initial_armed_bearing;
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Rate contoller targets
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -1523,7 +1527,7 @@ void update_yaw_mode(void)
|
|||
|
||||
case YAW_RESETTOARMEDYAW:
|
||||
// changes yaw to be same as when quad was armed
|
||||
nav_yaw = get_yaw_slew(nav_yaw, initial_simple_bearing, AUTO_YAW_SLEW_RATE);
|
||||
nav_yaw = get_yaw_slew(nav_yaw, initial_armed_bearing, AUTO_YAW_SLEW_RATE);
|
||||
get_stabilize_yaw(nav_yaw);
|
||||
|
||||
// if there is any pilot input, switch to YAW_HOLD mode for the next iteration
|
||||
|
|
|
@ -136,6 +136,8 @@ static void init_arm_motors()
|
|||
// --------------------
|
||||
init_simple_bearing();
|
||||
|
||||
initial_armed_bearing = ahrs.yaw_sensor;
|
||||
|
||||
// Reset home position
|
||||
// -------------------
|
||||
if(ap.home_is_set)
|
||||
|
|
Loading…
Reference in New Issue