AP_InertialSensor: wait forever for semaphore on startup

some boards take a silly amount of time to get semaphore on startup
This commit is contained in:
Andrew Tridgell 2016-11-18 12:04:22 +11:00 committed by Lucas De Marchi
parent d50fd3a6cd
commit 6129b1abb6
3 changed files with 7 additions and 7 deletions

View File

@ -152,7 +152,7 @@ void AP_InertialSensor_BMI160::start()
{ {
bool r; bool r;
if (!_dev->get_semaphore()->take(100)) { if (!_dev->get_semaphore()->take(0)) {
AP_HAL::panic("BMI160: Unable to get semaphore"); AP_HAL::panic("BMI160: Unable to get semaphore");
} }
@ -429,7 +429,7 @@ bool AP_InertialSensor_BMI160::_hardware_init()
hal.scheduler->delay(BMI160_POWERUP_DELAY_MSEC); hal.scheduler->delay(BMI160_POWERUP_DELAY_MSEC);
if (!_dev->get_semaphore()->take(100)) { if (!_dev->get_semaphore()->take(0)) {
AP_HAL::panic("BMI160: Unable to get semaphore"); AP_HAL::panic("BMI160: Unable to get semaphore");
} }

View File

@ -344,7 +344,7 @@ bool AP_InertialSensor_MPU6000::_has_auxiliary_bus()
void AP_InertialSensor_MPU6000::start() void AP_InertialSensor_MPU6000::start()
{ {
if (!_dev->get_semaphore()->take(100)) { if (!_dev->get_semaphore()->take(0)) {
AP_HAL::panic("MPU6000: Unable to get semaphore"); AP_HAL::panic("MPU6000: Unable to get semaphore");
} }
@ -722,7 +722,7 @@ bool AP_InertialSensor_MPU6000::_check_whoami(void)
bool AP_InertialSensor_MPU6000::_hardware_init(void) bool AP_InertialSensor_MPU6000::_hardware_init(void)
{ {
if (!_dev->get_semaphore()->take(100)) { if (!_dev->get_semaphore()->take(0)) {
AP_HAL::panic("MPU6000: Unable to get semaphore"); AP_HAL::panic("MPU6000: Unable to get semaphore");
} }
@ -803,7 +803,7 @@ bool AP_InertialSensor_MPU6000::_hardware_init(void)
void AP_InertialSensor_MPU6000::_dump_registers(void) void AP_InertialSensor_MPU6000::_dump_registers(void)
{ {
hal.console->println("MPU6000 registers"); hal.console->println("MPU6000 registers");
if (!_dev->get_semaphore()->take(100)) { if (!_dev->get_semaphore()->take(0)) {
return; return;
} }

View File

@ -295,7 +295,7 @@ bool AP_InertialSensor_MPU9250::_has_auxiliary_bus()
void AP_InertialSensor_MPU9250::start() void AP_InertialSensor_MPU9250::start()
{ {
if (!_dev->get_semaphore()->take(100)) { if (!_dev->get_semaphore()->take(0)) {
AP_HAL::panic("MPU92500: Unable to get semaphore"); AP_HAL::panic("MPU92500: Unable to get semaphore");
} }
@ -600,7 +600,7 @@ void AP_InertialSensor_MPU9250::_register_write(uint8_t reg, uint8_t val, bool c
bool AP_InertialSensor_MPU9250::_hardware_init(void) bool AP_InertialSensor_MPU9250::_hardware_init(void)
{ {
if (!_dev->get_semaphore()->take(100)) { if (!_dev->get_semaphore()->take(0)) {
AP_HAL::panic("MPU9250: Unable to get semaphore"); AP_HAL::panic("MPU9250: Unable to get semaphore");
} }