PX4 Firmware
PX4 Autopilot Software http://px4.io
rm3100_main.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file rm3100_main.cpp
36  *
37  * Driver for the RM3100 magnetometer connected via I2C or SPI.
38  */
39 
40 #include "rm3100_main.h"
41 #include <px4_platform_common/getopt.h>
42 
43 /**
44  * Driver 'main' command.
45  */
46 extern "C" __EXPORT int rm3100_main(int argc, char *argv[]);
47 
48 int
50 {
51  struct rm3100_bus_option &bus = find_bus(bus_id);
52 
53  PX4_WARN("running on bus: %u (%s)\n", (unsigned)bus.bus_id, bus.devpath);
54  bus.dev->print_info();
55  return 1;
56 }
57 
58 bool
60 {
61  struct rm3100_bus_option &bus = find_bus(bus_id);
62  const char *path = bus.devpath;
63 
64  int fd = open(path, O_RDONLY);
65 
66  if (fd < 0) {
67  return false;
68  }
69 
70  if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
71  close(fd);
72  errx(1, "Failed to setup poll rate");
73  return false;
74 
75  } else {
76  PX4_INFO("Poll rate set to 100 Hz");
77  }
78 
79  close(fd);
80 
81  return true;
82 }
83 
84 bool
86 {
87  if (bus.dev != nullptr) {
88  errx(1, "bus option already started");
89  return false;
90  }
91 
92  device::Device *interface = bus.interface_constructor(bus.busnum);
93 
94  if (interface->init() != OK) {
95  delete interface;
96  warnx("no device on bus %u", (unsigned)bus.bus_id);
97 
98  return false;
99  }
100 
101  bus.dev = new RM3100(interface, bus.devpath, rotation);
102 
103  if (bus.dev != nullptr &&
104  bus.dev->init() != OK) {
105  delete bus.dev;
106  bus.dev = NULL;
107  return false;
108  }
109 
110  return true;
111 }
112 
113 int
115 {
116  bool started = false;
117 
118  for (unsigned i = 0; i < NUM_BUS_OPTIONS; i++) {
119  if (bus_id == RM3100_BUS_ALL && bus_options[i].dev != NULL) {
120  // this device is already started
121  continue;
122  }
123 
124  if (bus_id != RM3100_BUS_ALL && bus_options[i].bus_id != bus_id) {
125  // not the one that is asked for
126  continue;
127  }
128 
129  started |= start_bus(bus_options[i], rotation);
130  //init(bus_id);
131  }
132 
133  return started;
134 }
135 
136 int
138 {
139  bool stopped = false;
140 
141  for (unsigned i = 0; i < NUM_BUS_OPTIONS; i++) {
142  if (bus_options[i].dev != nullptr) {
143  bus_options[i].dev->stop();
144  delete bus_options[i].dev;
145  bus_options[i].dev = nullptr;
146  stopped = true;
147  }
148  }
149 
150  return !stopped;
151 }
152 
153 bool
155 {
156  struct rm3100_bus_option &bus = find_bus(bus_id);
157  struct mag_report report;
158  ssize_t sz;
159  int ret;
160  const char *path = bus.devpath;
161 
162  int fd = open(path, O_RDONLY);
163 
164  if (fd < 0) {
165  PX4_WARN("%s open failed (try 'rm3100 start')", path);
166  return 1;
167  }
168 
169  /* do a simple demand read */
170  sz = read(fd, &report, sizeof(report));
171 
172  if (sz != sizeof(report)) {
173  PX4_WARN("immediate read failed");
174  return 1;
175  }
176 
177  print_message(report);
178 
179  /* check if mag is onboard or external */
180  if (ioctl(fd, MAGIOCGEXTERNAL, 0) < 0) {
181  PX4_WARN("failed to get if mag is onboard or external");
182  return 1;
183  }
184 
185  struct pollfd fds;
186 
187  /* read the sensor 5x and report each value */
188  for (unsigned i = 0; i < 5; i++) {
189 
190  /* wait for data to be ready */
191  fds.fd = fd;
192  fds.events = POLLIN;
193  ret = poll(&fds, 1, 2000);
194 
195  if (ret != 1) {
196  PX4_WARN("timed out waiting for sensor data");
197  return 1;
198  }
199 
200  /* now go get it */
201  sz = read(fd, &report, sizeof(report));
202 
203  if (sz != sizeof(report)) {
204  PX4_WARN("periodic read failed");
205  return 1;
206  }
207 
208  print_message(report);
209  }
210 
211  PX4_INFO("PASS");
212  return 1;
213 }
214 
215 bool
217 {
218  struct rm3100_bus_option &bus = find_bus(bus_id);
219  const char *path = bus.devpath;
220 
221  int fd = open(path, O_RDONLY);
222 
223  if (fd < 0) {
224  PX4_WARN("open failed ");
225  return 1;
226  }
227 
228  if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
229  PX4_WARN("driver reset failed");
230  return 1;
231  }
232 
233  if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
234  PX4_WARN("driver poll restart failed");
235  return 1;
236  }
237 
238  return 0;
239 }
240 
241 void
243 {
244  PX4_WARN("missing command: try 'start', 'info', 'test', 'reset', 'info'");
245  PX4_WARN("options:");
246  PX4_WARN(" -R rotation");
247  PX4_WARN(" -X external I2C bus");
248  PX4_WARN(" -I internal I2C bus");
249  PX4_WARN(" -S external SPI bus");
250  PX4_WARN(" -s internal SPI bus");
251 }
252 
253 int
254 rm3100_main(int argc, char *argv[])
255 {
256  int myoptind = 1;
257  int ch;
258  const char *myoptarg = nullptr;
259 
260  enum RM3100_BUS bus_id = RM3100_BUS_ALL;
261  enum Rotation rotation = ROTATION_NONE;
262 
263  while ((ch = px4_getopt(argc, argv, "XISR:T", &myoptind, &myoptarg)) != EOF) {
264  switch (ch) {
265  case 'R':
266  rotation = (enum Rotation)atoi(myoptarg);
267  break;
268 
269  case 'I':
270  bus_id = RM3100_BUS_I2C_INTERNAL;
271  break;
272 
273  case 'X':
274  bus_id = RM3100_BUS_I2C_EXTERNAL;
275  break;
276 
277  case 'S':
278  bus_id = RM3100_BUS_SPI_EXTERNAL;
279  break;
280 
281  case 's':
282  bus_id = RM3100_BUS_SPI_INTERNAL;
283  break;
284 
285  default:
286  rm3100::usage();
287  return 0;
288  }
289  }
290 
291  if (myoptind >= argc) {
292  rm3100::usage();
293  return -1;
294  }
295 
296  const char *verb = argv[myoptind];
297 
298  // Start/load the driver
299  if (!strcmp(verb, "start")) {
300 
301  if (rm3100::start(bus_id, rotation)) {
302 
303  rm3100::init(bus_id);
304 
305  return 0;
306 
307  } else {
308  return 1;
309  }
310  }
311 
312  // Stop the driver
313  if (!strcmp(verb, "stop")) {
314  return rm3100::stop();
315  }
316 
317  // Test the driver/device
318  if (!strcmp(verb, "test")) {
319  return rm3100::test(bus_id);
320  }
321 
322  // Reset the driver
323  if (!strcmp(verb, "reset")) {
324  return rm3100::reset(bus_id);
325  }
326 
327  // Print driver information
328  if (!strcmp(verb, "info") ||
329  !strcmp(verb, "status")) {
330  return rm3100::info(bus_id);
331  }
332 
333  PX4_INFO("unrecognized command, try 'start', 'test', 'reset' or 'info'");
334  return 1;
335 }
336 
337 struct
339 {
340  for (unsigned i = 0; i < NUM_BUS_OPTIONS; i++) {
341  if ((bus_id == RM3100_BUS_ALL ||
342  bus_id == bus_options[i].bus_id) && bus_options[i].dev != NULL) {
343  return bus_options[i];
344  }
345  }
346 
347  errx(1, "bus %u not started", (unsigned)bus_id);
348 }
#define MAGIOCGEXTERNAL
determine if mag is external or onboard
Definition: drv_mag.h:88
static struct bmp280_bus_option * find_bus(BMP280_BUS busid)
Definition: bmp280_main.cpp:75
#define SENSOR_POLLRATE_DEFAULT
poll at driver normal rate
Definition: drv_sensor.h:136
Definition: I2C.hpp:51
RM3100_BUS
Definition: rm3100.h:104
bool start_bus(struct rm3100_bus_option &bus, Rotation rotation)
Starts the driver for a specific bus option.
Definition: rm3100_main.cpp:85
Definition: rm3100.h:118
bool init(RM3100_BUS bus_id)
Initializes the driver – sets defaults and starts a cycle.
Definition: rm3100_main.cpp:59
__EXPORT int rm3100_main(int argc, char *argv[])
Driver &#39;main&#39; command.
static void read(bootloader_app_shared_t *pshared)
#define SENSORIOCSPOLLRATE
Set the driver polling rate to (arg) Hz, or one of the SENSOR_POLLRATE constants. ...
Definition: drv_sensor.h:134
int start(RM3100_BUS bus_id, Rotation rotation)
Starts the driver.
struct bmp280::bmp280_bus_option bus_options[]
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
void usage()
Prints info about the driver argument usage.
#define warnx(...)
Definition: err.h:95
#define NUM_BUS_OPTIONS
void print_info()
Diagnostics - print some basic information about the driver.
Definition: rm3100.cpp:477
static bool start_bus(bmp280_bus_option &bus)
Definition: bmp280_main.cpp:88
int fd
Definition: dataman.cpp:146
int info(RM3100_BUS bus_id)
Prints info about the driver.
Definition: rm3100_main.cpp:49
bool test(RM3100_BUS bus_id)
Perform some basic functional tests on the driver; make sure we can collect data from the sensor in p...
int stop()
Stop the driver.
#define SENSORIOCRESET
Reset the sensor to its default configuration.
Definition: drv_sensor.h:141
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
#define errx(eval,...)
Definition: err.h:89
rm3100_bus_option & find_bus(RM3100_BUS bus_id)
Finds a bus structure for a bus_id.
bool reset(RM3100_BUS bus_id)
Resets the driver.
#define OK
Definition: uavcan_main.cpp:71
#define mag_report
Definition: drv_mag.h:53