mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: correct RC2_REV to RC2_REVERSED in comment
This commit is contained in:
parent
47e1733bc5
commit
81222fbde0
@ -346,7 +346,7 @@ void JSBSim::send_servos(const struct sitl_input &input)
|
||||
float ch1 = aileron;
|
||||
float ch2 = elevator;
|
||||
aileron = (ch2-ch1)/2.0f;
|
||||
// the minus does away with the need for RC2_REV=-1
|
||||
// the minus does away with the need for RC2_REVERSED=-1
|
||||
elevator = -(ch2+ch1)/2.0f;
|
||||
} else if (frame == FRAME_VTAIL) {
|
||||
// fake a vtail plane
|
||||
|
@ -268,7 +268,7 @@ void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel
|
||||
float ch1 = aileron;
|
||||
float ch2 = elevator;
|
||||
aileron = (ch2-ch1)/2.0f;
|
||||
// the minus does away with the need for RC2_REV=-1
|
||||
// the minus does away with the need for RC2_REVERSED=-1
|
||||
elevator = -(ch2+ch1)/2.0f;
|
||||
|
||||
// assume no rudder
|
||||
|
Loading…
Reference in New Issue
Block a user