mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
Sub: do not reset attitude targets between althold<->stabilize
This commit is contained in:
parent
69142b9ec5
commit
41f4beb36f
@ -20,8 +20,10 @@ bool Sub::althold_init()
|
||||
// initialise position and desired velocity
|
||||
pos_control.init_z_controller_stopping_point();
|
||||
|
||||
last_roll = 0;
|
||||
last_pitch = 0;
|
||||
if(prev_control_mode != control_mode_t::STABILIZE) {
|
||||
last_roll = 0;
|
||||
last_pitch = 0;
|
||||
}
|
||||
last_pilot_heading = ahrs.yaw_sensor;
|
||||
last_input_ms = AP_HAL::millis();
|
||||
|
||||
|
@ -5,8 +5,10 @@ bool Sub::stabilize_init()
|
||||
{
|
||||
// set target altitude to zero for reporting
|
||||
pos_control.set_pos_target_z_cm(0);
|
||||
last_roll = 0;
|
||||
last_pitch = 0;
|
||||
if(prev_control_mode != control_mode_t::ALT_HOLD) {
|
||||
last_roll = 0;
|
||||
last_pitch = 0;
|
||||
}
|
||||
last_pilot_heading = ahrs.yaw_sensor;
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user