mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-05 21:23:58 -04:00
AP_InertialSensor: simplify using HAL board subtypes
This commit is contained in:
parent
fc8068adfe
commit
abb53eb9a2
@ -11,7 +11,7 @@
|
||||
maximum number of INS instances available on this platform. If more
|
||||
than 1 then redundent sensors may be available
|
||||
*/
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
#define INS_MAX_INSTANCES 3
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
#define INS_MAX_INSTANCES 2
|
||||
|
@ -21,7 +21,7 @@
|
||||
// L3G4200D gyro http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/CD00265057.pdf
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
||||
#include <AP_Math.h>
|
||||
#include "AP_InertialSensor_L3G4200D.h"
|
||||
|
@ -4,7 +4,7 @@
|
||||
#define __AP_INERTIAL_SENSOR_L3G4200D_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
||||
#include <AP_Progmem.h>
|
||||
#include "AP_InertialSensor.h"
|
||||
|
@ -20,7 +20,7 @@
|
||||
*/
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
#include "AP_InertialSensor_LSM9DS0.h"
|
||||
#include "../AP_HAL_Linux/GPIO.h"
|
||||
|
||||
|
@ -10,10 +10,12 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
#define MPU6000_DRDY_PIN 70
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF
|
||||
#include "../AP_HAL_Linux/GPIO.h"
|
||||
#define MPU6000_DRDY_PIN BBB_P8_14
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// MPU 6000 registers
|
||||
#define MPUREG_XG_OFFS_TC 0x00
|
||||
|
@ -22,7 +22,7 @@
|
||||
*/
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
||||
#include <AP_Math.h>
|
||||
#include "AP_InertialSensor_MPU9150.h"
|
||||
|
@ -4,7 +4,7 @@
|
||||
#define __AP_INERTIAL_SENSOR_MPU9150_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
||||
#include <AP_Progmem.h>
|
||||
#include "AP_InertialSensor.h"
|
||||
|
@ -17,6 +17,8 @@
|
||||
*/
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
||||
#include "AP_InertialSensor_MPU9250.h"
|
||||
#include "../AP_HAL_Linux/GPIO.h"
|
||||
|
||||
@ -621,4 +623,8 @@ float AP_InertialSensor_MPU9250::get_delta_time() const
|
||||
{
|
||||
// the sensor runs at 200Hz
|
||||
return 0.005 * _num_samples;
|
||||
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
||||
|
@ -1,7 +1,7 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
#include "AP_InertialSensor_Oilpan.h"
|
||||
|
||||
const extern AP_HAL::HAL& hal;
|
||||
|
Loading…
Reference in New Issue
Block a user