main.cpp
Go to the documentation of this file.
1 
35 #include <string>
36 
37 #include "geometry_msgs/Vector3Stamped.h"
38 #include "ros/ros.h"
39 #include "sensor_msgs/Imu.h"
40 #include "sensor_msgs/MagneticField.h"
41 #include "serial/serial.h"
42 #include "std_msgs/Float32.h"
43 #include "std_msgs/Header.h"
44 #include "um6/comms.h"
45 #include "um6/registers.h"
46 #include "um6/Reset.h"
47 
48 // Don't try to be too clever. Arrival of this message triggers
49 // us to publish everything we have.
51 
56 template<typename RegT>
58  std::string param, std::string human_name)
59 {
60  if (reg.length != 3)
61  {
62  throw std::logic_error("configureVector3 may only be used with 3-field registers!");
63  }
64 
65  if (ros::param::has(param))
66  {
67  double x, y, z;
68  ros::param::get(param + "/x", x);
69  ros::param::get(param + "/y", y);
70  ros::param::get(param + "/z", z);
71  ROS_INFO_STREAM("Configuring " << human_name << " to ("
72  << x << ", " << y << ", " << z << ")");
73  reg.set_scaled(0, x);
74  reg.set_scaled(1, y);
75  reg.set_scaled(2, z);
76  if (sensor->sendWaitAck(reg))
77  {
78  throw std::runtime_error("Unable to configure vector.");
79  }
80  }
81 }
82 
87 template<typename RegT>
88 void sendCommand(um6::Comms* sensor, const um6::Accessor<RegT>& reg, std::string human_name)
89 {
90  ROS_INFO_STREAM("Sending command: " << human_name);
91  if (!sensor->sendWaitAck(reg))
92  {
93  throw std::runtime_error("Command to device failed.");
94  }
95 }
96 
97 
102 void configureSensor(um6::Comms* sensor, ros::NodeHandle *private_nh)
103 {
104  um6::Registers r;
105 
106  // Enable outputs we need.
107  const uint8_t UM6_BAUD_115200 = 0x5;
108  uint32_t comm_reg = UM6_BROADCAST_ENABLED |
111  UM6_BAUD_115200 << UM6_BAUD_START_BIT;
112  // set the broadcast rate of the device
113  int rate;
114  private_nh->param<int>("update_rate", rate, 20);
115  if (rate < 20 || rate > 300)
116  {
117  ROS_WARN("Potentially unsupported update rate of %d", rate);
118  }
119  // converting from desired rate to broadcast_rate as defined in UM6 datasheet
120  uint32_t rate_bits = (uint32_t) ((rate-20)*255.0/280.0);
121  ROS_INFO("Setting update rate to %uHz", rate);
122  comm_reg |= (rate_bits & UM6_SERIAL_RATE_MASK);
123  r.communication.set(0, comm_reg);
124  if (!sensor->sendWaitAck(r.communication))
125  {
126  throw std::runtime_error("Unable to set communication register.");
127  }
128 
129  // Optionally disable mag and accel updates in the sensor's EKF.
130  bool mag_updates, accel_updates;
131  private_nh->param<bool>("mag_updates", mag_updates, true);
132  private_nh->param<bool>("accel_updates", accel_updates, true);
133  uint32_t misc_config_reg = UM6_QUAT_ESTIMATE_ENABLED;
134  if (mag_updates)
135  {
136  misc_config_reg |= UM6_MAG_UPDATE_ENABLED;
137  }
138  else
139  {
140  ROS_WARN("Excluding magnetometer updates from EKF.");
141  }
142  if (accel_updates)
143  {
144  misc_config_reg |= UM6_ACCEL_UPDATE_ENABLED;
145  }
146  else
147  {
148  ROS_WARN("Excluding accelerometer updates from EKF.");
149  }
150  r.misc_config.set(0, misc_config_reg);
151  if (!sensor->sendWaitAck(r.misc_config))
152  {
153  throw std::runtime_error("Unable to set misc config register.");
154  }
155 
156  // Optionally disable the gyro reset on startup. A user might choose to do this
157  // if there's an external process which can ascertain when the vehicle is stationary
158  // and periodically call the /reset service.
159  bool zero_gyros;
160  private_nh->param<bool>("zero_gyros", zero_gyros, true);
161  if (zero_gyros) sendCommand(sensor, r.cmd_zero_gyros, "zero gyroscopes");
162 
163  // Configurable vectors.
164  configureVector3(sensor, r.mag_ref, "~mag_ref", "magnetic reference vector");
165  configureVector3(sensor, r.accel_ref, "~accel_ref", "accelerometer reference vector");
166  configureVector3(sensor, r.mag_bias, "~mag_bias", "magnetic bias vector");
167  configureVector3(sensor, r.accel_bias, "~accel_bias", "accelerometer bias vector");
168  configureVector3(sensor, r.gyro_bias, "~gyro_bias", "gyroscope bias vector");
169 }
170 
171 
173  const um6::Reset::Request& req, const um6::Reset::Response& resp)
174 {
175  um6::Registers r;
176  if (req.zero_gyros) sendCommand(sensor, r.cmd_zero_gyros, "zero gyroscopes");
177  if (req.reset_ekf) sendCommand(sensor, r.cmd_reset_ekf, "reset EKF");
178  if (req.set_mag_ref) sendCommand(sensor, r.cmd_set_mag_ref, "set magnetometer reference");
179  if (req.set_accel_ref) sendCommand(sensor, r.cmd_set_accel_ref, "set accelerometer reference");
180  return true;
181 }
182 
187 void publishMsgs(um6::Registers& r, ros::NodeHandle* imu_nh, sensor_msgs::Imu& imu_msg,
188  bool tf_ned_to_enu, bool use_magnetic_field_msg)
189 {
190  static ros::Publisher imu_pub = imu_nh->advertise<sensor_msgs::Imu>("data", 1, false);
191  static ros::Publisher mag_pub;
192  if (use_magnetic_field_msg)
193  {
194  mag_pub = imu_nh->advertise<sensor_msgs::MagneticField>("mag", 1, false);
195  }
196  else
197  {
198  mag_pub = imu_nh->advertise<geometry_msgs::Vector3Stamped>("mag", 1, false);
199  }
200  static ros::Publisher rpy_pub = imu_nh->advertise<geometry_msgs::Vector3Stamped>("rpy", 1, false);
201  static ros::Publisher temp_pub = imu_nh->advertise<std_msgs::Float32>("temperature", 1, false);
202 
203  if (imu_pub.getNumSubscribers() > 0)
204  {
205  // IMU reports a 4x4 wxyz covariance, ROS requires only 3x3 xyz.
206  // NED -> ENU conversion req'd?
207  imu_msg.orientation_covariance[0] = r.covariance.get_scaled(5);
208  imu_msg.orientation_covariance[1] = r.covariance.get_scaled(6);
209  imu_msg.orientation_covariance[2] = r.covariance.get_scaled(7);
210  imu_msg.orientation_covariance[3] = r.covariance.get_scaled(9);
211  imu_msg.orientation_covariance[4] = r.covariance.get_scaled(10);
212  imu_msg.orientation_covariance[5] = r.covariance.get_scaled(11);
213  imu_msg.orientation_covariance[6] = r.covariance.get_scaled(13);
214  imu_msg.orientation_covariance[7] = r.covariance.get_scaled(14);
215  imu_msg.orientation_covariance[8] = r.covariance.get_scaled(15);
216 
217  // NED -> ENU conversion (x = y, y = x, z = -z)
218  if (tf_ned_to_enu)
219  {
220  imu_msg.orientation.x = r.quat.get_scaled(2);
221  imu_msg.orientation.y = r.quat.get_scaled(1);
222  imu_msg.orientation.z = -r.quat.get_scaled(3);
223  imu_msg.orientation.w = r.quat.get_scaled(0);
224 
225  imu_msg.angular_velocity.x = r.gyro.get_scaled(1);
226  imu_msg.angular_velocity.y = r.gyro.get_scaled(0);
227  imu_msg.angular_velocity.z = -r.gyro.get_scaled(2);
228 
229  imu_msg.linear_acceleration.x = r.accel.get_scaled(1);
230  imu_msg.linear_acceleration.y = r.accel.get_scaled(0);
231  imu_msg.linear_acceleration.z = -r.accel.get_scaled(2);
232  }
233  else
234  {
235  imu_msg.orientation.w = r.quat.get_scaled(0);
236  imu_msg.orientation.x = r.quat.get_scaled(1);
237  imu_msg.orientation.y = r.quat.get_scaled(2);
238  imu_msg.orientation.z = r.quat.get_scaled(3);
239 
240  imu_msg.angular_velocity.x = r.gyro.get_scaled(0);
241  imu_msg.angular_velocity.y = r.gyro.get_scaled(1);
242  imu_msg.angular_velocity.z = r.gyro.get_scaled(2);
243 
244  imu_msg.linear_acceleration.x = r.accel.get_scaled(0);
245  imu_msg.linear_acceleration.y = r.accel.get_scaled(1);
246  imu_msg.linear_acceleration.z = r.accel.get_scaled(2);
247  }
248 
249  imu_pub.publish(imu_msg);
250  }
251 
252  if (mag_pub.getNumSubscribers() > 0)
253  {
254  if (use_magnetic_field_msg)
255  {
256  sensor_msgs::MagneticField mag_msg;
257  mag_msg.header = imu_msg.header;
258 
259  if (tf_ned_to_enu)
260  {
261  mag_msg.magnetic_field.x = r.mag.get_scaled(1);
262  mag_msg.magnetic_field.y = r.mag.get_scaled(0);
263  mag_msg.magnetic_field.z = -r.mag.get_scaled(2);
264  }
265  else
266  {
267  mag_msg.magnetic_field.x = r.mag.get_scaled(0);
268  mag_msg.magnetic_field.y = r.mag.get_scaled(1);
269  mag_msg.magnetic_field.z = r.mag.get_scaled(2);
270  }
271 
272  mag_pub.publish(mag_msg);
273  }
274  else
275  {
276  geometry_msgs::Vector3Stamped mag_msg;
277  mag_msg.header = imu_msg.header;
278 
279  if (tf_ned_to_enu)
280  {
281  mag_msg.vector.x = r.mag.get_scaled(1);
282  mag_msg.vector.y = r.mag.get_scaled(0);
283  mag_msg.vector.z = -r.mag.get_scaled(2);
284  }
285  else
286  {
287  mag_msg.vector.x = r.mag.get_scaled(0);
288  mag_msg.vector.y = r.mag.get_scaled(1);
289  mag_msg.vector.z = r.mag.get_scaled(2);
290  }
291 
292  mag_pub.publish(mag_msg);
293  }
294  }
295 
296  if (rpy_pub.getNumSubscribers() > 0)
297  {
298  geometry_msgs::Vector3Stamped rpy_msg;
299  rpy_msg.header = imu_msg.header;
300 
301  if (tf_ned_to_enu)
302  {
303  rpy_msg.vector.x = r.euler.get_scaled(1);
304  rpy_msg.vector.y = r.euler.get_scaled(0);
305  rpy_msg.vector.z = -r.euler.get_scaled(2);
306  }
307  else
308  {
309  rpy_msg.vector.x = r.euler.get_scaled(0);
310  rpy_msg.vector.y = r.euler.get_scaled(1);
311  rpy_msg.vector.z = r.euler.get_scaled(2);
312  }
313 
314  rpy_pub.publish(rpy_msg);
315  }
316 
317  if (temp_pub.getNumSubscribers() > 0)
318  {
319  std_msgs::Float32 temp_msg;
320  temp_msg.data = r.temperature.get_scaled(0);
321  temp_pub.publish(temp_msg);
322  }
323 }
324 
328 int main(int argc, char **argv)
329 {
330  ros::init(argc, argv, "um6_driver");
331 
332  // Load parameters from private node handle.
333  std::string port;
334  int32_t baud;
335 
336  ros::NodeHandle imu_nh("imu"), private_nh("~");
337  private_nh.param<std::string>("port", port, "/dev/ttyUSB0");
338  private_nh.param<int32_t>("baud", baud, 115200);
339 
340  serial::Serial ser;
341  ser.setPort(port);
342  ser.setBaudrate(baud);
343  serial::Timeout to = serial::Timeout(50, 50, 0, 50, 0);
344  ser.setTimeout(to);
345 
346  sensor_msgs::Imu imu_msg;
347  double linear_acceleration_stdev, angular_velocity_stdev;
348  private_nh.param<std::string>("frame_id", imu_msg.header.frame_id, "imu_link");
349  // Defaults obtained experimentally from hardware, no device spec exists
350  private_nh.param<double>("linear_acceleration_stdev", linear_acceleration_stdev, 0.06);
351  private_nh.param<double>("angular_velocity_stdev", angular_velocity_stdev, 0.005);
352 
353  double linear_acceleration_cov = linear_acceleration_stdev * linear_acceleration_stdev;
354  double angular_velocity_cov = angular_velocity_stdev * angular_velocity_stdev;
355 
356  // Enable converting from NED to ENU by default
357  bool tf_ned_to_enu;
358  private_nh.param<bool>("tf_ned_to_enu", tf_ned_to_enu, true);
359 
360  // Use MagneticField message rather than Vector3Stamped.
361  bool use_magnetic_field_msg;
362  private_nh.param<bool>("use_magnetic_field_msg", use_magnetic_field_msg, false);
363 
364  imu_msg.linear_acceleration_covariance[0] = linear_acceleration_cov;
365  imu_msg.linear_acceleration_covariance[4] = linear_acceleration_cov;
366  imu_msg.linear_acceleration_covariance[8] = linear_acceleration_cov;
367 
368  imu_msg.angular_velocity_covariance[0] = angular_velocity_cov;
369  imu_msg.angular_velocity_covariance[4] = angular_velocity_cov;
370  imu_msg.angular_velocity_covariance[8] = angular_velocity_cov;
371 
372  bool first_failure = true;
373  while (ros::ok())
374  {
375  try
376  {
377  ser.open();
378  }
379  catch(const serial::IOException& e)
380  {
381  ROS_DEBUG("Unable to connect to port.");
382  }
383  if (ser.isOpen())
384  {
385  ROS_INFO("Successfully connected to serial port.");
386  first_failure = true;
387  try
388  {
389  um6::Comms sensor(&ser);
390  configureSensor(&sensor, &private_nh);
391  um6::Registers registers;
392  ros::ServiceServer srv = imu_nh.advertiseService<um6::Reset::Request, um6::Reset::Response>(
393  "reset", boost::bind(handleResetService, &sensor, _1, _2));
394 
395  while (ros::ok())
396  {
397  if (sensor.receive(&registers) == TRIGGER_PACKET)
398  {
399  // Triggered by arrival of final message in group.
400  imu_msg.header.stamp = ros::Time::now();
401  publishMsgs(registers, &imu_nh, imu_msg, tf_ned_to_enu, use_magnetic_field_msg);
402  ros::spinOnce();
403  }
404  }
405  }
406  catch(const std::exception& e)
407  {
408  if (ser.isOpen()) ser.close();
409  ROS_ERROR_STREAM(e.what());
410  ROS_INFO("Attempting reconnection after error.");
411  ros::Duration(1.0).sleep();
412  }
413  }
414  else
415  {
416  ROS_WARN_STREAM_COND(first_failure, "Could not connect to serial device "
417  << port << ". Trying again every 1 second.");
418  first_failure = false;
419  ros::Duration(1.0).sleep();
420  }
421  }
422 }
const Accessor< int16_t > quat
Definition: registers.h:189
#define UM6_EULER_ENABLED
const uint16_t length
Definition: registers.h:116
#define UM6_GYROS_PROC_ENABLED
const Accessor< int16_t > accel
Definition: registers.h:189
void publish(const boost::shared_ptr< M > &message) const
#define UM6_SERIAL_RATE_MASK
#define UM6_ACCEL_UPDATE_ENABLED
double get_scaled(uint16_t field) const
Definition: registers.h:138
#define UM6_BROADCAST_ENABLED
void configureSensor(um6::Comms *sensor, ros::NodeHandle *private_nh)
Definition: main.cpp:102
int main(int argc, char **argv)
Definition: main.cpp:328
const Accessor< int16_t > gyro
Definition: registers.h:189
const Accessor< float > mag_ref
Definition: registers.h:195
Provides the Registers class, which initializes with a suite of accessors suitable for reading and wr...
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define UM6_BAUD_START_BIT
void configureVector3(um6::Comms *sensor, const um6::Accessor< RegT > &reg, std::string param, std::string human_name)
Definition: main.cpp:57
#define ROS_WARN(...)
#define UM6_MAG_UPDATE_ENABLED
const Accessor< float > covariance
Definition: registers.h:191
const Accessor< int16_t > gyro_bias
Definition: registers.h:196
#define UM6_COV_ENABLED
#define UM6_ACCELS_PROC_ENABLED
const uint8_t TRIGGER_PACKET
Definition: main.cpp:50
const Accessor< float > temperature
Definition: registers.h:191
ROSCPP_DECL bool get(const std::string &key, std::string &s)
#define ROS_INFO(...)
const Accessor< int16_t > mag
Definition: registers.h:189
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const Accessor< uint32_t > communication
Definition: registers.h:194
int16_t receive(Registers *r)
Definition: comms.cpp:54
#define UM6_TEMPERATURE
ROSCPP_DECL bool ok()
const Accessor< int16_t > mag_bias
Definition: registers.h:196
#define ROS_WARN_STREAM_COND(cond, args)
ROSCPP_DECL bool has(const std::string &key)
void set_scaled(uint16_t field, double value) const
Definition: registers.h:149
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const Accessor< int16_t > accel_bias
Definition: registers.h:196
bool sendWaitAck(const Accessor_ &a)
Definition: comms.cpp:198
const Accessor< uint32_t > cmd_set_accel_ref
Definition: registers.h:199
#define UM6_QUAT_ENABLED
uint32_t getNumSubscribers() const
void setPort(const std::string &port)
void sendCommand(um6::Comms *sensor, const um6::Accessor< RegT > &reg, std::string human_name)
Definition: main.cpp:88
#define ROS_INFO_STREAM(args)
const Accessor< uint32_t > cmd_reset_ekf
Definition: registers.h:199
const Accessor< uint32_t > cmd_set_mag_ref
Definition: registers.h:199
Comms class definition. Does not manage the serial connection itself, but takes care of reading and w...
const Accessor< uint32_t > cmd_zero_gyros
Definition: registers.h:199
static Time now()
#define UM6_TEMPERATURE_ENABLED
const Accessor< float > accel_ref
Definition: registers.h:195
bool handleResetService(um6::Comms *sensor, const um6::Reset::Request &req, const um6::Reset::Response &resp)
Definition: main.cpp:172
#define UM6_MAG_PROC_ENABLED
const Accessor< int16_t > euler
Definition: registers.h:189
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()
#define UM6_QUAT_ESTIMATE_ENABLED
void set(uint8_t field, RegT value) const
Definition: registers.h:143
void publishMsgs(um6::Registers &r, ros::NodeHandle *imu_nh, sensor_msgs::Imu &imu_msg, bool tf_ned_to_enu, bool use_magnetic_field_msg)
Definition: main.cpp:187
const Accessor< uint32_t > misc_config
Definition: registers.h:194
#define ROS_DEBUG(...)


um6
Author(s): Mike Purvis
autogenerated on Thu Sep 26 2019 03:18:02