track_odometry.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2017, the neonavigation authors
3  * 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 are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 #include <geometry_msgs/Twist.h>
32 #include <nav_msgs/Odometry.h>
33 #include <sensor_msgs/Imu.h>
34 #include <std_msgs/Float32.h>
35 
39 
40 #include <limits>
41 #include <string>
42 
43 #include <Eigen/Core>
44 #include <Eigen/Geometry>
45 
46 #include <kalman_filter1.h>
47 
49 
50 Eigen::Vector3f toEigen(const geometry_msgs::Vector3& a)
51 {
52  return Eigen::Vector3f(a.x, a.y, a.z);
53 }
54 Eigen::Vector3f toEigen(const geometry_msgs::Point& a)
55 {
56  return Eigen::Vector3f(a.x, a.y, a.z);
57 }
58 Eigen::Quaternionf toEigen(const geometry_msgs::Quaternion& a)
59 {
60  return Eigen::Quaternionf(a.w, a.x, a.y, a.z);
61 }
62 geometry_msgs::Point toPoint(const Eigen::Vector3f& a)
63 {
64  geometry_msgs::Point b;
65  b.x = a.x();
66  b.y = a.y();
67  b.z = a.z();
68  return b;
69 }
70 geometry_msgs::Vector3 toVector3(const Eigen::Vector3f& a)
71 {
72  geometry_msgs::Vector3 b;
73  b.x = a.x();
74  b.y = a.y();
75  b.z = a.z();
76  return b;
77 }
78 
80 {
81 private:
91  nav_msgs::Odometry odom_prev_;
92  nav_msgs::Odometry odomraw_prev_;
93 
94  std::string base_link_id_;
96  std::string odom_id_;
97 
98  sensor_msgs::Imu imu_;
99  double gyro_zero_[3];
102 
103  bool debug_;
104  bool use_kf_;
107  double sigma_odom_;
109  float dist_;
111 
113 
114  bool has_imu_;
115  bool has_odom_;
117 
118  void cbResetZ(const std_msgs::Float32::Ptr& msg)
119  {
120  odom_prev_.pose.pose.position.z = msg->data;
121  }
122  void cbImu(const sensor_msgs::Imu::Ptr& msg)
123  {
124  if (base_link_id_.size() == 0)
125  {
126  ROS_ERROR("base_link id is not specified.");
127  return;
128  }
129 
130  imu_.header = msg->header;
131  try
132  {
133  geometry_msgs::TransformStamped trans = tf_buffer_.lookupTransform(
134  base_link_id_, msg->header.frame_id, ros::Time(0), ros::Duration(0.1));
135 
136  geometry_msgs::Vector3Stamped vin, vout;
137  vin.header = imu_.header;
138  vin.header.stamp = ros::Time(0);
139  vin.vector = msg->linear_acceleration;
140  tf2::doTransform(vin, vout, trans);
141  imu_.linear_acceleration = vout.vector;
142 
143  vin.header = imu_.header;
144  vin.header.stamp = ros::Time(0);
145  vin.vector = msg->angular_velocity;
146  tf2::doTransform(vin, vout, trans);
147  imu_.angular_velocity = vout.vector;
148 
150  geometry_msgs::QuaternionStamped qmin, qmout;
151  qmin.header = imu_.header;
152  qmin.quaternion = msg->orientation;
153  tf2::fromMsg(qmin, qin);
154 
155  auto axis = qin.getAxis();
156  auto angle = qin.getAngle();
157  geometry_msgs::Vector3Stamped axis2;
158  geometry_msgs::Vector3Stamped axis1;
159  axis1.vector = tf2::toMsg(axis);
160  axis1.header.stamp = ros::Time(0);
161  axis1.header.frame_id = qin.frame_id_;
162  tf2::doTransform(axis1, axis2, trans);
163 
164  tf2::fromMsg(axis2.vector, axis);
165  qout.setData(tf2::Quaternion(axis, angle));
166  qout.stamp_ = qin.stamp_;
167  qout.frame_id_ = base_link_id_;
168 
169  qmout = tf2::toMsg(qout);
170  imu_.orientation = qmout.quaternion;
171  // ROS_INFO("%0.3f %s -> %0.3f %s",
172  // tf2::getYaw(qmin.quaternion), qmin.header.frame_id.c_str(),
173  // tf2::getYaw(qmout.quaternion), qmout.header.frame_id.c_str());
174 
175  has_imu_ = true;
176  }
177  catch (tf2::TransformException& e)
178  {
179  ROS_ERROR("%s", e.what());
180  has_imu_ = false;
181  return;
182  }
183  }
184  void cbOdom(const nav_msgs::Odometry::Ptr& msg)
185  {
186  nav_msgs::Odometry odom = *msg;
187  if (has_odom_)
188  {
189  const double dt = (odom.header.stamp - odomraw_prev_.header.stamp).toSec();
190  if (base_link_id_overwrite_.size() == 0)
191  {
192  base_link_id_ = odom.child_frame_id;
193  }
194 
195  if (!has_imu_)
196  {
197  ROS_ERROR_THROTTLE(1.0, "IMU data not received");
198  return;
199  }
200 
201  float slip_ratio = 1.0;
202  odom.header.stamp += ros::Duration(tf_tolerance_);
203  odom.twist.twist.angular = imu_.angular_velocity;
204  odom.pose.pose.orientation = imu_.orientation;
205 
206  float w_imu = imu_.angular_velocity.z;
207  const float w_odom = msg->twist.twist.angular.z;
208 
209  if (w_imu * w_odom < 0 && !negative_slip_)
210  w_imu = w_odom;
211 
212  slip_.predict(-slip_.x_ * dt * predict_filter_tc_, dt * sigma_predict_);
213  if (fabs(w_odom) > sigma_odom_ * 3)
214  {
215  // non-kf mode: calculate slip_ratio if angular vel < 3*sigma
216  slip_ratio = w_imu / w_odom;
217  }
218 
219  const float slip_ratio_per_angvel =
220  (w_odom - w_imu) / (w_odom * fabs(w_odom));
221  float slip_ratio_per_angvel_sigma =
222  sigma_odom_ * fabs(2 * w_odom * sigma_odom_ / powf(w_odom * w_odom - sigma_odom_ * sigma_odom_, 2.0));
223  if (fabs(w_odom) < sigma_odom_)
224  slip_ratio_per_angvel_sigma = std::numeric_limits<float>::infinity();
225 
226  slip_.measure(slip_ratio_per_angvel, slip_ratio_per_angvel_sigma);
227  // printf("%0.5f %0.5f %0.5f %0.5f %0.5f %0.5f\n",
228  // slip_ratio_per_angvel, slip_ratio_sigma, slip_ratio_per_angvel_sigma,
229  // slip_.x_, slip_.sigma_, msg->twist.twist.angular.z);
230 
231  if (debug_)
232  {
233  printf("%0.3f %0.3f %0.3f %0.3f %0.3f %0.3f %0.3f\n",
234  imu_.angular_velocity.z,
235  msg->twist.twist.angular.z,
236  slip_ratio,
237  slip_.x_, slip_.sigma_,
238  odom.twist.twist.linear.x, dist_);
239  }
240  dist_ += odom.twist.twist.linear.x * dt;
241 
242  const Eigen::Vector3f diff = toEigen(msg->pose.pose.position) - toEigen(odomraw_prev_.pose.pose.position);
243  Eigen::Vector3f v =
244  toEigen(odom.pose.pose.orientation) * toEigen(msg->pose.pose.orientation).inverse() * diff;
245  if (use_kf_)
246  v *= 1.0 - slip_.x_;
247  else
248  v *= slip_ratio;
249 
250  odom.pose.pose.position = toPoint(toEigen(odom_prev_.pose.pose.position) + v);
251  if (z_filter_timeconst_ > 0)
252  odom.pose.pose.position.z *= 1.0 - (dt / z_filter_timeconst_);
253 
254  odom.child_frame_id = base_link_id_;
255  pub_odom_.publish(odom);
256 
257  geometry_msgs::TransformStamped odom_trans;
258 
259  odom_trans.header = odom.header;
260  odom_trans.child_frame_id = base_link_id_;
261  odom_trans.transform.translation = toVector3(toEigen(odom.pose.pose.position));
262  odom_trans.transform.rotation = odom.pose.pose.orientation;
263  if (publish_tf_)
264  tf_broadcaster_.sendTransform(odom_trans);
265  }
266  odomraw_prev_ = *msg;
267  odom_prev_ = odom;
268  has_odom_ = true;
269  }
270 
271 public:
273  : nh_()
274  , pnh_("~")
275  , tf_listener_(tf_buffer_)
276  {
278  pnh_.param("without_odom", without_odom_, false);
279  if (!without_odom_)
280  sub_odom_ = nh_.subscribe("odom_raw", 64, &TrackOdometryNode::cbOdom, this);
282  nh_, "imu/data",
283  nh_, "imu", 64, &TrackOdometryNode::cbImu, this);
285  nh_, "reset_odometry_z",
286  pnh_, "reset_z", 1, &TrackOdometryNode::cbResetZ, this);
287  pub_odom_ = nh_.advertise<nav_msgs::Odometry>("odom", 8);
288 
289  if (!without_odom_)
290  {
291  pnh_.param("base_link_id", base_link_id_overwrite_, std::string(""));
292  }
293  else
294  {
295  pnh_.param("base_link_id", base_link_id_, std::string("base_link"));
296  pnh_.param("odom_id", odom_id_, std::string("odom"));
297  }
298 
299  if (pnh_.hasParam("z_filter"))
300  {
301  z_filter_timeconst_ = -1.0;
302  double z_filter;
303  if (pnh_.getParam("z_filter", z_filter))
304  {
305  const double odom_freq = 100.0;
306  if (0.0 < z_filter && z_filter < 1.0)
307  z_filter_timeconst_ = (1.0 / odom_freq) / (1.0 - z_filter);
308  }
309  ROS_ERROR(
310  "track_odometry: ~z_filter parameter (exponential filter (1 - alpha) value) is deprecated. "
311  "Use ~z_filter_timeconst (in seconds) instead. "
312  "Treated as z_filter_timeconst=%0.6f. (negative value means disabled)",
313  z_filter_timeconst_);
314  }
315  else
316  {
317  pnh_.param("z_filter_timeconst", z_filter_timeconst_, -1.0);
318  }
319  pnh_.param("tf_tolerance", tf_tolerance_, 0.01);
320  pnh_.param("use_kf", use_kf_, true);
321  pnh_.param("enable_negative_slip", negative_slip_, false);
322  pnh_.param("debug", debug_, false);
323  pnh_.param("publish_tf", publish_tf_, true);
324 
325  if (base_link_id_overwrite_.size() > 0)
326  {
327  base_link_id_ = base_link_id_overwrite_;
328  }
329 
330  // sigma_odom_ [rad/s]: standard deviation of odometry angular vel on straight running
331  pnh_.param("sigma_odom", sigma_odom_, 0.005);
332  // sigma_predict_ [sigma/second]: prediction sigma of kalman filter
333  pnh_.param("sigma_predict", sigma_predict_, 0.5);
334  // predict_filter_tc_ [sec.]: LPF time-constant to forget estimated slip_ ratio
335  pnh_.param("predict_filter_tc", predict_filter_tc_, 1.0);
336 
337  has_imu_ = false;
338  has_odom_ = false;
339 
340  dist_ = 0;
341  slip_.set(0.0, 0.1);
342  }
343  void cbTimer(const ros::TimerEvent& event)
344  {
345  nav_msgs::Odometry::Ptr odom(new nav_msgs::Odometry);
346  odom->header.stamp = ros::Time::now();
347  odom->header.frame_id = odom_id_;
348  odom->child_frame_id = base_link_id_;
349  odom->pose.pose.orientation.w = 1.0;
350  cbOdom(odom);
351  }
352  void spin()
353  {
354  if (!without_odom_)
355  {
356  ros::spin();
357  }
358  else
359  {
360  ros::Timer timer = nh_.createTimer(
361  ros::Duration(1.0 / 50.0), &TrackOdometryNode::cbTimer, this);
362  ros::spin();
363  }
364  }
365 };
366 
367 int main(int argc, char* argv[])
368 {
369  ros::init(argc, argv, "track_odometry");
370 
371  TrackOdometryNode odom;
372 
373  odom.spin();
374 
375  return 0;
376 }
void measure(const float x_in, const float sigma_in)
std::string base_link_id_
ros::NodeHandle pnh_
ros::NodeHandle nh_
void publish(const boost::shared_ptr< M > &message) const
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void set(const float x0=0.0, const float sigma0=std::numeric_limits< float >::infinity())
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
tf2_ros::Buffer tf_buffer_
Eigen::Vector3f toEigen(const geometry_msgs::Vector3 &a)
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
tf2_ros::TransformListener tf_listener_
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
ros::Subscriber sub_reset_z_
ROSCPP_DECL void spin(Spinner &spinner)
tf2_ros::TransformBroadcaster tf_broadcaster_
geometry_msgs::Vector3 toVector3(const Eigen::Vector3f &a)
ros::Subscriber sub_odom_
void cbImu(const sensor_msgs::Imu::Ptr &msg)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define ROS_ERROR_THROTTLE(period,...)
ros::Time stamp_
void fromMsg(const A &, B &b)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ros::Subscriber sub_imu_
std::string odom_id_
ros::Publisher pub_odom_
int main(int argc, char *argv[])
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void sendTransform(const geometry_msgs::TransformStamped &transform)
void cbResetZ(const std_msgs::Float32::Ptr &msg)
geometry_msgs::Point toPoint(const Eigen::Vector3f &a)
B toMsg(const A &a)
std::string frame_id_
nav_msgs::Odometry odomraw_prev_
nav_msgs::Odometry odom_prev_
bool getParam(const std::string &key, std::string &s) const
void predict(const float x_plus, const float sigma_plus)
static Time now()
bool hasParam(const std::string &key) const
KalmanFilter1 slip_
#define ROS_ERROR(...)
sensor_msgs::Imu imu_
void setData(const T &input)
void cbOdom(const nav_msgs::Odometry::Ptr &msg)
std::string base_link_id_overwrite_
void cbTimer(const ros::TimerEvent &event)


track_odometry
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:05