mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AC_WPNav: remove pointless initialisations
new clears this memory
This commit is contained in:
parent
fa0b315374
commit
4c8c85f75b
@ -78,21 +78,7 @@ AC_WPNav::AC_WPNav(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosC
|
||||
_inav(inav),
|
||||
_ahrs(ahrs),
|
||||
_pos_control(pos_control),
|
||||
_attitude_control(attitude_control),
|
||||
_wp_last_update(0),
|
||||
_wp_step(0),
|
||||
_track_length(0.0f),
|
||||
_track_length_xy(0.0f),
|
||||
_track_desired(0.0f),
|
||||
_limited_speed_xy_cms(0.0f),
|
||||
_track_accel(0.0f),
|
||||
_track_speed(0.0f),
|
||||
_track_leash_length(0.0f),
|
||||
_slow_down_dist(0.0f),
|
||||
_spline_time(0.0f),
|
||||
_spline_time_scale(0.0f),
|
||||
_spline_vel_scaler(0.0f),
|
||||
_yaw(0.0f)
|
||||
_attitude_control(attitude_control)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user