AP_InertialSensor_HIL.cpp 912 B

12345678910111213141516171819202122232425262728293031323334353637383940414243
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_InertialSensor_HIL.h"
  3. const extern AP_HAL::HAL& hal;
  4. AP_InertialSensor_HIL::AP_InertialSensor_HIL(AP_InertialSensor &imu) :
  5. AP_InertialSensor_Backend(imu)
  6. {
  7. }
  8. /*
  9. detect the sensor
  10. */
  11. AP_InertialSensor_Backend *AP_InertialSensor_HIL::detect(AP_InertialSensor &_imu)
  12. {
  13. AP_InertialSensor_HIL *sensor = new AP_InertialSensor_HIL(_imu);
  14. if (sensor == nullptr) {
  15. return nullptr;
  16. }
  17. if (!sensor->_init_sensor()) {
  18. delete sensor;
  19. return nullptr;
  20. }
  21. return sensor;
  22. }
  23. bool AP_InertialSensor_HIL::_init_sensor(void)
  24. {
  25. // grab the used instances
  26. _imu.register_gyro(1200, 1);
  27. _imu.register_accel(1200, 1);
  28. _imu.set_hil_mode();
  29. return true;
  30. }
  31. bool AP_InertialSensor_HIL::update(void)
  32. {
  33. // the data is stored directly in the frontend, so update()
  34. // doesn't need to do anything
  35. return true;
  36. }