mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: move manual mode failsafe handling to mode class
This commit is contained in:
parent
6626c2e12e
commit
2321cefdc2
@ -51,15 +51,8 @@ bool Rover::in_stationary_loiter()
|
|||||||
/*****************************************
|
/*****************************************
|
||||||
Set the flight control servos based on the current calculated values
|
Set the flight control servos based on the current calculated values
|
||||||
*****************************************/
|
*****************************************/
|
||||||
void Rover::set_servos(void) {
|
void Rover::set_servos(void)
|
||||||
// Apply slew rate limit on non Manual modes
|
{
|
||||||
if (control_mode == &mode_manual || control_mode == &mode_learning) {
|
|
||||||
if (failsafe.bits & FAILSAFE_EVENT_THROTTLE) {
|
|
||||||
g2.motors.set_throttle(0.0f);
|
|
||||||
g2.motors.set_steering(0.0f);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// send output signals to motors
|
// send output signals to motors
|
||||||
if (motor_test) {
|
if (motor_test) {
|
||||||
g2.motors.slew_limit_throttle(false);
|
g2.motors.slew_limit_throttle(false);
|
||||||
|
@ -3,9 +3,15 @@
|
|||||||
|
|
||||||
void ModeManual::update()
|
void ModeManual::update()
|
||||||
{
|
{
|
||||||
|
// check for radio failsafe
|
||||||
|
if (rover.failsafe.bits & FAILSAFE_EVENT_THROTTLE) {
|
||||||
|
g2.motors.set_throttle(0.0f);
|
||||||
|
g2.motors.set_steering(0.0f);
|
||||||
|
} else {
|
||||||
// copy RC scaled inputs to outputs
|
// copy RC scaled inputs to outputs
|
||||||
g2.motors.set_throttle(channel_throttle->get_control_in());
|
g2.motors.set_throttle(channel_throttle->get_control_in());
|
||||||
g2.motors.set_steering(channel_steer->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
|
// 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()));
|
||||||
|
Loading…
Reference in New Issue
Block a user