mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_InertialSensor: add and use AP_SIM_INS_ENABLED
This commit is contained in:
parent
a31ff08f23
commit
c1c329e2b4
@ -1011,13 +1011,16 @@ AP_InertialSensor::detect_backends(void)
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(HAL_INS_PROBE_LIST)
|
#if AP_SIM_INS_ENABLED
|
||||||
// IMUs defined by IMU lines in hwdef.dat
|
|
||||||
HAL_INS_PROBE_LIST;
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
||||||
for (uint8_t i=0; i<AP::sitl()->imu_count; i++) {
|
for (uint8_t i=0; i<AP::sitl()->imu_count; i++) {
|
||||||
ADD_BACKEND(AP_InertialSensor_SITL::detect(*this, i==1?INS_SITL_SENSOR_B:INS_SITL_SENSOR_A));
|
ADD_BACKEND(AP_InertialSensor_SITL::detect(*this, i==1?INS_SITL_SENSOR_B:INS_SITL_SENSOR_A));
|
||||||
}
|
}
|
||||||
|
return;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(HAL_INS_PROBE_LIST)
|
||||||
|
// IMUs defined by IMU lines in hwdef.dat
|
||||||
|
HAL_INS_PROBE_LIST;
|
||||||
#if defined(HAL_SITL_INVENSENSEV3)
|
#if defined(HAL_SITL_INVENSENSEV3)
|
||||||
ADD_BACKEND(AP_InertialSensor_Invensensev3::probe(*this, hal.i2c_mgr->get_device(1, 1), ROTATION_NONE));
|
ADD_BACKEND(AP_InertialSensor_Invensensev3::probe(*this, hal.i2c_mgr->get_device(1, 1), ROTATION_NONE));
|
||||||
#endif
|
#endif
|
||||||
|
@ -47,6 +47,10 @@
|
|||||||
#include <Filter/HarmonicNotchFilter.h>
|
#include <Filter/HarmonicNotchFilter.h>
|
||||||
#include <AP_Math/polyfit.h>
|
#include <AP_Math/polyfit.h>
|
||||||
|
|
||||||
|
#ifndef AP_SIM_INS_ENABLED
|
||||||
|
#define AP_SIM_INS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||||
|
#endif
|
||||||
|
|
||||||
class AP_InertialSensor_Backend;
|
class AP_InertialSensor_Backend;
|
||||||
class AuxiliaryBus;
|
class AuxiliaryBus;
|
||||||
class AP_AHRS;
|
class AP_AHRS;
|
||||||
|
@ -3,7 +3,7 @@
|
|||||||
#include <SITL/SITL.h>
|
#include <SITL/SITL.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if AP_SIM_INS_ENABLED
|
||||||
|
|
||||||
const extern AP_HAL::HAL& hal;
|
const extern AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -347,4 +347,4 @@ void AP_InertialSensor_SITL::start()
|
|||||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_SITL::timer_update, void));
|
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_SITL::timer_update, void));
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAL_BOARD_SITL
|
#endif // AP_SIM_INS_ENABLED
|
||||||
|
@ -1,15 +1,17 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <SITL/SITL.h>
|
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
||||||
#include "AP_InertialSensor.h"
|
#include "AP_InertialSensor.h"
|
||||||
|
|
||||||
|
#if AP_SIM_INS_ENABLED
|
||||||
|
|
||||||
#include "AP_InertialSensor_Backend.h"
|
#include "AP_InertialSensor_Backend.h"
|
||||||
|
|
||||||
// simulated sensor rates in Hz. This matches a pixhawk1
|
// simulated sensor rates in Hz. This matches a pixhawk1
|
||||||
const uint16_t INS_SITL_SENSOR_A[] = { 1000, 1000 };
|
const uint16_t INS_SITL_SENSOR_A[] = { 1000, 1000 };
|
||||||
const uint16_t INS_SITL_SENSOR_B[] = { 760, 800 };
|
const uint16_t INS_SITL_SENSOR_B[] = { 760, 800 };
|
||||||
|
|
||||||
|
#include <SITL/SITL.h>
|
||||||
|
|
||||||
class AP_InertialSensor_SITL : public AP_InertialSensor_Backend
|
class AP_InertialSensor_SITL : public AP_InertialSensor_Backend
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
@ -47,4 +49,4 @@ private:
|
|||||||
|
|
||||||
static uint8_t bus_id;
|
static uint8_t bus_id;
|
||||||
};
|
};
|
||||||
#endif // CONFIG_HAL_BOARD
|
#endif // AP_SIM_INS_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user