mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_InertialSensor: minor tidy up for HIL driver
This commit is contained in:
parent
85686c22ec
commit
ff6d87f145
@ -43,6 +43,8 @@ bool AP_InertialSensor_HIL::_init_sensor(AP_InertialSensor::Sample_rate sample_r
|
||||
case AP_InertialSensor::RATE_400HZ:
|
||||
_sample_period_usec = 2500;
|
||||
break;
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
||||
// grab the used instances
|
||||
@ -54,10 +56,13 @@ bool AP_InertialSensor_HIL::_init_sensor(AP_InertialSensor::Sample_rate sample_r
|
||||
|
||||
bool AP_InertialSensor_HIL::update(void)
|
||||
{
|
||||
// the data is stored directly in the frontend, so update()
|
||||
// doesn't need to do anything
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_HIL::_sample_available()
|
||||
{
|
||||
// just use the timing based wait_for_sample() in the frontend
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user