AC_WPNav: remove un-needed initialisation

This commit is contained in:
Peter Barker 2024-05-21 08:49:29 +10:00 committed by Peter Barker
parent bb0d1cf7b8
commit 24e54dac88
1 changed files with 1 additions and 7 deletions

View File

@ -43,13 +43,7 @@ const AP_Param::GroupInfo AC_Circle::var_info[] = {
AC_Circle::AC_Circle(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control) :
_inav(inav),
_ahrs(ahrs),
_pos_control(pos_control),
_yaw(0.0f),
_angle(0.0f),
_angle_total(0.0f),
_angular_vel(0.0f),
_angular_vel_max(0.0f),
_angular_accel(0.0f)
_pos_control(pos_control)
{
AP_Param::setup_object_defaults(this, var_info);