APM:Libraries
AP_InertialSensor_HIL.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
3 
4 const extern AP_HAL::HAL& hal;
5 
8 {
9 }
10 
11 /*
12  detect the sensor
13  */
15 {
16  AP_InertialSensor_HIL *sensor = new AP_InertialSensor_HIL(_imu);
17  if (sensor == nullptr) {
18  return nullptr;
19  }
20  if (!sensor->_init_sensor()) {
21  delete sensor;
22  return nullptr;
23  }
24  return sensor;
25 }
26 
28 {
29  // grab the used instances
30  _imu.register_gyro(1200, 1);
31  _imu.register_accel(1200, 1);
32 
34 
35  return true;
36 }
37 
39 {
40  // the data is stored directly in the frontend, so update()
41  // doesn't need to do anything
42  return true;
43 }
AP_InertialSensor_HIL(AP_InertialSensor &imu)
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)