mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_InertialSensor: use take_blocking instead of HAL_SEMAPHORE_BLOCK_FOREVER
this makes for cleaner and smaller code as the failure case is not needed
This commit is contained in:
parent
67bd4ed396
commit
b89c241329
@ -152,9 +152,7 @@ void AP_InertialSensor_BMI160::start()
|
||||
{
|
||||
bool r;
|
||||
|
||||
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return;
|
||||
}
|
||||
_dev->get_semaphore()->take_blocking();
|
||||
|
||||
r = _configure_accel();
|
||||
if (!r) {
|
||||
@ -428,9 +426,7 @@ bool AP_InertialSensor_BMI160::_hardware_init()
|
||||
|
||||
hal.scheduler->delay(BMI160_POWERUP_DELAY_MSEC);
|
||||
|
||||
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
}
|
||||
_dev->get_semaphore()->take_blocking();
|
||||
|
||||
_dev->set_speed(AP_HAL::Device::SPEED_LOW);
|
||||
|
||||
|
@ -174,9 +174,7 @@ bool AP_InertialSensor_Invensense::_has_auxiliary_bus()
|
||||
|
||||
void AP_InertialSensor_Invensense::start()
|
||||
{
|
||||
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return;
|
||||
}
|
||||
_dev->get_semaphore()->take_blocking();
|
||||
|
||||
// initially run the bus at low speed
|
||||
_dev->set_speed(AP_HAL::Device::SPEED_LOW);
|
||||
@ -769,9 +767,7 @@ bool AP_InertialSensor_Invensense::_check_whoami(void)
|
||||
|
||||
bool AP_InertialSensor_Invensense::_hardware_init(void)
|
||||
{
|
||||
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
}
|
||||
_dev->get_semaphore()->take_blocking();
|
||||
|
||||
// setup for register checking. We check much less often on I2C
|
||||
// where the cost of the checks is higher
|
||||
@ -985,10 +981,8 @@ void AP_Invensense_AuxiliaryBus::_configure_slaves()
|
||||
return;
|
||||
}
|
||||
|
||||
if (!backend._dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return;
|
||||
}
|
||||
|
||||
backend._dev->get_semaphore()->take_blocking();
|
||||
|
||||
/* Enable the I2C master to slaves on the auxiliary I2C bus*/
|
||||
if (!(backend._last_stat_user_ctrl & BIT_USER_CTRL_I2C_MST_EN)) {
|
||||
backend._last_stat_user_ctrl |= BIT_USER_CTRL_I2C_MST_EN;
|
||||
|
@ -155,9 +155,7 @@ bool AP_InertialSensor_Invensensev2::_has_auxiliary_bus()
|
||||
|
||||
void AP_InertialSensor_Invensensev2::start()
|
||||
{
|
||||
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return;
|
||||
}
|
||||
_dev->get_semaphore()->take_blocking();
|
||||
|
||||
// initially run the bus at low speed
|
||||
_dev->set_speed(AP_HAL::Device::SPEED_LOW);
|
||||
@ -636,9 +634,7 @@ bool AP_InertialSensor_Invensensev2::_check_whoami(void)
|
||||
|
||||
bool AP_InertialSensor_Invensensev2::_hardware_init(void)
|
||||
{
|
||||
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
}
|
||||
_dev->get_semaphore()->take_blocking();
|
||||
|
||||
// disabled setup of checked registers as it can't cope with bank switching
|
||||
// _dev->setup_checked_registers(7, _dev->bus_type() == AP_HAL::Device::BUS_TYPE_I2C?200:20);
|
||||
@ -835,10 +831,8 @@ void AP_Invensensev2_AuxiliaryBus::_configure_slaves()
|
||||
{
|
||||
auto &backend = AP_InertialSensor_Invensensev2::from(_ins_backend);
|
||||
|
||||
if (!backend._dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return;
|
||||
}
|
||||
|
||||
backend._dev->get_semaphore()->take_blocking();
|
||||
|
||||
/* Enable the I2C master to slaves on the auxiliary I2C bus*/
|
||||
if (!(backend._last_stat_user_ctrl & BIT_USER_CTRL_I2C_MST_EN)) {
|
||||
backend._last_stat_user_ctrl |= BIT_USER_CTRL_I2C_MST_EN;
|
||||
|
@ -122,9 +122,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_L3G4200D::probe(AP_InertialSensor &
|
||||
|
||||
bool AP_InertialSensor_L3G4200D::_init_sensor(void)
|
||||
{
|
||||
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
}
|
||||
_dev->get_semaphore()->take_blocking();
|
||||
|
||||
// Init the accelerometer
|
||||
uint8_t data = 0;
|
||||
|
@ -449,9 +449,7 @@ bool AP_InertialSensor_LSM9DS0::_init_sensor()
|
||||
|
||||
bool AP_InertialSensor_LSM9DS0::_hardware_init()
|
||||
{
|
||||
if (!_spi_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
}
|
||||
_spi_sem->take_blocking();
|
||||
|
||||
uint8_t tries, whoami;
|
||||
|
||||
|
@ -246,9 +246,7 @@ bool AP_InertialSensor_LSM9DS1::_init_sensor()
|
||||
|
||||
bool AP_InertialSensor_LSM9DS1::_hardware_init()
|
||||
{
|
||||
if (!_spi_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
}
|
||||
_spi_sem->take_blocking();
|
||||
|
||||
uint8_t tries, whoami;
|
||||
|
||||
|
@ -222,9 +222,7 @@ bool AP_InertialSensor_RST::_init_gyro(void)
|
||||
{
|
||||
uint8_t whoami;
|
||||
|
||||
if (!_dev_gyro->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
}
|
||||
_dev_gyro->get_semaphore()->take_blocking();
|
||||
|
||||
// set flag for reading registers
|
||||
_dev_gyro->set_read_flag(0x80);
|
||||
@ -285,9 +283,7 @@ bool AP_InertialSensor_RST::_init_accel(void)
|
||||
{
|
||||
uint8_t whoami;
|
||||
|
||||
if (!_dev_accel->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
}
|
||||
_dev_accel->get_semaphore()->take_blocking();
|
||||
|
||||
_dev_accel->set_speed(AP_HAL::Device::SPEED_HIGH);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user