mirror of https://github.com/ArduPilot/ardupilot
Rover: add E-stop
This commit is contained in:
parent
49ec059420
commit
4f9b8e1b6c
|
@ -320,6 +320,12 @@ void Rover::update_GPS(void)
|
||||||
|
|
||||||
void Rover::update_current_mode(void)
|
void Rover::update_current_mode(void)
|
||||||
{
|
{
|
||||||
|
// check for emergency stop
|
||||||
|
if (SRV_Channels::get_emergency_stop()) {
|
||||||
|
// relax controllers, motor stopping done at output level
|
||||||
|
g2.attitude_control.relax_I();
|
||||||
|
}
|
||||||
|
|
||||||
control_mode->update();
|
control_mode->update();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -71,6 +71,13 @@ bool AP_Arming_Rover::gps_checks(bool display_failure)
|
||||||
|
|
||||||
bool AP_Arming_Rover::pre_arm_checks(bool report)
|
bool AP_Arming_Rover::pre_arm_checks(bool report)
|
||||||
{
|
{
|
||||||
|
if (SRV_Channels::get_emergency_stop()) {
|
||||||
|
if (report) {
|
||||||
|
gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Motors Emergency Stopped");
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
return (AP_Arming::pre_arm_checks(report)
|
return (AP_Arming::pre_arm_checks(report)
|
||||||
& rover.g2.motors.pre_arm_check(report)
|
& rover.g2.motors.pre_arm_check(report)
|
||||||
& fence_checks(report)
|
& fence_checks(report)
|
||||||
|
|
Loading…
Reference in New Issue