wheel_odometry.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2017 Pavlo Kolomiiets.
11  *
12  * This file is part of the mavros package and subject to the license terms
13  * in the top-level LICENSE file of the mavros repository.
14  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
15  */
16 
17 #include <mavros/mavros_plugin.h>
18 #include <mavros_msgs/WheelOdomStamped.h>
19 
20 #include <geometry_msgs/TwistWithCovarianceStamped.h>
21 #include <nav_msgs/Odometry.h>
24 #include <tf2_eigen/tf2_eigen.h>
25 
26 namespace mavros {
27 namespace extra_plugins {
36 public:
37  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
38 
40  wo_nh("~wheel_odometry"),
41  odom_mode(OM::NONE),
42  count(0),
43  raw_send(false),
44  twist_send(false),
45  tf_send(false),
46  yaw_initialized(false),
47  rpose(Eigen::Vector3d::Zero()),
48  rtwist(Eigen::Vector3d::Zero()),
49  rpose_cov(Eigen::Matrix3d::Zero()),
50  rtwist_cov(Eigen::Vector3d::Zero())
51  { }
52 
53  void initialize(UAS &uas_) override
54  {
56 
57  // General params
58  wo_nh.param("send_raw", raw_send, false);
59  // Wheels configuration
60  wo_nh.param("count", count, 2);
61  count = std::max(1, count); // bound check
62 
63  bool use_rpm;
64  wo_nh.param("use_rpm", use_rpm, false);
65  if (use_rpm)
67  else
69 
70  // Odometry params
71  wo_nh.param("send_twist", twist_send, false);
72  wo_nh.param<std::string>("frame_id", frame_id, "odom");
73  wo_nh.param<std::string>("child_frame_id", child_frame_id, "base_link");
74  wo_nh.param("vel_error", vel_cov, 0.1);
75  vel_cov = vel_cov * vel_cov; // std -> cov
76  // TF subsection
77  wo_nh.param("tf/send", tf_send, false);
78  wo_nh.param<std::string>("tf/frame_id", tf_frame_id, "odom");
79  wo_nh.param<std::string>("tf/child_frame_id", tf_child_frame_id, "base_link");
80 
81  // Read parameters for each wheel.
82  {
83  int iwheel = 0;
84  while (true) {
85  // Build the string in the form "wheelX", where X is the wheel number.
86  // Check if we have "wheelX" parameter.
87  // Indices starts from 0 and should increase without gaps.
88  auto name = utils::format("wheel%i", iwheel++);
89 
90  // Check if we have "wheelX" parameter
91  if (!wo_nh.hasParam(name)) break;
92 
93  // Read
94  Eigen::Vector2d offset;
95  double radius;
96 
97  wo_nh.param(name + "/x", offset[0], 0.0);
98  wo_nh.param(name + "/y", offset[1], 0.0);
99  wo_nh.param(name + "/radius", radius, 0.05);
100 
101  wheel_offset.push_back(offset);
102  wheel_radius.push_back(radius);
103  }
104 
105  // Check for all wheels specified
106  if (wheel_offset.size() >= count) {
107  // Duplicate 1st wheel if only one is available.
108  // This generalizes odometry computations for 1- and 2-wheels configurations.
109  if (wheel_radius.size() == 1) {
110  wheel_offset.resize(2);
111  wheel_radius.resize(2);
112  wheel_offset[1].x() = wheel_offset[0].x();
113  wheel_offset[1].y() = wheel_offset[0].y() + 1.0;// make separation non-zero to avoid div-by-zero
114  wheel_radius[1] = wheel_radius[0];
115  }
116 
117  // Check for non-zero wheel separation (first two wheels)
118  double separation = std::abs(wheel_offset[1].y() - wheel_offset[0].y());
119  if (separation < 1.e-5) {
121  ROS_WARN_NAMED("wo", "WO: Separation between the first two wheels is too small (%f).", separation);
122  }
123 
124  // Check for reasonable radiuses
125  for (int i = 0; i < wheel_radius.size(); i++) {
126  if (wheel_radius[i] <= 1.e-5) {
128  ROS_WARN_NAMED("wo", "WO: Wheel #%i has incorrect radius (%f).", i, wheel_radius[i]);
129  }
130  }
131  }
132  else {
134  ROS_WARN_NAMED("wo", "WO: Not all wheels have parameters specified (%lu/%i).", wheel_offset.size(), count);
135  }
136  }
137 
138  // Advertise RPM-s and distance-s
139  if (raw_send) {
140  rpm_pub = wo_nh.advertise<mavros_msgs::WheelOdomStamped>("rpm", 10);
141  dist_pub = wo_nh.advertise<mavros_msgs::WheelOdomStamped>("distance", 10);
142  }
143 
144  // Advertize topics
145  if (odom_mode != OM::NONE) {
146  if (twist_send)
147  twist_pub = wo_nh.advertise<geometry_msgs::TwistWithCovarianceStamped>("velocity", 10);
148  else
149  odom_pub = wo_nh.advertise<nav_msgs::Odometry>("odom", 10);
150  }
151  // No-odometry warning
152  else
153  ROS_WARN_NAMED("wo", "WO: No odometry computations will be performed.");
154  }
155 
157  {
158  return {
161  };
162  }
163 
164 private:
166 
171 
173  enum class OM {
174  NONE,
175  RPM,
176  DIST
177  };
179 
180  int count;
181  bool raw_send;
182  std::vector<Eigen::Vector2d> wheel_offset;
183  std::vector<double> wheel_radius;
184 
185  bool twist_send;
186  bool tf_send;
187  std::string frame_id;
188  std::string child_frame_id;
189  std::string tf_frame_id;
190  std::string tf_child_frame_id;
191  double vel_cov;
192 
195  std::vector<double> measurement_prev;
196 
198 
200  Eigen::Vector3d rpose;
201  Eigen::Vector3d rtwist;
202  Eigen::Matrix3d rpose_cov;
203  Eigen::Vector3d rtwist_cov;
204 
213  {
214  // Get initial yaw (from IMU)
215  // Check that IMU was already initialized
216  if (!yaw_initialized && m_uas->get_attitude_imu_enu()) {
218 
219  // Rotate current pose by initial yaw
220  Eigen::Rotation2Dd rot(yaw);
221  rpose.head(2) = rot * rpose.head(2); // x,y
222  rpose(2) += yaw;// yaw
223 
224  ROS_INFO_NAMED("wo", "WO: Initial yaw (deg): %f", yaw / M_PI * 180.0);
225  yaw_initialized = true;
226  }
227 
228  // Orientation (only if we have initial yaw)
229  geometry_msgs::Quaternion quat;
230  if (yaw_initialized)
231  quat = tf2::toMsg(ftf::quaternion_from_rpy(0.0, 0.0, rpose(2)));
232 
233  // Twist
234  geometry_msgs::TwistWithCovariance twist_cov;
235  // linear
236  twist_cov.twist.linear.x = rtwist(0);
237  twist_cov.twist.linear.y = rtwist(1);
238  twist_cov.twist.linear.z = 0.0;
239  // angular
240  twist_cov.twist.angular.x = 0.0;
241  twist_cov.twist.angular.y = 0.0;
242  twist_cov.twist.angular.z = rtwist(2);
243  // covariance
244  ftf::EigenMapCovariance6d twist_cov_map(twist_cov.covariance.data());
245  twist_cov_map.setZero();
246  twist_cov_map.block<2, 2>(0, 0).diagonal() << rtwist_cov(0), rtwist_cov(1);
247  twist_cov_map.block<1, 1>(5, 5).diagonal() << rtwist_cov(2);
248 
249  // Publish twist
250  if (twist_send) {
251  auto twist_cov_t = boost::make_shared<geometry_msgs::TwistWithCovarianceStamped>();
252  // header
253  twist_cov_t->header.stamp = time;
254  twist_cov_t->header.frame_id = frame_id;
255  // twist
256  twist_cov_t->twist = twist_cov;
257  // publish
258  twist_pub.publish(twist_cov_t);
259  }
260  // Publish odometry (only if we have initial yaw)
261  else if (yaw_initialized) {
262  auto odom = boost::make_shared<nav_msgs::Odometry>();
263  // header
264  odom->header.stamp = time;
265  odom->header.frame_id = frame_id;
266  odom->child_frame_id = child_frame_id;
267  // pose
268  odom->pose.pose.position.x = rpose(0);
269  odom->pose.pose.position.y = rpose(1);
270  odom->pose.pose.position.z = 0.0;
271  odom->pose.pose.orientation = quat;
272  ftf::EigenMapCovariance6d pose_cov_map(odom->pose.covariance.data());
273  pose_cov_map.block<2, 2>(0, 0) << rpose_cov.block<2, 2>(0, 0);
274  pose_cov_map.block<2, 1>(0, 5) << rpose_cov.block<2, 1>(0, 2);
275  pose_cov_map.block<1, 2>(5, 0) << rpose_cov.block<1, 2>(2, 0);
276  pose_cov_map.block<1, 1>(5, 5) << rpose_cov.block<1, 1>(2, 2);
277  // twist
278  odom->twist = twist_cov;
279  // publish
280  odom_pub.publish(odom);
281  }
282 
283  // Publish TF (only if we have initial yaw)
284  if (tf_send && yaw_initialized) {
285  geometry_msgs::TransformStamped transform;
286  // header
287  transform.header.stamp = time;
288  transform.header.frame_id = tf_frame_id;
289  transform.child_frame_id = tf_child_frame_id;
290  // translation
291  transform.transform.translation.x = rpose(0);
292  transform.transform.translation.y = rpose(1);
293  transform.transform.translation.z = 0.0;
294  // rotation
295  transform.transform.rotation = quat;
296  // publish
297  m_uas->tf2_broadcaster.sendTransform(transform);
298  }
299  }
300 
316  void update_odometry_diffdrive(std::vector<double> distance, double dt)
317  {
318  double y0 = wheel_offset[0](1);
319  double y1 = wheel_offset[1](1);
320  double a = -wheel_offset[0](0);
321  double dy_inv = 1.0 / (y1 - y0);
322  double dt_inv = 1.0 / dt;
323 
324  // Rotation angle
325  double theta = (distance[1] - distance[0]) * dy_inv;
326  // Distance traveled by the projection of origin onto the axis connecting the wheels (Op)
327  double L = (y1 * distance[0] - y0 * distance[1]) * dy_inv;
328 
329  // Instantenous pose update in local (robot) coordinate system (vel*dt)
330  Eigen::Vector3d v(L, a * theta, theta);
331  // Instantenous local twist
332  rtwist = v * dt_inv;
333 
334  // Compute local pose update (approximate).
335  // In the book a=0 and |y0|=|y1|, additionally.
336  // dx = L*cos(theta/2) - a*theta*sin(theta/2)
337  // dy = L*sin(theta/2) + a*theta*cos(theta/2)
338  // Compute local pose update (exact)
339  // dx = a*(cos(theta)-1) + R*sin(theta)
340  // dy = a*sin(theta) - R*(cos(theta)-1)
341  // where R - rotation radius of Op around ICC (R = L/theta).
342  double cos_theta = std::cos(theta);
343  double sin_theta = std::sin(theta);
344  double p; // sin(theta)/theta
345  double q; // (1-cos(theta))/theta
346  if (std::abs(theta) > 1.e-5) {
347  p = sin_theta / theta;
348  q = (1.0 - cos_theta) / theta;
349  }
350  // Limits for theta -> 0
351  else {
352  p = 1.0;
353  q = 0.0;
354  }
355 
356  // Local pose update matrix
357  Eigen::Matrix3d M;
358  M << p, -q, 0,
359  q, p, 0,
360  0, 0, 1;
361 
362  // Local pose update
363  Eigen::Vector3d dpose = M * v;
364 
365  // Rotation by yaw
366  double cy = std::cos(rpose(2));
367  double sy = std::sin(rpose(2));
368  Eigen::Matrix3d R;
369  R << cy, -sy, 0,
370  sy, cy, 0,
371  0, 0, 1;
372 
373  // World pose
374  rpose += R * dpose;
375  rpose(2) = fmod(rpose(2), 2.0 * M_PI); // Clamp to (-2*PI, 2*PI)
376 
377  // Twist errors (constant in time)
378  if (rtwist_cov(0) == 0.0) {
379  rtwist_cov(0) = vel_cov * (y0 * y0 + y1 * y1) * dy_inv * dy_inv;// vx_cov
380  rtwist_cov(1) = vel_cov * a * a * 2.0 * dy_inv * dy_inv + 0.001;// vy_cov (add extra error, otherwise vy_cov= 0 if a=0)
381  rtwist_cov(2) = vel_cov * 2.0 * dy_inv * dy_inv;// vyaw_cov
382  }
383 
384  // Pose errors (accumulated in time).
385  // Exact formulations respecting kinematic equations.
386  // dR/dYaw
387  Eigen::Matrix3d R_yaw;
388  R_yaw << -sy, -cy, 0,
389  cy, -sy, 0,
390  0, 0, 0;
391  // dYaw/dPose
392  Eigen::Vector3d yaw_pose(0, 0, 1);
393  // Jacobian by previous pose
394  Eigen::Matrix3d J_pose = Eigen::Matrix3d::Identity() + R_yaw * dpose * yaw_pose.transpose();
395 
396  // dL,dTheta / dL0,dL1
397  double L_L0 = y1 * dy_inv;
398  double L_L1 = -y0 * dy_inv;
399  double theta_L0 = -dy_inv;
400  double theta_L1 = dy_inv;
401  // dv/dMeasurement
402  Eigen::Matrix<double, 3, 2> v_meas;
403  v_meas << L_L0, L_L1,
404  a*theta_L0, a*theta_L1,
405  theta_L0, theta_L1;
406  // dTheta/dMeasurement
407  Eigen::Vector2d theta_meas(theta_L0, theta_L1);
408  // dM/dTheta
409  double px; // dP/dTheta
410  double qx; // dQ/dTheta
411  if (std::abs(theta) > 1.e-5) {
412  px = (theta * cos_theta - sin_theta) / (theta * theta);
413  qx = (theta * sin_theta - (1 - cos_theta)) / (theta * theta);
414  }
415  // Limits for theta -> 0
416  else {
417  px = 0;
418  qx = 0.5;
419  }
420  // dM/dTheta
421  Eigen::Matrix3d M_theta;
422  M_theta << px, -qx, 0,
423  qx, px, 0,
424  0, 0, 0;
425  // Jacobian by measurement
426  Eigen::Matrix<double, 3, 2> J_meas = R * (M * v_meas + M_theta * v * theta_meas.transpose());
427 
428  // Measurement cov
429  double L0_cov = vel_cov * dt * dt;
430  double L1_cov = vel_cov * dt * dt;
431  Eigen::Matrix2d meas_cov;
432  meas_cov << L0_cov, 0,
433  0, L1_cov;
434 
435  // Update pose cov
436  rpose_cov = J_pose * rpose_cov * J_pose.transpose() + J_meas * meas_cov * J_meas.transpose();
437  }
438 
445  void update_odometry(std::vector<double> distance, double dt)
446  {
447  // Currently, only 2-wheels configuration implemented
448  int nwheels = std::min(2, (int)distance.size());
449  switch (nwheels)
450  {
451  // Differential drive robot.
452  case 2:
453  update_odometry_diffdrive(distance, dt);
454  break;
455  }
456  }
457 
465  void process_measurement(std::vector<double> measurement, bool rpm, ros::Time time, ros::Time time_pub)
466  {
467  // Initial measurement
468  if (time_prev == ros::Time(0)) {
469  count_meas = measurement.size();
470  measurement_prev.resize(count_meas);
471  count = std::min(count, count_meas); // don't try to use more wheels than we have
472  }
473  // Same time stamp (messages are generated by FCU more often than the wheel state updated)
474  else if (time == time_prev) {
475  return;
476  }
477  // # of wheels differs from the initial value
478  else if (measurement.size() != count_meas) {
479  ROS_WARN_THROTTLE_NAMED(10, "wo", "WO: Number of wheels in measurement (%lu) differs from the initial value (%i).", measurement.size(), count_meas);
480  return;
481  }
482  // Compute odometry
483  else {
484  double dt = (time - time_prev).toSec(); // Time since previous measurement (s)
485 
486  // Distance traveled by each wheel since last measurement.
487  // Reserve for at least 2 wheels.
488  std::vector<double> distance(std::max(2, count));
489  // Compute using RPM-s
490  if (rpm) {
491  for (int i = 0; i < count; i++) {
492  double RPM_2_SPEED = wheel_radius[i] * 2.0 * M_PI / 60.0; // RPM -> speed (m/s)
493  double rpm = 0.5 * (measurement[i] + measurement_prev[i]); // Mean RPM during last dt seconds
494  distance[i] = rpm * RPM_2_SPEED * dt;
495  }
496  }
497  // Compute using cumulative distances
498  else {
499  for (int i = 0; i < count; i++)
500  distance[i] = measurement[i] - measurement_prev[i];
501  }
502 
503  // Make distance of the 2nd wheel equal to that of the 1st one if requested or only one is available.
504  // This generalizes odometry computations for 1- and 2-wheels configurations.
505  if (count == 1)
506  distance[1] = distance[0];
507 
508  // Update odometry
509  update_odometry(distance, dt);
510 
511  // Publish odometry
512  publish_odometry(time_pub);
513  }
514 
515  // Time step
516  time_prev = time;
517  std::copy_n(measurement.begin(), measurement.size(), measurement_prev.begin());
518  }
519 
520  /* -*- message handlers -*- */
521 
528  void handle_rpm(const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::RPM &rpm)
529  {
530  // Get ROS timestamp of the message
532 
533  // Publish RPM-s
534  if (raw_send) {
535  auto rpm_msg = boost::make_shared<mavros_msgs::WheelOdomStamped>();
536 
537  rpm_msg->header.stamp = timestamp;
538  rpm_msg->data.resize(2);
539  rpm_msg->data[0] = rpm.rpm1;
540  rpm_msg->data[1] = rpm.rpm2;
541 
542  rpm_pub.publish(rpm_msg);
543  }
544 
545  // Process measurement
546  if (odom_mode == OM::RPM) {
547  std::vector<double> measurement{rpm.rpm1, rpm.rpm2};
548  process_measurement(measurement, true, timestamp, timestamp);
549  }
550  }
551 
558  void handle_wheel_distance(const mavlink::mavlink_message_t *msg, mavlink::common::msg::WHEEL_DISTANCE &wheel_dist)
559  {
560  // Check for bad wheels count
561  if (wheel_dist.count == 0)
562  return;
563 
564  // Get ROS timestamp of the message
565  ros::Time timestamp = m_uas->synchronise_stamp(wheel_dist.time_usec);
566  // Get internal timestamp of the message
567  ros::Time timestamp_int = ros::Time(wheel_dist.time_usec / 1000000UL, 1000UL * (wheel_dist.time_usec % 1000000UL));
568 
569  // Publish distances
570  if (raw_send) {
571  auto wheel_dist_msg = boost::make_shared<mavros_msgs::WheelOdomStamped>();
572 
573  wheel_dist_msg->header.stamp = timestamp;
574  wheel_dist_msg->data.resize(wheel_dist.count);
575  std::copy_n(wheel_dist.distance.begin(), wheel_dist.count, wheel_dist_msg->data.begin());
576 
577  dist_pub.publish(wheel_dist_msg);
578  }
579 
580  // Process measurement
581  if (odom_mode == OM::DIST) {
582  std::vector<double> measurement(wheel_dist.count);
583  std::copy_n(wheel_dist.distance.begin(), wheel_dist.count, measurement.begin());
584  process_measurement(measurement, false, timestamp_int, timestamp);
585  }
586  }
587 };
588 } // namespace extra_plugins
589 } // namespace mavros
590 
Eigen::Vector3d rpose
Robot origin 2D-state (SI units)
bool twist_send
send geometry_msgs/TwistWithCovarianceStamped instead of nav_msgs/Odometry
std::string format(const std::string &fmt, Args ... args)
OM odom_mode
odometry computation mode
int count_meas
number of wheels in measurements
#define ROS_INFO_NAMED(name,...)
#define ROS_WARN_THROTTLE_NAMED(period, name,...)
#define ROS_WARN_NAMED(name,...)
geometry_msgs::Quaternion get_attitude_orientation_enu()
void handle_rpm(const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::RPM &rpm)
Handle Ardupilot RPM MAVlink message. Message specification: http://mavlink.io/en/messages/ardupilotm...
ros::Time time_prev
timestamp of previous measurement
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
uint32_t offset
use wheel&#39;s cumulative distance
Eigen::Map< Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > EigenMapCovariance6d
std::vector< Eigen::Vector2d > wheel_offset
wheel x,y offsets (m,NED)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW WheelOdometryPlugin()
std::string tf_child_frame_id
frame for TF and Pose
std::string frame_id
origin frame for topic headers
tf2_ros::TransformBroadcaster tf2_broadcaster
bool raw_send
send wheel&#39;s RPM and cumulative distance
std::vector< double > wheel_radius
wheel radiuses (m)
Eigen::Vector3d rtwist
twist (vx, vy, vyaw)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
std::vector< double > measurement_prev
previous measurement
int count
requested number of wheels to compute odometry
void process_measurement(std::vector< double > measurement, bool rpm, ros::Time time, ros::Time time_pub)
Process wheel measurement.
ros::Time synchronise_stamp(uint32_t time_boot_ms)
Eigen::Matrix3d rpose_cov
pose error 1-var
void update_odometry_diffdrive(std::vector< double > distance, double dt)
Update odometry for differential drive robot. Odometry is computed for robot&#39;s origin (IMU)...
Eigen::Vector3d to_eigen(const geometry_msgs::Point r)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool yaw_initialized
initial yaw initialized (from IMU)
void sendTransform(const geometry_msgs::TransformStamped &transform)
std::string child_frame_id
body-fixed frame for topic headers
bool hasParam(const std::string &key) const
B toMsg(const A &a)
void publish_odometry(ros::Time time)
Publish odometry. Odometry is computed from the very start but no pose info is published until we hav...
double vel_cov
wheel velocity measurement error 1-var (m/s)
Eigen::Quaterniond quaternion_from_rpy(const Eigen::Vector3d &rpy)
Eigen::Vector3d rtwist_cov
twist error 1-var (vx_cov, vy_cov, vyaw_cov)
std::vector< HandlerInfo > Subscriptions
double quaternion_get_yaw(const Eigen::Quaterniond &q)
void handle_wheel_distance(const mavlink::mavlink_message_t *msg, mavlink::common::msg::WHEEL_DISTANCE &wheel_dist)
Handle WHEEL_DISTANCE MAVlink message. Message specification: https://mavlink.io/en/messages/common.html#WHEEL_DISTANCE.
ftf::StaticTF transform
static Time now()
void initialize(UAS &uas_) override
sensor_msgs::Imu::Ptr get_attitude_imu_enu()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void update_odometry(std::vector< double > distance, double dt)
Update odometry (currently, only 2-wheels differential configuration implemented). Odometry is computed for robot&#39;s origin (IMU).


mavros_extras
Author(s): Vladimir Ermakov , Amilcar Lucas
autogenerated on Tue Jun 13 2023 02:17:59