mirror of https://github.com/ArduPilot/ardupilot
Copter: heli acro, stabilize use pilot throttle as float
This commit is contained in:
parent
07b311f6a8
commit
5dde87734c
|
@ -27,7 +27,7 @@ bool Copter::heli_acro_init(bool ignore_checks)
|
|||
void Copter::heli_acro_run()
|
||||
{
|
||||
float target_roll, target_pitch, target_yaw;
|
||||
int16_t pilot_throttle_scaled;
|
||||
float pilot_throttle_scaled;
|
||||
|
||||
// Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because
|
||||
// we may be in autorotation flight. These should be reset only when transitioning from disarmed
|
||||
|
|
|
@ -26,7 +26,7 @@ void Copter::heli_stabilize_run()
|
|||
{
|
||||
float target_roll, target_pitch;
|
||||
float target_yaw_rate;
|
||||
int16_t pilot_throttle_scaled;
|
||||
float pilot_throttle_scaled;
|
||||
|
||||
// Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because
|
||||
// we may be in autorotation flight. These should be reset only when transitioning from disarmed
|
||||
|
|
Loading…
Reference in New Issue