mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
TradHeli: update AttControlHeli constructor
reference to rc_1, rc2 are replaced with constant updates during acro_run
This commit is contained in:
parent
2cd6d986d5
commit
7d350735df
@ -648,7 +648,7 @@ static AP_InertialNav inertial_nav(ahrs, barometer, gps_glitch, baro_glitch);
|
|||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
AC_AttitudeControl_Heli attitude_control(ahrs, aparm, motors, g.p_stabilize_roll, g.p_stabilize_pitch, g.p_stabilize_yaw,
|
AC_AttitudeControl_Heli attitude_control(ahrs, aparm, motors, g.p_stabilize_roll, g.p_stabilize_pitch, g.p_stabilize_yaw,
|
||||||
g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw, g.rc_1, g.rc_2);
|
g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw);
|
||||||
#else
|
#else
|
||||||
AC_AttitudeControl attitude_control(ahrs, aparm, motors, g.p_stabilize_roll, g.p_stabilize_pitch, g.p_stabilize_yaw,
|
AC_AttitudeControl attitude_control(ahrs, aparm, motors, g.p_stabilize_roll, g.p_stabilize_pitch, g.p_stabilize_yaw,
|
||||||
g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw);
|
g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw);
|
||||||
|
Loading…
Reference in New Issue
Block a user