mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: only mode manual directly copies rc input to motors
This commit is contained in:
parent
f17f56dea4
commit
6626c2e12e
@ -3,7 +3,10 @@
|
|||||||
|
|
||||||
void ModeManual::update()
|
void ModeManual::update()
|
||||||
{
|
{
|
||||||
// mark us as in_reverse when using a negative throttle to
|
// copy RC scaled inputs to outputs
|
||||||
// stop AHRS getting off
|
g2.motors.set_throttle(channel_throttle->get_control_in());
|
||||||
|
g2.motors.set_steering(channel_steer->get_control_in());
|
||||||
|
|
||||||
|
// mark us as in_reverse when using a negative throttle to stop AHRS getting off
|
||||||
rover.set_reverse(is_negative(g2.motors.get_throttle()));
|
rover.set_reverse(is_negative(g2.motors.get_throttle()));
|
||||||
}
|
}
|
||||||
|
@ -152,10 +152,6 @@ void Rover::read_radio()
|
|||||||
channel_throttle->set_pwm(thr);
|
channel_throttle->set_pwm(thr);
|
||||||
}
|
}
|
||||||
|
|
||||||
// copy RC scaled inputs to outputs
|
|
||||||
g2.motors.set_throttle(channel_throttle->get_control_in());
|
|
||||||
g2.motors.set_steering(channel_steer->get_control_in());
|
|
||||||
|
|
||||||
// check if we try to do RC arm/disarm
|
// check if we try to do RC arm/disarm
|
||||||
rudder_arm_disarm_check();
|
rudder_arm_disarm_check();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user