aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-12-07 10:34:25 +0100
committerLorenz Meier <lm@inf.ethz.ch>2013-12-07 10:34:32 +0100
commit7becbcdbd59c0842ff44e682df0f13fd067def10 (patch)
tree3d76b47eb3b72dee302be2d083c8e41dfe007324 /src/drivers
parent264ef47197432d2cc1372cabf93c3bd7a52df0aa (diff)
downloadpx4-firmware-7becbcdbd59c0842ff44e682df0f13fd067def10.tar.gz
px4-firmware-7becbcdbd59c0842ff44e682df0f13fd067def10.tar.bz2
px4-firmware-7becbcdbd59c0842ff44e682df0f13fd067def10.zip
Made all usual suspects default to their custom names and only register the default name if its not already taken by someone else
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp7
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp7
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp33
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp33
4 files changed, 60 insertions, 20 deletions
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index 5f0ce4ff8..22ad301ff 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -77,6 +77,7 @@
*/
#define HMC5883L_ADDRESS PX4_I2C_OBDEV_HMC5883
+#define HMC5883L_DEVICE_PATH "/dev/hmc5883"
/* Max measurement rate is 160Hz, however with 160 it will be set to 166 Hz, therefore workaround using 150 */
#define HMC5883_CONVERSION_INTERVAL (1000000 / 150) /* microseconds */
@@ -315,7 +316,7 @@ extern "C" __EXPORT int hmc5883_main(int argc, char *argv[]);
HMC5883::HMC5883(int bus) :
- I2C("HMC5883", MAG_DEVICE_PATH, bus, HMC5883L_ADDRESS, 400000),
+ I2C("HMC5883", HMC5883L_DEVICE_PATH, bus, HMC5883L_ADDRESS, 400000),
_measure_ticks(0),
_reports(nullptr),
_range_scale(0), /* default range scale from counts to gauss */
@@ -1256,7 +1257,7 @@ start()
goto fail;
/* set the poll rate to default, starts automatic data collection */
- fd = open(MAG_DEVICE_PATH, O_RDONLY);
+ fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
if (fd < 0)
goto fail;
@@ -1288,7 +1289,7 @@ test()
ssize_t sz;
int ret;
- int fd = open(MAG_DEVICE_PATH, O_RDONLY);
+ int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
if (fd < 0)
err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", MAG_DEVICE_PATH);
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 103b26ac5..d816b1a59 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -360,6 +360,13 @@ L3GD20::init()
if (_reports == nullptr)
goto out;
+ /* try to claim the generic accel node as well - it's OK if we fail at this */
+ ret = register_driver(GYRO_DEVICE_PATH, &fops, 0666, (void *)this);
+
+ if (ret == OK) {
+ log("default gyro device");
+ }
+
/* advertise sensor topic */
struct gyro_report zero_report;
memset(&zero_report, 0, sizeof(zero_report));
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index 47109b67d..229b052a9 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -78,7 +78,8 @@ static const int ERROR = -1;
#define DIR_WRITE (0<<7)
#define ADDR_INCREMENT (1<<6)
-
+#define LSM303D_DEVICE_PATH_MAG "/dev/lsm303d_mag"
+#define LSM303D_DEVICE_PATH_ACCEL "/dev/lsm303d_accel"
/* register addresses: A: accel, M: mag, T: temp */
#define ADDR_WHO_AM_I 0x0F
@@ -551,6 +552,20 @@ LSM303D::init()
reset();
+ /* try to claim the generic accel node as well - it's OK if we fail at this */
+ ret = register_driver(ACCEL_DEVICE_PATH, &fops, 0666, (void *)this);
+
+ if (ret == OK) {
+ log("default accel device");
+ }
+
+ /* try to claim the generic accel node as well - it's OK if we fail at this */
+ mag_ret = register_driver(MAG_DEVICE_PATH, &fops, 0666, (void *)this);
+
+ if (mag_ret == OK) {
+ log("default mag device");
+ }
+
/* advertise mag topic */
struct mag_report zero_mag_report;
memset(&zero_mag_report, 0, sizeof(zero_mag_report));
@@ -1491,7 +1506,7 @@ LSM303D::print_registers()
}
LSM303D_mag::LSM303D_mag(LSM303D *parent) :
- CDev("LSM303D_mag", MAG_DEVICE_PATH),
+ CDev("LSM303D_mag", "/dev/lsm303d_mag"),
_parent(parent)
{
}
@@ -1556,7 +1571,7 @@ start()
errx(0, "already started");
/* create the driver */
- g_dev = new LSM303D(1 /* XXX magic number */, ACCEL_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
+ g_dev = new LSM303D(1 /* XXX magic number */, LSM303D_DEVICE_PATH_MAG, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
if (g_dev == nullptr) {
warnx("failed instantiating LSM303D obj");
@@ -1567,7 +1582,7 @@ start()
goto fail;
/* set the poll rate to default, starts automatic data collection */
- fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
+ fd = open(LSM303D_DEVICE_PATH_ACCEL, O_RDONLY);
if (fd < 0)
goto fail;
@@ -1575,7 +1590,7 @@ start()
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
goto fail;
- fd_mag = open(MAG_DEVICE_PATH, O_RDONLY);
+ fd_mag = open(LSM303D_DEVICE_PATH_MAG, O_RDONLY);
/* don't fail if open cannot be opened */
if (0 <= fd_mag) {
@@ -1610,10 +1625,10 @@ test()
int ret;
/* get the driver */
- fd_accel = open(ACCEL_DEVICE_PATH, O_RDONLY);
+ fd_accel = open(LSM303D_DEVICE_PATH_ACCEL, O_RDONLY);
if (fd_accel < 0)
- err(1, "%s open failed", ACCEL_DEVICE_PATH);
+ err(1, "%s open failed", LSM303D_DEVICE_PATH_ACCEL);
/* do a simple demand read */
sz = read(fd_accel, &accel_report, sizeof(accel_report));
@@ -1639,10 +1654,10 @@ test()
struct mag_report m_report;
/* get the driver */
- fd_mag = open(MAG_DEVICE_PATH, O_RDONLY);
+ fd_mag = open(LSM303D_DEVICE_PATH_MAG, O_RDONLY);
if (fd_mag < 0)
- err(1, "%s open failed", MAG_DEVICE_PATH);
+ err(1, "%s open failed", LSM303D_DEVICE_PATH_MAG);
/* check if mag is onboard or external */
if ((ret = ioctl(fd_mag, MAGIOCGEXTERNAL, 0)) < 0)
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index 6bfa583fb..ce0010752 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -75,6 +75,9 @@
#define DIR_READ 0x80
#define DIR_WRITE 0x00
+#define MPU_DEVICE_PATH_ACCEL "/dev/mpu6000_accel"
+#define MPU_DEVICE_PATH_GYRO "/dev/mpu6000_gyro"
+
// MPU 6000 registers
#define MPUREG_WHOAMI 0x75
#define MPUREG_SMPLRT_DIV 0x19
@@ -359,7 +362,7 @@ private:
extern "C" { __EXPORT int mpu6000_main(int argc, char *argv[]); }
MPU6000::MPU6000(int bus, spi_dev_e device) :
- SPI("MPU6000", ACCEL_DEVICE_PATH, bus, device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED),
+ SPI("MPU6000", MPU_DEVICE_PATH_ACCEL, bus, device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED),
_gyro(new MPU6000_gyro(this)),
_product(0),
_call_interval(0),
@@ -468,6 +471,20 @@ MPU6000::init()
/* fetch an initial set of measurements for advertisement */
measure();
+ /* try to claim the generic accel node as well - it's OK if we fail at this */
+ ret = register_driver(ACCEL_DEVICE_PATH, &fops, 0666, (void *)this);
+
+ if (ret == OK) {
+ log("default accel device");
+ }
+
+ /* try to claim the generic accel node as well - it's OK if we fail at this */
+ ret = register_driver(GYRO_DEVICE_PATH, &fops, 0666, (void *)this);
+
+ if (ret == OK) {
+ log("default gyro device");
+ }
+
if (gyro_ret != OK) {
_gyro_topic = -1;
} else {
@@ -1290,7 +1307,7 @@ MPU6000::print_info()
}
MPU6000_gyro::MPU6000_gyro(MPU6000 *parent) :
- CDev("MPU6000_gyro", GYRO_DEVICE_PATH),
+ CDev("MPU6000_gyro", MPU_DEVICE_PATH_GYRO),
_parent(parent)
{
}
@@ -1352,7 +1369,7 @@ start()
goto fail;
/* set the poll rate to default, starts automatic data collection */
- fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
+ fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY);
if (fd < 0)
goto fail;
@@ -1384,17 +1401,17 @@ test()
ssize_t sz;
/* get the driver */
- int fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
+ int fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY);
if (fd < 0)
err(1, "%s open failed (try 'mpu6000 start' if the driver is not running)",
- ACCEL_DEVICE_PATH);
+ MPU_DEVICE_PATH_ACCEL);
/* get the driver */
- int fd_gyro = open(GYRO_DEVICE_PATH, O_RDONLY);
+ int fd_gyro = open(MPU_DEVICE_PATH_GYRO, O_RDONLY);
if (fd_gyro < 0)
- err(1, "%s open failed", GYRO_DEVICE_PATH);
+ err(1, "%s open failed", MPU_DEVICE_PATH_GYRO);
/* reset to manual polling */
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MANUAL) < 0)
@@ -1452,7 +1469,7 @@ test()
void
reset()
{
- int fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
+ int fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY);
if (fd < 0)
err(1, "failed ");