mirror of https://github.com/ArduPilot/ardupilot
AC_Loiter: init brake_accel and fix brake timer type
This commit is contained in:
parent
7335e4640f
commit
dbc9b0c2f9
|
@ -99,6 +99,7 @@ void AC_Loiter::init_target(const Vector3f& position)
|
|||
_predicted_accel.zero();
|
||||
_desired_accel.zero();
|
||||
_predicted_euler_angle.zero();
|
||||
_brake_accel = 0.0f;
|
||||
|
||||
// set target position
|
||||
_pos_control.set_pos_target_xy_cm(position.x, position.y);
|
||||
|
@ -121,6 +122,7 @@ void AC_Loiter::init_target()
|
|||
_predicted_accel.y = _pos_control.get_accel_target_cmss().y;
|
||||
_predicted_euler_angle.x = radians(_pos_control.get_roll_cd()*0.01f);
|
||||
_predicted_euler_angle.y = radians(_pos_control.get_pitch_cd()*0.01f);
|
||||
_brake_accel = 0.0f;
|
||||
}
|
||||
|
||||
/// reduce response for landing
|
||||
|
|
|
@ -85,6 +85,6 @@ protected:
|
|||
Vector2f _predicted_accel;
|
||||
Vector2f _predicted_euler_angle;
|
||||
Vector2f _predicted_euler_rate;
|
||||
float _brake_timer;
|
||||
float _brake_accel;
|
||||
uint32_t _brake_timer; // system time that brake was initiated
|
||||
float _brake_accel; // acceleration due to braking from previous iteration (used for jerk limiting)
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue