mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_InertialSensor: Correct out-of-bounds array access that was causing SITL to crash
This commit is contained in:
parent
736201689b
commit
e81d2e9584
@ -11,7 +11,7 @@
|
||||
maximum number of INS instances available on this platform. If more
|
||||
than 1 then redundent sensors may be available
|
||||
*/
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
#define INS_MAX_INSTANCES 2
|
||||
#else
|
||||
#define INS_MAX_INSTANCES 1
|
||||
|
@ -68,6 +68,9 @@ bool AP_InertialSensor_HIL::wait_for_sample(uint16_t timeout_ms)
|
||||
|
||||
void AP_InertialSensor_HIL::set_accel(uint8_t instance, const Vector3f &accel)
|
||||
{
|
||||
if (instance >= INS_MAX_INSTANCES) {
|
||||
return;
|
||||
}
|
||||
_previous_accel[instance] = _accel[instance];
|
||||
_accel[instance] = accel;
|
||||
_last_accel_usec[instance] = hal.scheduler->micros();
|
||||
@ -75,17 +78,26 @@ void AP_InertialSensor_HIL::set_accel(uint8_t instance, const Vector3f &accel)
|
||||
|
||||
void AP_InertialSensor_HIL::set_gyro(uint8_t instance, const Vector3f &gyro)
|
||||
{
|
||||
if (instance >= INS_MAX_INSTANCES) {
|
||||
return;
|
||||
}
|
||||
_gyro[instance] = gyro;
|
||||
_last_gyro_usec[instance] = hal.scheduler->micros();
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_HIL::get_gyro_health(uint8_t instance) const
|
||||
{
|
||||
if (instance >= INS_MAX_INSTANCES) {
|
||||
return false;
|
||||
}
|
||||
return (hal.scheduler->micros() - _last_gyro_usec[instance]) < 40000;
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_HIL::get_accel_health(uint8_t instance) const
|
||||
{
|
||||
if (instance >= INS_MAX_INSTANCES) {
|
||||
return false;
|
||||
}
|
||||
return (hal.scheduler->micros() - _last_accel_usec[instance]) < 40000;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user