Driver headers: Move to 0-based indices

This commit is contained in:
Lorenz Meier 2015-02-03 13:43:28 +01:00
parent 4a8044f338
commit 16fea51e00
18 changed files with 31 additions and 19 deletions

View File

@ -46,7 +46,10 @@
#include "drv_sensor.h"
#include "drv_orb_dev.h"
#define ACCEL_DEVICE_PATH "/dev/accel"
#define ACCEL_BASE_DEVICE_PATH "/dev/accel"
#define ACCEL0_DEVICE_PATH "/dev/accel0"
#define ACCEL1_DEVICE_PATH "/dev/accel1"
#define ACCEL2_DEVICE_PATH "/dev/accel2"
/**
* accel report structure. Reads from the device must be in multiples of this

View File

@ -45,7 +45,7 @@
#include <stdint.h>
#include <sys/ioctl.h>
#define ADC_DEVICE_PATH "/dev/adc0"
#define ADC0_DEVICE_PATH "/dev/adc0"
/*
* ioctl definitions

View File

@ -48,7 +48,8 @@
#include "drv_sensor.h"
#include "drv_orb_dev.h"
#define AIRSPEED_DEVICE_PATH "/dev/airspeed"
#define AIRSPEED_BASE_DEVICE_PATH "/dev/airspeed"
#define AIRSPEED0_DEVICE_PATH "/dev/airspeed0"
/*
* ioctl() definitions

View File

@ -46,7 +46,8 @@
#include "drv_sensor.h"
#include "drv_orb_dev.h"
#define BARO_DEVICE_PATH "/dev/baro"
#define BARO_BASE_DEVICE_PATH "/dev/baro"
#define BARO0_DEVICE_PATH "/dev/baro0"
/**
* baro report structure. Reads from the device must be in multiples of this

View File

@ -44,4 +44,4 @@
#include "drv_orb_dev.h"
/* device path */
#define BATT_SMBUS_DEVICE_PATH "/dev/batt_smbus"
#define BATT_SMBUS0_DEVICE_PATH "/dev/batt_smbus0"

View File

@ -45,7 +45,7 @@
#include <stdint.h>
#include <sys/ioctl.h>
#define BLINKM_DEVICE_PATH "/dev/blinkm"
#define BLINKM0_DEVICE_PATH "/dev/blinkm0"
/*
* ioctl() definitions

View File

@ -52,7 +52,7 @@
#define GPS_DEFAULT_UART_PORT "/dev/ttyS3"
#endif
#define GPS_DEVICE_PATH "/dev/gps"
#define GPS0_DEVICE_PATH "/dev/gps0"
typedef enum {
GPS_DRIVER_MODE_NONE = 0,

View File

@ -46,7 +46,10 @@
#include "drv_sensor.h"
#include "drv_orb_dev.h"
#define GYRO_DEVICE_PATH "/dev/gyro"
#define GYRO_BASE_DEVICE_PATH "/dev/gyro"
#define GYRO0_DEVICE_PATH "/dev/gyro0"
#define GYRO1_DEVICE_PATH "/dev/gyro1"
#define GYRO2_DEVICE_PATH "/dev/gyro2"
/**
* gyro report structure. Reads from the device must be in multiples of this

View File

@ -42,7 +42,7 @@
#include <stdint.h>
#include <sys/ioctl.h>
#define LED_DEVICE_PATH "/dev/led"
#define LED0_DEVICE_PATH "/dev/led0"
#define _LED_BASE 0x2800

View File

@ -44,8 +44,10 @@
#include "drv_sensor.h"
#include "drv_orb_dev.h"
#define MAG_DEVICE_PATH "/dev/mag"
#define MAG_BASE_DEVICE_PATH "/dev/mag"
#define MAG0_DEVICE_PATH "/dev/mag0"
#define MAG1_DEVICE_PATH "/dev/mag0"
#define MAG2_DEVICE_PATH "/dev/mag0"
/**
* mag report structure. Reads from the device must be in multiples of this

View File

@ -56,7 +56,7 @@
#include <stdint.h>
#include <sys/ioctl.h>
#define MIXER_DEVICE_PATH "/dev/mixer"
#define MIXER0_DEVICE_PATH "/dev/mixer0"
/*
* ioctl() definitions

View File

@ -57,7 +57,8 @@ __BEGIN_DECLS
* PX4FMU with PX4IO connected) there may be other devices that
* respond to this protocol.
*/
#define PWM_OUTPUT_DEVICE_PATH "/dev/pwm_output"
#define PWM_OUTPUT_BASE_DEVICE_PATH "dev/pwm_output"
#define PWM_OUTPUT0_DEVICE_PATH "/dev/pwm_output0"
/**
* Maximum number of PWM output channels supported by the device.

View File

@ -44,7 +44,7 @@
#include "drv_sensor.h"
#include "drv_orb_dev.h"
#define PX4FLOW_DEVICE_PATH "/dev/px4flow"
#define PX4FLOW0_DEVICE_PATH "/dev/px4flow0"
/*
* ObjDev tag for px4flow data.

View File

@ -44,7 +44,8 @@
#include "drv_sensor.h"
#include "drv_orb_dev.h"
#define RANGE_FINDER_DEVICE_PATH "/dev/range_finder"
#define RANGE_FINDER_BASE_DEVICE_PATH "/dev/range_finder"
#define RANGE_FINDER0_DEVICE_PATH "/dev/range_finder0"
#define MB12XX_MAX_RANGEFINDERS 12 //Maximum number of RangeFinders that can be connected
enum RANGE_FINDER_TYPE {

View File

@ -55,7 +55,7 @@
* Input data may be obtained by subscribing to the input_rc
* object, or by poll/reading from the device.
*/
#define RC_INPUT_DEVICE_PATH "/dev/input_rc"
#define RC_INPUT0_DEVICE_PATH "/dev/input_rc0"
/**
* Maximum number of R/C input channels in the system. S.Bus has up to 18 channels.

View File

@ -43,7 +43,7 @@
#include <sys/ioctl.h>
/* more devices will be 1, 2, etc */
#define RGBLED_DEVICE_PATH "/dev/rgbled0"
#define RGBLED0_DEVICE_PATH "/dev/rgbled0"
/*
* ioctl() definitions

View File

@ -48,7 +48,7 @@
/**
* Path for the default S.BUS device
*/
#define SBUS_DEVICE_PATH "/dev/sbus"
#define SBUS0_DEVICE_PATH "/dev/sbus0"
#define _SBUS_BASE 0x2c00

View File

@ -62,7 +62,7 @@
#include <sys/ioctl.h>
#define TONEALARM_DEVICE_PATH "/dev/tone_alarm"
#define TONEALARM0_DEVICE_PATH "/dev/tone_alarm0"
#define _TONE_ALARM_BASE 0x7400
#define TONE_SET_ALARM _IOC(_TONE_ALARM_BASE, 1)