Rover: removed min speed crash check for balance bot

This commit is contained in:
Ebin 2018-06-29 23:56:44 +05:30 committed by Randy Mackay
parent 9702f4f822
commit 07fc5c8349

View File

@ -27,22 +27,24 @@ 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 (!crashed && ((ahrs.groundspeed() >= CRASH_CHECK_VEL_MIN) || // Check velocity if (!is_balancebot()) {
(fabsf(ahrs.get_gyro().z) >= CRASH_CHECK_VEL_MIN) || // Check turn speed if (!crashed && ((ahrs.groundspeed() >= CRASH_CHECK_VEL_MIN) || // Check velocity
(fabsf(g2.motors.get_throttle()) < CRASH_CHECK_THROTTLE_MIN))) { (fabsf(ahrs.get_gyro().z) >= CRASH_CHECK_VEL_MIN) || // Check turn speed
crash_counter = 0; (fabsf(g2.motors.get_throttle()) < CRASH_CHECK_THROTTLE_MIN))) {
return; crash_counter = 0;
return;
}
// we may be crashing
crash_counter++;
// check if crashing for 2 seconds
if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * 10)) {
crashed = true;
}
} }
// we may be crashing if (crashed) {
crash_counter++;
// check if crashing for 2 seconds
if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * 10)) {
crashed = true;
}
if (crashed){
// log an error in the dataflash // log an error in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_CRASH_CHECK, ERROR_CODE_CRASH_CHECK_CRASH); Log_Write_Error(ERROR_SUBSYSTEM_CRASH_CHECK, ERROR_CODE_CRASH_CHECK_CRASH);