mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: Fix comment on expected variable range
the move_actuators function in AP_MotorsHeli_Dual previously indicated incorrect ranges for its input variables.
This commit is contained in:
parent
cd52c5a5c5
commit
379005ebc7
|
@ -431,10 +431,10 @@ void AP_MotorsHeli_Dual::update_motor_control(RotorControlState state)
|
||||||
//
|
//
|
||||||
// move_actuators - moves swash plate to attitude of parameters passed in
|
// move_actuators - moves swash plate to attitude of parameters passed in
|
||||||
// - expected ranges:
|
// - expected ranges:
|
||||||
// roll : -4500 ~ 4500
|
// roll : -1 ~ +1
|
||||||
// pitch: -4500 ~ 4500
|
// pitch: -1 ~ +1
|
||||||
// collective: 0 ~ 1000
|
// collective: 0 ~ 1
|
||||||
// yaw: -4500 ~ 4500
|
// yaw: -1 ~ +1
|
||||||
//
|
//
|
||||||
void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float collective_in, float yaw_out)
|
void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float collective_in, float yaw_out)
|
||||||
{
|
{
|
||||||
|
|
Loading…
Reference in New Issue