6 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 21 if (sensor ==
nullptr) {
34 if (
sitl ==
nullptr) {
56 float accel_noise = 0.01f;
77 Vector3f lever_arm_accel = angular_accel % pos_offset;
81 Vector3f centripetal_accel = angular_rate % (angular_rate % pos_offset);
84 xAccel += lever_arm_accel.
x + centripetal_accel.
x;
85 yAccel += lever_arm_accel.
y + centripetal_accel.
y;
86 zAccel += lever_arm_accel.
z + centripetal_accel.
z;
108 float gyro_noise =
ToRad(0.04
f);
127 gyro.
x *= (1 + scale.
x*0.01);
128 gyro.
y *= (1 + scale.
y*0.01);
129 gyro.
z *= (1 + scale.
z*0.01);
142 if (now > 5e6 && now < 6e6) {
170 if (minutes < period/2) {
187 #endif // HAL_BOARD_SITL
static AP_Param * find_object(const char *name)
Vector3< float > Vector3f
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
AP_Vector3f imu_pos_offset
void generate_accel(uint8_t instance)
#define INS_SITL_INSTANCES
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
void _notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0)
void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro)
void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false)
uint8_t accel_instance[INS_SITL_INSTANCES]
AP_InertialSensor_SITL(AP_InertialSensor &imu)
virtual void register_timer_process(AP_HAL::MemberProc)=0
const uint16_t accel_sample_hz[INS_SITL_INSTANCES]
static constexpr float radians(float deg)
void update_gyro(uint8_t instance)
uint64_t next_accel_sample[INS_SITL_INSTANCES]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
uint64_t next_gyro_sample[INS_SITL_INSTANCES]
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
const uint16_t gyro_sample_hz[INS_SITL_INSTANCES]
void generate_gyro(uint8_t instance)
uint8_t gyro_instance[INS_SITL_INSTANCES]
void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel)
void update_accel(uint8_t instance)
AP_HAL::Scheduler * scheduler