mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Rover: removed min speed crash check for balance bot
This commit is contained in:
parent
9702f4f822
commit
07fc5c8349
@ -27,6 +27,7 @@ void Rover::crash_check()
|
|||||||
// TODO : Check if min vel can be calculated
|
// TODO : Check if min vel can be calculated
|
||||||
// min_vel = ( CRASH_CHECK_THROTTLE_MIN * g.speed_cruise) / g.throttle_cruise;
|
// min_vel = ( CRASH_CHECK_THROTTLE_MIN * g.speed_cruise) / g.throttle_cruise;
|
||||||
|
|
||||||
|
if (!is_balancebot()) {
|
||||||
if (!crashed && ((ahrs.groundspeed() >= CRASH_CHECK_VEL_MIN) || // Check velocity
|
if (!crashed && ((ahrs.groundspeed() >= CRASH_CHECK_VEL_MIN) || // Check velocity
|
||||||
(fabsf(ahrs.get_gyro().z) >= CRASH_CHECK_VEL_MIN) || // Check turn speed
|
(fabsf(ahrs.get_gyro().z) >= CRASH_CHECK_VEL_MIN) || // Check turn speed
|
||||||
(fabsf(g2.motors.get_throttle()) < CRASH_CHECK_THROTTLE_MIN))) {
|
(fabsf(g2.motors.get_throttle()) < CRASH_CHECK_THROTTLE_MIN))) {
|
||||||
@ -41,6 +42,7 @@ void Rover::crash_check()
|
|||||||
if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * 10)) {
|
if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * 10)) {
|
||||||
crashed = true;
|
crashed = true;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (crashed) {
|
if (crashed) {
|
||||||
// log an error in the dataflash
|
// log an error in the dataflash
|
||||||
|
Loading…
Reference in New Issue
Block a user