Browse Source

refactor rm3100: use driver base class

sbg
Beat Küng 5 years ago committed by Daniel Agar
parent
commit
00280d55c2
  1. 4
      boards/modalai/fc-v1/init/rc.board_sensors
  2. 4
      boards/nxp/fmurt1062-v1/init/rc.board_sensors
  3. 4
      boards/px4/fmu-v3/init/rc.board_sensors
  4. 2
      boards/px4/fmu-v4/init/rc.board_sensors
  5. 2
      boards/px4/fmu-v4pro/init/rc.board_sensors
  6. 4
      boards/px4/fmu-v5/init/rc.board_sensors
  7. 33
      src/drivers/magnetometer/rm3100/rm3100.cpp
  8. 58
      src/drivers/magnetometer/rm3100/rm3100.h
  9. 16
      src/drivers/magnetometer/rm3100/rm3100_i2c.cpp
  10. 310
      src/drivers/magnetometer/rm3100/rm3100_main.cpp
  11. 122
      src/drivers/magnetometer/rm3100/rm3100_main.h
  12. 20
      src/drivers/magnetometer/rm3100/rm3100_spi.cpp

4
boards/modalai/fc-v1/init/rc.board_sensors

@ -29,5 +29,5 @@ qmc5883 -X start @@ -29,5 +29,5 @@ qmc5883 -X start
# Internal I2C Baro
bmp388 -I start
# External RM3100 (I2C or SPI)
rm3100 start
# External RM3100
rm3100 -X start

4
boards/nxp/fmurt1062-v1/init/rc.board_sensors

@ -48,8 +48,8 @@ ist8310 -I start @@ -48,8 +48,8 @@ ist8310 -I start
# Baro on internal SPI
ms5611 -s start
# External RM3100 (I2C or SPI)
rm3100 start
# External RM3100
rm3100 -X start
# Possible pmw3901 optical flow sensor
pmw3901 -S start

4
boards/px4/fmu-v3/init/rc.board_sensors

@ -117,7 +117,7 @@ else @@ -117,7 +117,7 @@ else
lsm303d start
fi
# External RM3100 (I2C or SPI)
rm3100 start
# External RM3100
rm3100 -X start
unset BOARD_FMUV3

2
boards/px4/fmu-v4/init/rc.board_sensors

@ -19,7 +19,7 @@ hmc5883 -T -X start @@ -19,7 +19,7 @@ hmc5883 -T -X start
lis3mdl -X start
ist8310 -X start
qmc5883 -X start
rm3100 start
rm3100 -X start
# Internal SPI
ms5611 -s start

2
boards/px4/fmu-v4pro/init/rc.board_sensors

@ -24,7 +24,7 @@ hmc5883 -T -X start @@ -24,7 +24,7 @@ hmc5883 -T -X start
qmc5883 -X start
# RM3100
rm3100 start
rm3100 -X start
# Internal SPI
ms5611 -s start

4
boards/px4/fmu-v5/init/rc.board_sensors

@ -42,5 +42,5 @@ ist8310 -I start @@ -42,5 +42,5 @@ ist8310 -I start
# Baro on internal SPI
ms5611 -s start
# External RM3100 (I2C or SPI)
rm3100 start
# External RM3100
rm3100 -X start

33
src/drivers/magnetometer/rm3100/rm3100.cpp

