mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: added per-instance rotation for LSM9DS0
This commit is contained in:
parent
2df6ed08c2
commit
b92c48548a
|
@ -594,7 +594,7 @@ AP_InertialSensor::detect_backends(void)
|
|||
_add_backend(AP_InertialSensor_MPU6000::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME), ROTATION_ROLL_180));
|
||||
_add_backend(AP_InertialSensor_LSM9DS0::probe(*this,
|
||||
hal.spi->get_device(HAL_INS_LSM9DS0_G_NAME),
|
||||
hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME)));
|
||||
hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_ROLL_180));
|
||||
} else if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V4) {
|
||||
_add_backend(AP_InertialSensor_MPU6000::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME)));
|
||||
}
|
||||
|
|
|
@ -381,23 +381,27 @@ AP_InertialSensor_LSM9DS0::AP_InertialSensor_LSM9DS0(AP_InertialSensor &imu,
|
|||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_gyro,
|
||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_accel,
|
||||
int drdy_pin_num_a,
|
||||
int drdy_pin_num_g)
|
||||
int drdy_pin_num_g,
|
||||
enum Rotation rotation)
|
||||
: AP_InertialSensor_Backend(imu)
|
||||
, _dev_gyro(std::move(dev_gyro))
|
||||
, _dev_accel(std::move(dev_accel))
|
||||
, _drdy_pin_num_a(drdy_pin_num_a)
|
||||
, _drdy_pin_num_g(drdy_pin_num_g)
|
||||
, _rotation(rotation)
|
||||
{
|
||||
_product_id = AP_PRODUCT_ID_NONE;
|
||||
}
|
||||
|
||||
AP_InertialSensor_Backend *AP_InertialSensor_LSM9DS0::probe(AP_InertialSensor &_imu,
|
||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_gyro,
|
||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_accel)
|
||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_accel,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
AP_InertialSensor_LSM9DS0 *sensor =
|
||||
new AP_InertialSensor_LSM9DS0(_imu, std::move(dev_gyro), std::move(dev_accel),
|
||||
LSM9DS0_DRY_X_PIN, LSM9DS0_DRY_G_PIN);
|
||||
LSM9DS0_DRY_X_PIN, LSM9DS0_DRY_G_PIN,
|
||||
rotation);
|
||||
if (!sensor || !sensor->_init_sensor()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
|
@ -506,6 +510,9 @@ void AP_InertialSensor_LSM9DS0::start(void)
|
|||
{
|
||||
_gyro_instance = _imu.register_gyro(760);
|
||||
_accel_instance = _imu.register_accel(800);
|
||||
|
||||
set_gyro_orientation(_gyro_instance, _rotation);
|
||||
set_accel_orientation(_accel_instance, _rotation);
|
||||
|
||||
_set_accel_max_abs_offset(_accel_instance, 5.0f);
|
||||
|
||||
|
|
|
@ -17,13 +17,15 @@ public:
|
|||
|
||||
static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
|
||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_gyro,
|
||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_accel);
|
||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_accel,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
private:
|
||||
AP_InertialSensor_LSM9DS0(AP_InertialSensor &imu,
|
||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_gyro,
|
||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_accel,
|
||||
int drdy_pin_num_a, int drdy_pin_num_b);
|
||||
int drdy_pin_num_a, int drdy_pin_num_b,
|
||||
enum Rotation rotation);
|
||||
|
||||
struct PACKED sensor_raw_data {
|
||||
int16_t x;
|
||||
|
@ -92,4 +94,6 @@ private:
|
|||
int _drdy_pin_num_g;
|
||||
uint8_t _gyro_instance;
|
||||
uint8_t _accel_instance;
|
||||
|
||||
enum Rotation _rotation;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue