mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_InertialSensor: remove use of never-set AP_HAL_PX4 and AP_HAL_VRBRAIN
This commit is contained in:
parent
1dde70007a
commit
43e3acc954
@ -512,7 +512,7 @@ uint8_t AP_InertialSensor::register_gyro(uint16_t raw_sample_rate_hz,
|
||||
|
||||
_gyro_id[_gyro_count].set((int32_t) id);
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN || CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
if (!saved) {
|
||||
// assume this is the same sensor and save its ID to allow seamless
|
||||
// transition from when we didn't have the IDs.
|
||||
@ -551,7 +551,7 @@ uint8_t AP_InertialSensor::register_accel(uint16_t raw_sample_rate_hz,
|
||||
|
||||
_accel_id[_accel_count].set((int32_t) id);
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN || CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
// assume this is the same sensor and save its ID to allow seamless
|
||||
// transition from when we didn't have the IDs.
|
||||
_accel_id_ok[_accel_count] = true;
|
||||
|
Loading…
Reference in New Issue
Block a user