l3gd20: use register_class_devname()

This commit is contained in:
Andrew Tridgell 2013-12-07 22:45:10 +11:00 committed by Lorenz Meier
parent 5ee41bc083
commit 5a88dc02a7
1 changed files with 20 additions and 17 deletions

View File

@ -66,6 +66,8 @@
#include <board_config.h> #include <board_config.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp> #include <mathlib/math/filter/LowPassFilter2p.hpp>
#define L3GD20_DEVICE_PATH "/dev/l3gd20"
/* oddly, ERROR is not defined for c++ */ /* oddly, ERROR is not defined for c++ */
#ifdef ERROR #ifdef ERROR
# undef ERROR # undef ERROR
@ -199,6 +201,7 @@ private:
float _gyro_range_scale; float _gyro_range_scale;
float _gyro_range_rad_s; float _gyro_range_rad_s;
orb_advert_t _gyro_topic; orb_advert_t _gyro_topic;
int _class_instance;
unsigned _current_rate; unsigned _current_rate;
unsigned _orientation; unsigned _orientation;
@ -317,6 +320,7 @@ L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) :
_gyro_range_scale(0.0f), _gyro_range_scale(0.0f),
_gyro_range_rad_s(0.0f), _gyro_range_rad_s(0.0f),
_gyro_topic(-1), _gyro_topic(-1),
_class_instance(-1),
_current_rate(0), _current_rate(0),
_orientation(SENSOR_BOARD_ROTATION_270_DEG), _orientation(SENSOR_BOARD_ROTATION_270_DEG),
_read(0), _read(0),
@ -346,6 +350,9 @@ L3GD20::~L3GD20()
if (_reports != nullptr) if (_reports != nullptr)
delete _reports; delete _reports;
if (_class_instance != -1)
unregister_class_devname(GYRO_DEVICE_PATH, _class_instance);
/* delete the perf counter */ /* delete the perf counter */
perf_free(_sample_perf); perf_free(_sample_perf);
} }
@ -365,17 +372,13 @@ L3GD20::init()
if (_reports == nullptr) if (_reports == nullptr)
goto out; goto out;
/* try to claim the generic accel node as well - it's OK if we fail at this */ _class_instance = register_class_devname(GYRO_DEVICE_PATH);
ret = register_driver(GYRO_DEVICE_PATH, &fops, 0666, (void *)this); if (_class_instance == CLASS_DEVICE_PRIMARY) {
/* advertise sensor topic */
if (ret == OK) { struct gyro_report zero_report;
log("default gyro device"); memset(&zero_report, 0, sizeof(zero_report));
} _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &zero_report);
}
/* advertise sensor topic */
struct gyro_report zero_report;
memset(&zero_report, 0, sizeof(zero_report));
_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &zero_report);
reset(); reset();
@ -743,7 +746,7 @@ L3GD20::reset()
/* set default configuration */ /* set default configuration */
write_reg(ADDR_CTRL_REG1, REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE); write_reg(ADDR_CTRL_REG1, REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
write_reg(ADDR_CTRL_REG2, 0); /* disable high-pass filters */ write_reg(ADDR_CTRL_REG2, 0); /* disable high-pass filters */
write_reg(ADDR_CTRL_REG3, 0); /* no interrupts - we don't use them */ write_reg(ADDR_CTRL_REG3, 0); /* no interrupts - we don't use them */
write_reg(ADDR_CTRL_REG4, REG4_BDU); write_reg(ADDR_CTRL_REG4, REG4_BDU);
write_reg(ADDR_CTRL_REG5, 0); write_reg(ADDR_CTRL_REG5, 0);
@ -922,7 +925,7 @@ start()
errx(0, "already started"); errx(0, "already started");
/* create the driver */ /* create the driver */
g_dev = new L3GD20(1 /* XXX magic number */, GYRO_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO); g_dev = new L3GD20(1 /* SPI bus 1 */, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
if (g_dev == nullptr) if (g_dev == nullptr)
goto fail; goto fail;
@ -931,7 +934,7 @@ start()
goto fail; goto fail;
/* set the poll rate to default, starts automatic data collection */ /* set the poll rate to default, starts automatic data collection */
fd = open(GYRO_DEVICE_PATH, O_RDONLY); fd = open(L3GD20_DEVICE_PATH, O_RDONLY);
if (fd < 0) if (fd < 0)
goto fail; goto fail;
@ -963,10 +966,10 @@ test()
ssize_t sz; ssize_t sz;
/* get the driver */ /* get the driver */
fd_gyro = open(GYRO_DEVICE_PATH, O_RDONLY); fd_gyro = open(L3GD20_DEVICE_PATH, O_RDONLY);
if (fd_gyro < 0) if (fd_gyro < 0)
err(1, "%s open failed", GYRO_DEVICE_PATH); err(1, "%s open failed", L3GD20_DEVICE_PATH);
/* reset to manual polling */ /* reset to manual polling */
if (ioctl(fd_gyro, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MANUAL) < 0) if (ioctl(fd_gyro, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MANUAL) < 0)
@ -999,7 +1002,7 @@ test()
void void
reset() reset()
{ {
int fd = open(GYRO_DEVICE_PATH, O_RDONLY); int fd = open(L3GD20_DEVICE_PATH, O_RDONLY);
if (fd < 0) if (fd < 0)
err(1, "failed "); err(1, "failed ");