@ -41,9 +41,9 @@ @@ -41,9 +41,9 @@
#include "rm3100.h"
RM3100::RM3100(device::Device *interface, const char *path, enum Rotation rotation) :
CDev("RM3100", path),
ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id())),
RM3100::RM3100(device::Device *interface, enum Rotation rotation, I2CSPIBusOption bus_option, int bus) :
CDev("RM3100", nullptr),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id()), bus_option, bus),
_interface(interface),
_reports(nullptr),
_scale{},
@ -80,9 +80,6 @@ RM3100::RM3100(device::Device *interface, const char *path, enum Rotation rotati @@ -80,9 +80,6 @@ RM3100::RM3100(device::Device *interface, const char *path, enum Rotation rotati
RM3100::~RM3100()
{
/* make sure we are truly inactive */
stop();
if (_reports != nullptr) {
delete _reports;
}
@ -101,9 +98,6 @@ RM3100::~RM3100() @@ -101,9 +98,6 @@ RM3100::~RM3100()
int
RM3100::self_test()
{
/* Stop current measurements */
stop();
/* Chances are that a poll event was triggered, so wait for conversion and read registers in order to clear DRDY bit */
usleep(RM3100_CONVERSION_INTERVAL);
collect();
@ -144,9 +138,6 @@ RM3100::self_test() @@ -144,9 +138,6 @@ RM3100::self_test()
ret = !((cmd & BIST_XYZ_OK) == BIST_XYZ_OK);
/* Restart measurement state machine */
start();
return ret;
}
@ -287,7 +278,7 @@ RM3100::convert_signed(int32_t *n) @@ -287,7 +278,7 @@ RM3100::convert_signed(int32_t *n)
}
void
RM3100::Run()
RM3100::RunImpl()
{
/* _measure_interval == 0 is used as _task_should_exit */
if (_measure_interval == 0) {
@ -343,6 +334,9 @@ RM3100::init() @@ -343,6 +334,9 @@ RM3100::init()
PX4_ERR("self test failed");
}
_measure_interval = RM3100_CONVERSION_INTERVAL;
start();
return ret;
}
@ -474,8 +468,9 @@ RM3100::measure() @@ -474,8 +468,9 @@ RM3100::measure()
}
void
RM3100::print_info()
RM3100::print_status()
{
I2CSPIDriverBase::print_status();
perf_print_counter(_sample_perf);
perf_print_counter(_comms_errors);
PX4_INFO("poll interval: %u", _measure_interval);
@ -591,18 +586,8 @@ RM3100::start() @@ -591,18 +586,8 @@ RM3100::start()
_reports->flush();
set_default_register_values();
_measure_interval = (RM3100_CONVERSION_INTERVAL);
/* schedule a cycle to start things */
ScheduleNow();
}
void
RM3100::stop()
{
if (_measure_interval > 0) {
/* ensure no new items are queued while we cancel this one */
_measure_interval = 0;
ScheduleClear();
}
}

58
src/drivers/magnetometer/rm3100/rm3100.h

@ -52,7 +52,7 @@ @@ -52,7 +52,7 @@
#include <px4_platform_common/defines.h>
#include <systemlib/err.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/i2c_spi_buses.h>
/**
* RM3100 internal constants and data structures.
@ -97,17 +97,8 @@ @@ -97,17 +97,8 @@
#define NUM_BUS_OPTIONS (sizeof(bus_options)/sizeof(bus_options[0]))
/* interface factories */
extern device::Device *RM3100_SPI_interface(int bus);
extern device::Device *RM3100_I2C_interface(int bus);
typedef device::Device *(*RM3100_constructor)(int);
enum RM3100_BUS {
RM3100_BUS_ALL = 0,
RM3100_BUS_I2C_INTERNAL,
RM3100_BUS_I2C_EXTERNAL,
RM3100_BUS_SPI_INTERNAL,
RM3100_BUS_SPI_EXTERNAL
};
extern device::Device *RM3100_SPI_interface(int bus, uint32_t devid, int bus_frequency, spi_mode_e spi_mode);
extern device::Device *RM3100_I2C_interface(int bus, int bus_frequency);
enum OPERATING_MODE {
CONTINUOUS = 0,
@ -115,34 +106,32 @@ enum OPERATING_MODE { @@ -115,34 +106,32 @@ enum OPERATING_MODE {
};
class RM3100 : public device::CDev, public px4::ScheduledWorkItem
class RM3100 : public device::CDev, public I2CSPIDriver<RM3100>
{
public:
RM3100(device::Device *interface, const char *path, enum Rotation rotation);
RM3100(device::Device *interface, enum Rotation rotation, I2CSPIBusOption bus_option, int bus);
virtual ~RM3100();
virtual int init();
static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
int runtime_instance);
static void print_usage();
virtual int ioctl(struct file *file_pointer, int cmd, unsigned long arg);
void custom_method(const BusCLIArguments &cli) override;
virtual int read(struct file *file_pointer, char *buffer, size_t buffer_len);
int init() override;
/**
* Diagnostics - print some basic information about the driver.
*/
void print_info();
int ioctl(struct file *file_pointer, int cmd, unsigned long arg) override;
int read(struct file *file_pointer, char *buffer, size_t buffer_len) override;
void print_status() override;
/**
* Configures the device with default register values.
*/
int set_default_register_values();
/**
* Stop the automatic measurement state machine.
*/
void stop();
void RunImpl();
protected:
Device *_interface;
@ -201,21 +190,6 @@ private: @@ -201,21 +190,6 @@ private:
*/
void convert_signed(int32_t *n);
/**
* @brief Performs a poll cycle; collect from the previous measurement
* and start a new one.
*
* This is the heart of the measurement state machine. This function
* alternately starts a measurement, or collects the data from the
* previous measurement.
*
* When the interval between measurements is greater than the minimum
* measurement interval, a gap is inserted between collection
* and measurement to provide the most recent measurement possible
* at the next interval.
*/
void Run() override;
/**
* Issue a measurement command.
*

16
src/drivers/magnetometer/rm3100/rm3100_i2c.cpp

@ -57,14 +57,12 @@ @@ -57,14 +57,12 @@
#include "board_config.h"
#include "rm3100.h"
#if defined(PX4_I2C_BUS_ONBOARD) || defined(PX4_I2C_BUS_EXPANSION)
#define RM3100_ADDRESS 0x20
class RM3100_I2C : public device::I2C
{
public:
RM3100_I2C(int bus);
RM3100_I2C(int bus, int bus_frequency);
virtual ~RM3100_I2C() = default;
virtual int init();
@ -78,16 +76,16 @@ protected: @@ -78,16 +76,16 @@ protected:
};
device::Device *
RM3100_I2C_interface(int bus);
RM3100_I2C_interface(int bus, int bus_frequency);
device::Device *
RM3100_I2C_interface(int bus)
RM3100_I2C_interface(int bus, int bus_frequency)
{
return new RM3100_I2C(bus);
return new RM3100_I2C(bus, bus_frequency);
}
RM3100_I2C::RM3100_I2C(int bus) :
I2C("RM300_I2C", nullptr, bus, RM3100_ADDRESS, 400000)
RM3100_I2C::RM3100_I2C(int bus, int bus_frequency) :
I2C("RM300_I2C", nullptr, bus, RM3100_ADDRESS, bus_frequency)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_RM3100;
}
@ -170,5 +168,3 @@ RM3100_I2C::write(unsigned address, void *data, unsigned count) @@ -170,5 +168,3 @@ RM3100_I2C::write(unsigned address, void *data, unsigned count)
return transfer(&buf[0], count + 1, nullptr, 0);
}
#endif /* PX4_I2C_OBDEV_RM3100 */

310
src/drivers/magnetometer/rm3100/rm3100_main.cpp

@ -37,312 +37,106 @@ @@ -37,312 +37,106 @@
* Driver for the RM3100 magnetometer connected via I2C or SPI.
*/
#include "rm3100_main.h"
#include "rm3100.h"
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/module.h>
/**
* Driver 'main' command.
*/
extern "C" __EXPORT int rm3100_main(int argc, char *argv[]);
int
rm3100::info(RM3100_BUS bus_id)
{
struct rm3100_bus_option &bus = find_bus(bus_id);
PX4_WARN("running on bus: %u (%s)\n", (unsigned)bus.bus_id, bus.devpath);
bus.dev->print_info();
return 1;
}
bool
rm3100::init(RM3100_BUS bus_id)
I2CSPIDriverBase *RM3100::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
int runtime_instance)
{
struct rm3100_bus_option &bus = find_bus(bus_id);
const char *path = bus.devpath;
device::Device *interface = nullptr;
int fd = open(path, O_RDONLY);
if (iterator.busType() == BOARD_I2C_BUS) {
interface = RM3100_I2C_interface(iterator.bus(), cli.bus_frequency);
if (fd < 0) {
return false;
} else if (iterator.busType() == BOARD_SPI_BUS) {
interface = RM3100_SPI_interface(iterator.bus(), iterator.devid(), cli.bus_frequency, cli.spi_mode);
}
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
close(fd);
errx(1, "Failed to setup poll rate");
return false;
} else {
PX4_INFO("Poll rate set to 100 Hz");
if (interface == nullptr) {
PX4_ERR("alloc failed");
return nullptr;
}
close(fd);
return true;
}
bool
rm3100::start_bus(struct rm3100_bus_option &bus, Rotation rotation)
{
if (bus.dev != nullptr) {
errx(1, "bus option already started");
return false;
}
device::Device *interface = bus.interface_constructor(bus.busnum);
if (interface->init() != OK) {
delete interface;
warnx("no device on bus %u", (unsigned)bus.bus_id);
return false;
PX4_DEBUG("no device on bus %i (devid 0x%x)", iterator.bus(), iterator.devid());
return nullptr;
}
bus.dev = new RM3100(interface, bus.devpath, rotation);
if (bus.dev != nullptr &&
bus.dev->init() != OK) {
delete bus.dev;
bus.dev = NULL;
return false;
}
return true;
}
int
rm3100::start(RM3100_BUS bus_id, Rotation rotation)
{
bool started = false;
for (unsigned i = 0; i < NUM_BUS_OPTIONS; i++) {
if (bus_id == RM3100_BUS_ALL && bus_options[i].dev != NULL) {
// this device is already started
continue;
}
if (bus_id != RM3100_BUS_ALL && bus_options[i].bus_id != bus_id) {
// not the one that is asked for
continue;
}
started |= start_bus(bus_options[i], rotation);
//init(bus_id);
}
return started;
}
int
rm3100::stop()
{
bool stopped = false;
for (unsigned i = 0; i < NUM_BUS_OPTIONS; i++) {
if (bus_options[i].dev != nullptr) {
bus_options[i].dev->stop();
delete bus_options[i].dev;
bus_options[i].dev = nullptr;
stopped = true;
}
}
return !stopped;
}
bool
rm3100::test(RM3100_BUS bus_id)
{
struct rm3100_bus_option &bus = find_bus(bus_id);
sensor_mag_s report;
ssize_t sz;
int ret;
const char *path = bus.devpath;
int fd = open(path, O_RDONLY);
if (fd < 0) {
PX4_WARN("%s open failed (try 'rm3100 start')", path);
return 1;
}
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
if (sz != sizeof(report)) {
PX4_WARN("immediate read failed");
return 1;
}
RM3100 *dev = new RM3100(interface, cli.rotation, iterator.configuredBusOption(), iterator.bus());
print_message(report);
/* check if mag is onboard or external */
if (ioctl(fd, MAGIOCGEXTERNAL, 0) < 0) {
PX4_WARN("failed to get if mag is onboard or external");
return 1;
if (dev == nullptr) {
delete interface;
return nullptr;
}
struct pollfd fds;
/* read the sensor 5x and report each value */
for (unsigned i = 0; i < 5; i++) {
/* wait for data to be ready */
fds.fd = fd;
fds.events = POLLIN;
ret = poll(&fds, 1, 2000);
if (ret != 1) {
PX4_WARN("timed out waiting for sensor data");
return 1;
}
/* now go get it */
sz = read(fd, &report, sizeof(report));
if (sz != sizeof(report)) {
PX4_WARN("periodic read failed");
return 1;
}
print_message(report);
if (OK != dev->init()) {
delete dev;
return nullptr;
}
PX4_INFO("PASS");
return 1;
return dev;
}
bool
rm3100::reset(RM3100_BUS bus_id)
void
RM3100::custom_method(const BusCLIArguments &cli)
{
struct rm3100_bus_option &bus = find_bus(bus_id);
const char *path = bus.devpath;
int fd = open(path, O_RDONLY);
if (fd < 0) {
PX4_WARN("open failed ");
return 1;
}
if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
PX4_WARN("driver reset failed");
return 1;
}
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
PX4_WARN("driver poll restart failed");
return 1;
}
return 0;
reset();
}
void
rm3100::usage()
void RM3100::print_usage()
{
PX4_WARN("missing command: try 'start', 'info', 'test', 'reset', 'info'");
PX4_WARN("options:");
PX4_WARN(" -R rotation");
PX4_WARN(" -X external I2C bus");
PX4_WARN(" -I internal I2C bus");
PX4_WARN(" -S external SPI bus");
PX4_WARN(" -s internal SPI bus");
PRINT_MODULE_USAGE_NAME("rm3100", "driver");
PRINT_MODULE_USAGE_SUBCATEGORY("magnetometer");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, true);
PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true);
PRINT_MODULE_USAGE_COMMAND("reset");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
}
int
rm3100_main(int argc, char *argv[])
extern "C" int rm3100_main(int argc, char *argv[])
{
int myoptind = 1;
using ThisDriver = RM3100;
int ch;
const char *myoptarg = nullptr;
BusCLIArguments cli{true, true};
cli.default_i2c_frequency = 400000;
cli.default_spi_frequency = 1 * 1000 * 1000;
enum RM3100_BUS bus_id = RM3100_BUS_ALL;
enum Rotation rotation = ROTATION_NONE;
while ((ch = px4_getopt(argc, argv, "XISR:T", &myoptind, &myoptarg)) != EOF) {
while ((ch = cli.getopt(argc, argv, "R:")) != EOF) {
switch (ch) {
case 'R':
rotation = (enum Rotation)atoi(myoptarg);
break;
case 'I':
bus_id = RM3100_BUS_I2C_INTERNAL;
break;
case 'X':
bus_id = RM3100_BUS_I2C_EXTERNAL;
cli.rotation = (enum Rotation)atoi(cli.optarg());
break;
case 'S':
bus_id = RM3100_BUS_SPI_EXTERNAL;
break;
case 's':
bus_id = RM3100_BUS_SPI_INTERNAL;
break;
default:
rm3100::usage();
return 0;
}
}
if (myoptind >= argc) {
rm3100::usage();
const char *verb = cli.optarg();
if (!verb) {
ThisDriver::print_usage();
return -1;
}
const char *verb = argv[myoptind];
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_MAG_DEVTYPE_RM3100);
// Start/load the driver
if (!strcmp(verb, "start")) {
if (rm3100::start(bus_id, rotation)) {
rm3100::init(bus_id);
return 0;
} else {
return 1;
}
return ThisDriver::module_start(cli, iterator);
}
// Stop the driver
if (!strcmp(verb, "stop")) {
return rm3100::stop();
return ThisDriver::module_stop(iterator);
}
// Test the driver/device
if (!strcmp(verb, "test")) {
return rm3100::test(bus_id);
if (!strcmp(verb, "status")) {
return ThisDriver::module_status(iterator);
}
// Reset the driver
if (!strcmp(verb, "reset")) {
return rm3100::reset(bus_id);
}
// Print driver information
if (!strcmp(verb, "info") ||
!strcmp(verb, "status")) {
return rm3100::info(bus_id);
}
PX4_INFO("unrecognized command, try 'start', 'test', 'reset' or 'info'");
return 1;
}
struct
rm3100::rm3100_bus_option &rm3100::find_bus(RM3100_BUS bus_id)
{
for (unsigned i = 0; i < NUM_BUS_OPTIONS; i++) {
if ((bus_id == RM3100_BUS_ALL ||
bus_id == bus_options[i].bus_id) && bus_options[i].dev != NULL) {
return bus_options[i];
}
return ThisDriver::module_custom_method(cli, iterator);
}
errx(1, "bus %u not started", (unsigned)bus_id);
ThisDriver::print_usage();
return -1;
}

122
src/drivers/magnetometer/rm3100/rm3100_main.h

@ -1,122 +0,0 @@ @@ -1,122 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file rm3100_main.h
*/
#pragma once
#include "rm3100.h"
namespace rm3100
{
/**
* @struct List of supported bus configurations
*/
struct rm3100_bus_option {
RM3100_BUS bus_id;
const char *devpath;
RM3100_constructor interface_constructor;
uint8_t busnum;
RM3100 *dev;
} bus_options[] = {
#ifdef PX4_I2C_BUS_EXPANSION
{ RM3100_BUS_I2C_EXTERNAL, "/dev/rm3100_ext", &RM3100_I2C_interface, PX4_I2C_BUS_EXPANSION, NULL },
#endif /* PX4_I2C_BUS_EXPANSION */
#ifdef PX4_I2C_BUS_EXPANSION1
{ RM3100_BUS_I2C_EXTERNAL, "/dev/rm3100_ext1", &RM3100_I2C_interface, PX4_I2C_BUS_EXPANSION1, NULL },
#endif /* PX4_I2C_BUS_EXPANSION1 */
#ifdef PX4_I2C_BUS_EXPANSION2
{ RM3100_BUS_I2C_EXTERNAL, "/dev/rm3100_ext2", &RM3100_I2C_interface, PX4_I2C_BUS_EXPANSION2, NULL },
#endif /* PX4_I2C_BUS_EXPANSION2 */
#ifdef PX4_I2C_BUS_ONBOARD
{ RM3100_BUS_I2C_INTERNAL, "/dev/rm3100_int", &RM3100_I2C_interface, PX4_I2C_BUS_ONBOARD, NULL },
#endif /* PX4_I2C_BUS_ONBOARD */
#ifdef PX4_SPIDEV_RM
{ RM3100_BUS_SPI_INTERNAL, "/dev/rm3100_spi_int", &RM3100_SPI_interface, PX4_SPI_BUS_SENSORS, NULL },
#endif /* PX4_SPIDEV_RM */
#ifdef PX4_SPIDEV_RM_EXT
{ RM3100_BUS_SPI_EXTERNAL, "/dev/rm3100_spi_ext", &RM3100_SPI_interface, PX4_SPI_BUS_EXT, NULL },
#endif /* PX4_SPIDEV_RM_EXT */
};
/**
* @brief Finds a bus structure for a bus_id
*/
rm3100_bus_option &find_bus(RM3100_BUS bus_id);
/**
* @brief Prints info about the driver.
*/
int info(RM3100_BUS bus_id);
/**
* @brief Initializes the driver -- sets defaults and starts a cycle
*/
bool init(RM3100_BUS bus_id);
/**
* @brief Resets the driver.
*/
bool reset(RM3100_BUS bus_id);
/**
* @brief Starts the driver for a specific bus option
*/
bool start_bus(struct rm3100_bus_option &bus, Rotation rotation);
/**
* @brief Starts the driver. This function call only returns once the driver
* is either successfully up and running or failed to start.
*/
int start(RM3100_BUS bus_id, Rotation rotation);
/**
* @brief Stop the driver.
*/
int stop();
/**
* @brief Perform some basic functional tests on the driver;
* make sure we can collect data from the sensor in polled
* and automatic modes.
*/
bool test(RM3100_BUS bus_id);
/**
* @brief Prints info about the driver argument usage.
*/
void usage();
} // namespace RM3100

20
src/drivers/magnetometer/rm3100/rm3100_spi.cpp

@ -55,8 +55,6 @@ @@ -55,8 +55,6 @@
#include "board_config.h"
#include "rm3100.h"
#if defined(PX4_SPIDEV_RM) || defined (PX4_SPIDEV_RM_EXT)
/* SPI protocol address bits */
#define DIR_READ (1<<7)
#define DIR_WRITE (0<<7)
@ -64,7 +62,7 @@ @@ -64,7 +62,7 @@
class RM3100_SPI : public device::SPI
{
public:
RM3100_SPI(int bus, uint32_t device);
RM3100_SPI(int bus, uint32_t devid, int bus_frequency, spi_mode_e spi_mode);
virtual ~RM3100_SPI() = default;
virtual int init();
@ -74,20 +72,16 @@ public: @@ -74,20 +72,16 @@ public:
};
device::Device *
RM3100_SPI_interface(int bus);
RM3100_SPI_interface(int bus, uint32_t devid, int bus_frequency, spi_mode_e spi_mode);
device::Device *
RM3100_SPI_interface(int bus)
RM3100_SPI_interface(int bus, uint32_t devid, int bus_frequency, spi_mode_e spi_mode)
{
#ifdef PX4_SPIDEV_RM_EXT
return new RM3100_SPI(bus, PX4_SPIDEV_RM_EXT);
#else
return new RM3100_SPI(bus, PX4_SPIDEV_RM);
#endif
return new RM3100_SPI(bus, devid, bus_frequency, spi_mode);
}
RM3100_SPI::RM3100_SPI(int bus, uint32_t device) :
SPI("RM3100_SPI", nullptr, bus, device, SPIDEV_MODE3, 1 * 1000 * 1000 /* */)
RM3100_SPI::RM3100_SPI(int bus, uint32_t devid, int bus_frequency, spi_mode_e spi_mode) :
SPI("RM3100_SPI", nullptr, bus, devid, spi_mode, bus_frequency)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_RM3100;
}
@ -170,5 +164,3 @@ RM3100_SPI::write(unsigned address, void *data, unsigned count) @@ -170,5 +164,3 @@ RM3100_SPI::write(unsigned address, void *data, unsigned count)
return transfer(&buf[0], &buf[0], count + 1);
}
#endif /* PX4_SPIDEV_RM || PX4_SPIDEV_RM_EXT */

Loading…
Cancel
Save