mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
AP_InertialSensor: remove checks for HAL_BOARD_APM2 and HAL_BOARD_APM1
This commit is contained in:
parent
cf8203c08b
commit
3142f21363
@ -49,7 +49,6 @@
|
|||||||
#define HAL_BOARD_SUBTYPE_VRUBRAIN_V52 4004
|
#define HAL_BOARD_SUBTYPE_VRUBRAIN_V52 4004
|
||||||
|
|
||||||
// InertialSensor driver types
|
// InertialSensor driver types
|
||||||
#define HAL_INS_OILPAN 1
|
|
||||||
#define HAL_INS_MPU60XX_SPI 2
|
#define HAL_INS_MPU60XX_SPI 2
|
||||||
#define HAL_INS_MPU60XX_I2C 3
|
#define HAL_INS_MPU60XX_I2C 3
|
||||||
#define HAL_INS_HIL 4
|
#define HAL_INS_HIL 4
|
||||||
|
@ -500,8 +500,6 @@ AP_InertialSensor::_detect_backends(void)
|
|||||||
_add_backend(AP_InertialSensor_MPU6000::detect_i2c(*this, hal.i2c2, HAL_INS_MPU60XX_I2C_ADDR));
|
_add_backend(AP_InertialSensor_MPU6000::detect_i2c(*this, hal.i2c2, HAL_INS_MPU60XX_I2C_ADDR));
|
||||||
#elif HAL_INS_DEFAULT == HAL_INS_PX4 || HAL_INS_DEFAULT == HAL_INS_VRBRAIN
|
#elif HAL_INS_DEFAULT == HAL_INS_PX4 || HAL_INS_DEFAULT == HAL_INS_VRBRAIN
|
||||||
_add_backend(AP_InertialSensor_PX4::detect(*this));
|
_add_backend(AP_InertialSensor_PX4::detect(*this));
|
||||||
#elif HAL_INS_DEFAULT == HAL_INS_OILPAN
|
|
||||||
_add_backend(AP_InertialSensor_Oilpan::detect(*this));
|
|
||||||
#elif HAL_INS_DEFAULT == HAL_INS_MPU9250
|
#elif HAL_INS_DEFAULT == HAL_INS_MPU9250
|
||||||
_add_backend(AP_InertialSensor_MPU9250::detect(*this, hal.spi->device(AP_HAL::SPIDevice_MPU9250)));
|
_add_backend(AP_InertialSensor_MPU9250::detect(*this, hal.spi->device(AP_HAL::SPIDevice_MPU9250)));
|
||||||
#elif HAL_INS_DEFAULT == HAL_INS_FLYMAPLE
|
#elif HAL_INS_DEFAULT == HAL_INS_FLYMAPLE
|
||||||
|
@ -381,7 +381,6 @@ private:
|
|||||||
#include "AP_InertialSensor_Backend.h"
|
#include "AP_InertialSensor_Backend.h"
|
||||||
#include "AP_InertialSensor_MPU6000.h"
|
#include "AP_InertialSensor_MPU6000.h"
|
||||||
#include "AP_InertialSensor_PX4.h"
|
#include "AP_InertialSensor_PX4.h"
|
||||||
#include "AP_InertialSensor_Oilpan.h"
|
|
||||||
#include "AP_InertialSensor_MPU9250.h"
|
#include "AP_InertialSensor_MPU9250.h"
|
||||||
#include "AP_InertialSensor_L3G4200D.h"
|
#include "AP_InertialSensor_L3G4200D.h"
|
||||||
#include "AP_InertialSensor_Flymaple.h"
|
#include "AP_InertialSensor_Flymaple.h"
|
||||||
|
@ -10,9 +10,7 @@ extern const AP_HAL::HAL& hal;
|
|||||||
// MPU6000 accelerometer scaling
|
// MPU6000 accelerometer scaling
|
||||||
#define MPU6000_ACCEL_SCALE_1G (GRAVITY_MSS / 4096.0f)
|
#define MPU6000_ACCEL_SCALE_1G (GRAVITY_MSS / 4096.0f)
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
#define MPU6000_DRDY_PIN 70
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
#include <AP_HAL_Linux/GPIO.h>
|
#include <AP_HAL_Linux/GPIO.h>
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF
|
||||||
#define MPU6000_DRDY_PIN BBB_P8_14
|
#define MPU6000_DRDY_PIN BBB_P8_14
|
||||||
@ -808,7 +806,7 @@ bool AP_InertialSensor_MPU6000::_hardware_init(void)
|
|||||||
hal.scheduler->panic("MPU6000: Unable to get semaphore");
|
hal.scheduler->panic("MPU6000: Unable to get semaphore");
|
||||||
}
|
}
|
||||||
|
|
||||||
// initially run the bus at low speed (500kHz on APM2)
|
// initially run the bus at low speed
|
||||||
_bus->set_bus_speed(AP_HAL::SPIDeviceDriver::SPI_SPEED_LOW);
|
_bus->set_bus_speed(AP_HAL::SPIDeviceDriver::SPI_SPEED_LOW);
|
||||||
|
|
||||||
// Chip reset
|
// Chip reset
|
||||||
|
@ -514,7 +514,6 @@ bool AP_InertialSensor_MPU9250::_hardware_init(void)
|
|||||||
_register_write(MPUREG_INT_PIN_CFG, BIT_INT_RD_CLEAR | BIT_LATCH_INT_EN);
|
_register_write(MPUREG_INT_PIN_CFG, BIT_INT_RD_CLEAR | BIT_LATCH_INT_EN);
|
||||||
|
|
||||||
// now that we have initialised, we set the SPI bus speed to high
|
// now that we have initialised, we set the SPI bus speed to high
|
||||||
// (8MHz on APM2)
|
|
||||||
_spi->set_bus_speed(AP_HAL::SPIDeviceDriver::SPI_SPEED_HIGH);
|
_spi->set_bus_speed(AP_HAL::SPIDeviceDriver::SPI_SPEED_HIGH);
|
||||||
|
|
||||||
_spi_sem->give();
|
_spi_sem->give();
|
||||||
|
@ -1,128 +0,0 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
||||||
#include "AP_InertialSensor_Oilpan.h"
|
|
||||||
#include <AP_ADC/AP_ADC.h>
|
|
||||||
|
|
||||||
const extern AP_HAL::HAL& hal;
|
|
||||||
|
|
||||||
// this driver assumes an AP_ADC object has been declared globally
|
|
||||||
extern AP_ADC_ADS7844 apm1_adc;
|
|
||||||
|
|
||||||
// ADC channel mappings on for the APM Oilpan
|
|
||||||
// Sensors: GYROX, GYROY, GYROZ, ACCELX, ACCELY, ACCELZ
|
|
||||||
const uint8_t AP_InertialSensor_Oilpan::_sensors[6] = { 1, 2, 0, 4, 5, 6 };
|
|
||||||
|
|
||||||
// ADC result sign adjustment for sensors.
|
|
||||||
const int8_t AP_InertialSensor_Oilpan::_sensor_signs[6] =
|
|
||||||
{ 1, -1, -1, 1, -1, -1 };
|
|
||||||
|
|
||||||
// Maximum possible value returned by an offset-corrected sensor channel
|
|
||||||
const float AP_InertialSensor_Oilpan::_adc_constraint = 900;
|
|
||||||
|
|
||||||
// ADC : Voltage reference 3.3v / 12bits(4096 steps) => 0.8mV/ADC step
|
|
||||||
// ADXL335 Sensitivity(from datasheet) => 330mV/g,
|
|
||||||
// 0.8mV/ADC step => 330/0.8 = 412
|
|
||||||
// Tested value : 418
|
|
||||||
|
|
||||||
// Oilpan accelerometer scaling & offsets
|
|
||||||
#define OILPAN_ACCEL_SCALE_1G (GRAVITY_MSS * 2.0f / (2465.0f - 1617.0f))
|
|
||||||
#define OILPAN_RAW_ACCEL_OFFSET ((2465.0f + 1617.0f) * 0.5f)
|
|
||||||
#define OILPAN_RAW_GYRO_OFFSET 1658.0f
|
|
||||||
|
|
||||||
// IDG500 Sensitivity (from datasheet) => 2.0mV/degree/s,
|
|
||||||
// 0.8mV/ADC step => 0.8/3.33 = 0.4
|
|
||||||
// Tested values : 0.4026, ?, 0.4192
|
|
||||||
const float AP_InertialSensor_Oilpan::_gyro_gain_x = radians(0.4f);
|
|
||||||
const float AP_InertialSensor_Oilpan::_gyro_gain_y = radians(0.41f);
|
|
||||||
const float AP_InertialSensor_Oilpan::_gyro_gain_z = radians(0.41f);
|
|
||||||
|
|
||||||
/* ------ Public functions -------------------------------------------*/
|
|
||||||
|
|
||||||
AP_InertialSensor_Oilpan::AP_InertialSensor_Oilpan(AP_InertialSensor &imu) :
|
|
||||||
AP_InertialSensor_Backend(imu)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
|
||||||
detect the sensor
|
|
||||||
*/
|
|
||||||
AP_InertialSensor_Backend *AP_InertialSensor_Oilpan::detect(AP_InertialSensor &_imu)
|
|
||||||
{
|
|
||||||
AP_InertialSensor_Oilpan *sensor = new AP_InertialSensor_Oilpan(_imu);
|
|
||||||
if (sensor == NULL) {
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
if (!sensor->_init_sensor()) {
|
|
||||||
delete sensor;
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
|
|
||||||
return sensor;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool AP_InertialSensor_Oilpan::_init_sensor(void)
|
|
||||||
{
|
|
||||||
apm1_adc.Init();
|
|
||||||
|
|
||||||
switch (_imu.get_sample_rate()) {
|
|
||||||
case AP_InertialSensor::RATE_50HZ:
|
|
||||||
_sample_threshold = 20;
|
|
||||||
break;
|
|
||||||
case AP_InertialSensor::RATE_100HZ:
|
|
||||||
_sample_threshold = 10;
|
|
||||||
break;
|
|
||||||
case AP_InertialSensor::RATE_200HZ:
|
|
||||||
_sample_threshold = 5;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
// can't do this speed
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
_gyro_instance = _imu.register_gyro();
|
|
||||||
_accel_instance = _imu.register_accel();
|
|
||||||
|
|
||||||
_product_id = AP_PRODUCT_ID_APM1_2560;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
|
||||||
copy data from ADC to frontend
|
|
||||||
*/
|
|
||||||
bool AP_InertialSensor_Oilpan::update()
|
|
||||||
{
|
|
||||||
float adc_values[6];
|
|
||||||
|
|
||||||
apm1_adc.Ch6(_sensors, adc_values);
|
|
||||||
|
|
||||||
// copy gyros to frontend
|
|
||||||
Vector3f v;
|
|
||||||
v(_sensor_signs[0] * ( adc_values[0] - OILPAN_RAW_GYRO_OFFSET ) * _gyro_gain_x,
|
|
||||||
_sensor_signs[1] * ( adc_values[1] - OILPAN_RAW_GYRO_OFFSET ) * _gyro_gain_y,
|
|
||||||
_sensor_signs[2] * ( adc_values[2] - OILPAN_RAW_GYRO_OFFSET ) * _gyro_gain_z);
|
|
||||||
_rotate_and_correct_gyro(_gyro_instance, v);
|
|
||||||
_publish_gyro(_gyro_instance, v);
|
|
||||||
|
|
||||||
// copy accels to frontend
|
|
||||||
v(_sensor_signs[3] * (adc_values[3] - OILPAN_RAW_ACCEL_OFFSET),
|
|
||||||
_sensor_signs[4] * (adc_values[4] - OILPAN_RAW_ACCEL_OFFSET),
|
|
||||||
_sensor_signs[5] * (adc_values[5] - OILPAN_RAW_ACCEL_OFFSET));
|
|
||||||
v *= OILPAN_ACCEL_SCALE_1G;
|
|
||||||
_rotate_and_correct_accel(_accel_instance, v);
|
|
||||||
_publish_accel(_accel_instance, v);
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
// return true if a new sample is available
|
|
||||||
bool AP_InertialSensor_Oilpan::_sample_available() const
|
|
||||||
{
|
|
||||||
return apm1_adc.num_samples_available(_sensors) >= _sample_threshold;
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
|
@ -1,37 +0,0 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#ifndef __AP_INERTIAL_SENSOR_OILPAN_H__
|
|
||||||
#define __AP_INERTIAL_SENSOR_OILPAN_H__
|
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
|
||||||
#include "AP_InertialSensor.h"
|
|
||||||
|
|
||||||
class AP_InertialSensor_Oilpan : public AP_InertialSensor_Backend
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
AP_InertialSensor_Oilpan(AP_InertialSensor &imu);
|
|
||||||
|
|
||||||
/* update accel and gyro state */
|
|
||||||
bool update();
|
|
||||||
|
|
||||||
bool gyro_sample_available(void) { return _sample_available(); }
|
|
||||||
bool accel_sample_available(void) { return _sample_available(); }
|
|
||||||
|
|
||||||
// detect the sensor
|
|
||||||
static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu);
|
|
||||||
|
|
||||||
private:
|
|
||||||
bool _init_sensor(void);
|
|
||||||
bool _sample_available() const;
|
|
||||||
static const uint8_t _sensors[6];
|
|
||||||
static const int8_t _sensor_signs[6];
|
|
||||||
static const float _gyro_gain_x;
|
|
||||||
static const float _gyro_gain_y;
|
|
||||||
static const float _gyro_gain_z;
|
|
||||||
static const float _adc_constraint;
|
|
||||||
uint8_t _sample_threshold;
|
|
||||||
uint8_t _gyro_instance;
|
|
||||||
uint8_t _accel_instance;
|
|
||||||
};
|
|
||||||
|
|
||||||
#endif // __AP_INERTIAL_SENSOR_OILPAN_H__
|
|
@ -13,10 +13,6 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||||||
|
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
||||||
AP_ADC_ADS7844 apm1_adc;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static void display_offsets_and_scaling();
|
static void display_offsets_and_scaling();
|
||||||
static void run_test();
|
static void run_test();
|
||||||
static void run_calibration();
|
static void run_calibration();
|
||||||
@ -25,12 +21,6 @@ void setup(void)
|
|||||||
{
|
{
|
||||||
hal.console->println("AP_InertialSensor startup...");
|
hal.console->println("AP_InertialSensor startup...");
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
||||||
// we need to stop the barometer from holding the SPI bus
|
|
||||||
hal.gpio->pinMode(40, HAL_GPIO_OUTPUT);
|
|
||||||
hal.gpio->write(40, 1);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
ins.init(AP_InertialSensor::RATE_100HZ);
|
ins.init(AP_InertialSensor::RATE_100HZ);
|
||||||
|
|
||||||
// display initial values
|
// display initial values
|
||||||
|
Loading…
Reference in New Issue
Block a user