mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: remove superfluous linefeed from panic strings
panic adds this within the HAL layer.
This commit is contained in:
parent
57ac1e5911
commit
5becd59265
|
@ -226,10 +226,10 @@ void AP_InertialSensor_BMI160::_check_err_reg()
|
|||
|
||||
r = _dev->read_registers(BMI160_REG_ERR_REG, &v, 1);
|
||||
if (!r) {
|
||||
AP_HAL::panic("BMI160: couldn't read ERR_REG\n");
|
||||
AP_HAL::panic("BMI160: couldn't read ERR_REG");
|
||||
}
|
||||
if (v) {
|
||||
AP_HAL::panic("BMI160: error detected on ERR_REG\n");
|
||||
AP_HAL::panic("BMI160: error detected on ERR_REG");
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -424,7 +424,7 @@ bool AP_InertialSensor_LSM9DS0::_init_sensor()
|
|||
if (_drdy_pin_num_a >= 0) {
|
||||
_drdy_pin_a = hal.gpio->channel(_drdy_pin_num_a);
|
||||
if (_drdy_pin_a == nullptr) {
|
||||
AP_HAL::panic("LSM9DS0: null accel data-ready GPIO channel\n");
|
||||
AP_HAL::panic("LSM9DS0: null accel data-ready GPIO channel");
|
||||
}
|
||||
|
||||
_drdy_pin_a->mode(HAL_GPIO_INPUT);
|
||||
|
@ -433,7 +433,7 @@ bool AP_InertialSensor_LSM9DS0::_init_sensor()
|
|||
if (_drdy_pin_num_g >= 0) {
|
||||
_drdy_pin_g = hal.gpio->channel(_drdy_pin_num_g);
|
||||
if (_drdy_pin_g == nullptr) {
|
||||
AP_HAL::panic("LSM9DS0: null gyro data-ready GPIO channel\n");
|
||||
AP_HAL::panic("LSM9DS0: null gyro data-ready GPIO channel");
|
||||
}
|
||||
|
||||
_drdy_pin_g->mode(HAL_GPIO_INPUT);
|
||||
|
|
|
@ -231,7 +231,7 @@ bool AP_InertialSensor_LSM9DS1::_init_sensor()
|
|||
if (_drdy_pin_num_xg >= 0) {
|
||||
_drdy_pin_xg = hal.gpio->channel(_drdy_pin_num_xg);
|
||||
if (_drdy_pin_xg == nullptr) {
|
||||
AP_HAL::panic("LSM9DS1: null accel data-ready GPIO channel\n");
|
||||
AP_HAL::panic("LSM9DS1: null accel data-ready GPIO channel");
|
||||
}
|
||||
_drdy_pin_xg->mode(HAL_GPIO_INPUT);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue