AP_InertialSensor_SITL.h 1.0 KB

1234567891011121314151617181920212223242526272829303132333435363738
  1. #pragma once
  2. #include <SITL/SITL.h>
  3. #include "AP_InertialSensor.h"
  4. #include "AP_InertialSensor_Backend.h"
  5. #define INS_SITL_INSTANCES 2
  6. class AP_InertialSensor_SITL : public AP_InertialSensor_Backend
  7. {
  8. public:
  9. AP_InertialSensor_SITL(AP_InertialSensor &imu);
  10. /* update accel and gyro state */
  11. bool update() override;
  12. // detect the sensor
  13. static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu);
  14. private:
  15. bool init_sensor(void);
  16. void timer_update();
  17. float gyro_drift(void);
  18. void generate_accel(uint8_t instance);
  19. void generate_gyro(uint8_t instance);
  20. SITL::SITL *sitl;
  21. // simulated sensor rates in Hz. This matches a pixhawk1
  22. const uint16_t gyro_sample_hz[INS_SITL_INSTANCES] { 1000, 760 };
  23. const uint16_t accel_sample_hz[INS_SITL_INSTANCES] { 1000, 800 };
  24. uint8_t gyro_instance[INS_SITL_INSTANCES];
  25. uint8_t accel_instance[INS_SITL_INSTANCES];
  26. uint64_t next_gyro_sample[INS_SITL_INSTANCES];
  27. uint64_t next_accel_sample[INS_SITL_INSTANCES];
  28. };