mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
AC_AttControlHeli: init passthrough_yaw
This commit is contained in:
parent
35a924703f
commit
157c97447d
@ -27,7 +27,7 @@ public:
|
||||
AC_AttitudeControl(ahrs, aparm, motors,
|
||||
p_angle_roll, p_angle_pitch, p_angle_yaw,
|
||||
pid_rate_roll, pid_rate_pitch, pid_rate_yaw),
|
||||
_passthrough_roll(0), _passthrough_pitch(0),
|
||||
_passthrough_roll(0), _passthrough_pitch(0), _passthrough_yaw(0),
|
||||
pitch_feedforward_filter(AC_ATTITUDE_HELI_RATE_RP_FF_FILTER),
|
||||
roll_feedforward_filter(AC_ATTITUDE_HELI_RATE_RP_FF_FILTER),
|
||||
yaw_velocity_feedforward_filter(AC_ATTITUDE_HELI_RATE_Y_VFF_FILTER),
|
||||
|
Loading…
Reference in New Issue
Block a user