track_odometry.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2019, 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 <cmath>
31 #include <limits>
32 #include <memory>
33 #include <string>
34 
35 #include <Eigen/Core>
36 #include <Eigen/Geometry>
37 
38 #include <ros/ros.h>
39 
40 #include <geometry_msgs/Twist.h>
41 #include <nav_msgs/Odometry.h>
42 #include <sensor_msgs/Imu.h>
43 #include <std_msgs/Float32.h>
44 
48 
52 
54 
56 
57 Eigen::Vector3d toEigen(const geometry_msgs::Vector3& a)
58 {
59  return Eigen::Vector3d(a.x, a.y, a.z);
60 }
61 Eigen::Vector3d toEigen(const geometry_msgs::Point& a)
62 {
63  return Eigen::Vector3d(a.x, a.y, a.z);
64 }
65 Eigen::Quaterniond toEigen(const geometry_msgs::Quaternion& a)
66 {
67  return Eigen::Quaterniond(a.w, a.x, a.y, a.z);
68 }
69 geometry_msgs::Point toPoint(const Eigen::Vector3d& a)
70 {
71  geometry_msgs::Point b;
72  b.x = a.x();
73  b.y = a.y();
74  b.z = a.z();
75  return b;
76 }
77 geometry_msgs::Vector3 toVector3(const Eigen::Vector3d& a)
78 {
79  geometry_msgs::Vector3 b;
80  b.x = a.x();
81  b.y = a.y();
82  b.z = a.z();
83  return b;
84 }
85 
87 {
88 private:
89  using SyncPolicy =
91 
94 
96  std::shared_ptr<message_filters::Subscriber<nav_msgs::Odometry>> sub_odom_;
97  std::shared_ptr<message_filters::Subscriber<sensor_msgs::Imu>> sub_imu_;
98  std::shared_ptr<message_filters::Synchronizer<SyncPolicy>> sync_;
99 
105  nav_msgs::Odometry odom_prev_;
106  nav_msgs::Odometry odomraw_prev_;
107 
108  std::string base_link_id_;
110  std::string odom_id_;
111 
112  sensor_msgs::Imu imu_;
113  double gyro_zero_[3];
116 
117  bool debug_;
118  bool use_kf_;
121  double sigma_odom_;
123  double dist_;
125 
127 
128  bool has_imu_;
129  bool has_odom_;
131 
132  void cbResetZ(const std_msgs::Float32::Ptr& msg)
133  {
134  odom_prev_.pose.pose.position.z = msg->data;
135  }
136  void cbOdomImu(const nav_msgs::Odometry::ConstPtr& odom_msg, const sensor_msgs::Imu::ConstPtr& imu_msg)
137  {
138  ROS_DEBUG(
139  "Synchronized timestamp: odom %0.3f, imu %0.3f",
140  odom_msg->header.stamp.toSec(),
141  imu_msg->header.stamp.toSec());
142  cbImu(imu_msg);
143  cbOdom(odom_msg);
144  }
145  void cbImu(const sensor_msgs::Imu::ConstPtr& msg)
146  {
147  if (base_link_id_.size() == 0)
148  {
149  ROS_ERROR("base_link id is not specified.");
150  return;
151  }
152 
153  imu_.header = msg->header;
154  try
155  {
156  geometry_msgs::TransformStamped trans = tf_buffer_.lookupTransform(
157  base_link_id_, msg->header.frame_id, ros::Time(0), ros::Duration(0.1));
158 
159  geometry_msgs::Vector3Stamped vin, vout;
160  vin.header = imu_.header;
161  vin.header.stamp = ros::Time(0);
162  vin.vector = msg->linear_acceleration;
163  tf2::doTransform(vin, vout, trans);
164  imu_.linear_acceleration = vout.vector;
165 
166  vin.header = imu_.header;
167  vin.header.stamp = ros::Time(0);
168  vin.vector = msg->angular_velocity;
169  tf2::doTransform(vin, vout, trans);
170  imu_.angular_velocity = vout.vector;
171 
173  geometry_msgs::QuaternionStamped qmin, qmout;
174  qmin.header = imu_.header;
175  qmin.quaternion = msg->orientation;
176  tf2::fromMsg(qmin, qin);
177 
178  auto axis = qin.getAxis();
179  auto angle = qin.getAngle();
180  geometry_msgs::Vector3Stamped axis2;
181  geometry_msgs::Vector3Stamped axis1;
182  axis1.vector = tf2::toMsg(axis);
183  axis1.header.stamp = ros::Time(0);
184  axis1.header.frame_id = qin.frame_id_;
185  tf2::doTransform(axis1, axis2, trans);
186 
187  tf2::fromMsg(axis2.vector, axis);
188  qout.setData(tf2::Quaternion(axis, angle));
189  qout.stamp_ = qin.stamp_;
190  qout.frame_id_ = base_link_id_;
191 
192  qmout = tf2::toMsg(qout);
193  imu_.orientation = qmout.quaternion;
194  // ROS_INFO("%0.3f %s -> %0.3f %s",
195  // tf2::getYaw(qmin.quaternion), qmin.header.frame_id.c_str(),
196  // tf2::getYaw(qmout.quaternion), qmout.header.frame_id.c_str());
197 
198  has_imu_ = true;
199  }
200  catch (tf2::TransformException& e)
201  {
202  ROS_ERROR("%s", e.what());
203  has_imu_ = false;
204  return;
205  }
206  }
207  void cbOdom(const nav_msgs::Odometry::ConstPtr& msg)
208  {
209  nav_msgs::Odometry odom = *msg;
210  if (has_odom_)
211  {
212  const double dt = (odom.header.stamp - odomraw_prev_.header.stamp).toSec();
213  if (base_link_id_overwrite_.size() == 0)
214  {
215  base_link_id_ = odom.child_frame_id;
216  }
217 
218  if (!has_imu_)
219  {
220  ROS_ERROR_THROTTLE(1.0, "IMU data not received");
221  return;
222  }
223 
224  double slip_ratio = 1.0;
225  odom.header.stamp += ros::Duration(tf_tolerance_);
226  odom.twist.twist.angular = imu_.angular_velocity;
227  odom.pose.pose.orientation = imu_.orientation;
228 
229  double w_imu = imu_.angular_velocity.z;
230  const double w_odom = msg->twist.twist.angular.z;
231 
232  if (w_imu * w_odom < 0 && !negative_slip_)
233  w_imu = w_odom;
234 
236  if (std::abs(w_odom) > sigma_odom_ * 3)
237  {
238  // non-kf mode: calculate slip_ratio if angular vel < 3*sigma
239  slip_ratio = w_imu / w_odom;
240  }
241 
242  const double slip_ratio_per_angvel =
243  (w_odom - w_imu) / (w_odom * std::abs(w_odom));
244  double slip_ratio_per_angvel_sigma =
245  sigma_odom_ * std::abs(2.0 * w_odom * sigma_odom_ / std::pow(w_odom * w_odom - sigma_odom_ * sigma_odom_, 2));
246  if (std::abs(w_odom) < sigma_odom_)
247  slip_ratio_per_angvel_sigma = std::numeric_limits<double>::infinity();
248 
249  slip_.measure(slip_ratio_per_angvel, slip_ratio_per_angvel_sigma);
250  // printf("%0.5f %0.5f %0.5f %0.5f %0.5f %0.5f\n",
251  // slip_ratio_per_angvel, slip_ratio_sigma, slip_ratio_per_angvel_sigma,
252  // slip_.x_, slip_.sigma_, msg->twist.twist.angular.z);
253 
254  if (debug_)
255  {
256  printf("%0.3f %0.3f %0.3f %0.3f %0.3f %0.3f %0.3f\n",
257  imu_.angular_velocity.z,
258  msg->twist.twist.angular.z,
259  slip_ratio,
260  slip_.x_, slip_.sigma_,
261  odom.twist.twist.linear.x, dist_);
262  }
263  dist_ += odom.twist.twist.linear.x * dt;
264 
265  const Eigen::Vector3d diff = toEigen(msg->pose.pose.position) - toEigen(odomraw_prev_.pose.pose.position);
266  Eigen::Vector3d v =
267  toEigen(odom.pose.pose.orientation) * toEigen(msg->pose.pose.orientation).inverse() * diff;
268  if (use_kf_)
269  v *= 1.0 - slip_.x_;
270  else
271  v *= slip_ratio;
272 
273  odom.pose.pose.position = toPoint(toEigen(odom_prev_.pose.pose.position) + v);
274  if (z_filter_timeconst_ > 0)
275  odom.pose.pose.position.z *= 1.0 - (dt / z_filter_timeconst_);
276 
277  odom.child_frame_id = base_link_id_;
278  pub_odom_.publish(odom);
279 
280  geometry_msgs::TransformStamped odom_trans;
281 
282  odom_trans.header = odom.header;
283  odom_trans.child_frame_id = base_link_id_;
284  odom_trans.transform.translation = toVector3(toEigen(odom.pose.pose.position));
285  odom_trans.transform.rotation = odom.pose.pose.orientation;
286  if (publish_tf_)
287  tf_broadcaster_.sendTransform(odom_trans);
288  }
289  odomraw_prev_ = *msg;
290  odom_prev_ = odom;
291  has_odom_ = true;
292  }
293 
294 public:
296  : nh_()
297  , pnh_("~")
299  {
301 
302  bool enable_tcp_no_delay;
303  pnh_.param("enable_tcp_no_delay", enable_tcp_no_delay, true);
304  const ros::TransportHints transport_hints =
305  enable_tcp_no_delay ? ros::TransportHints().reliable().tcpNoDelay(true) : ros::TransportHints();
306 
307  pnh_.param("without_odom", without_odom_, false);
308  if (without_odom_)
309  {
311  nh_, "imu/data",
312  nh_, "imu", 64, &TrackOdometryNode::cbImu, this);
313  pnh_.param("base_link_id", base_link_id_, std::string("base_link"));
314  pnh_.param("odom_id", odom_id_, std::string("odom"));
315  }
316  else
317  {
318  sub_odom_.reset(
319  new message_filters::Subscriber<nav_msgs::Odometry>(nh_, "odom_raw", 50, transport_hints));
321  {
322  sub_imu_.reset(
323  new message_filters::Subscriber<sensor_msgs::Imu>(nh_, "imu/data", 50, transport_hints));
324  }
325  else
326  {
327  sub_imu_.reset(
328  new message_filters::Subscriber<sensor_msgs::Imu>(nh_, "imu", 50, transport_hints));
329  }
330 
331  int sync_window;
332  pnh_.param("sync_window", sync_window, 50);
333  sync_.reset(
335  SyncPolicy(sync_window), *sub_odom_, *sub_imu_));
336  sync_->registerCallback(boost::bind(&TrackOdometryNode::cbOdomImu, this, _1, _2));
337 
338  pnh_.param("base_link_id", base_link_id_overwrite_, std::string(""));
339  }
340 
342  nh_, "reset_odometry_z",
343  pnh_, "reset_z", 1, &TrackOdometryNode::cbResetZ, this);
344  pub_odom_ = nh_.advertise<nav_msgs::Odometry>("odom", 8);
345 
346  if (pnh_.hasParam("z_filter"))
347  {
348  z_filter_timeconst_ = -1.0;
349  double z_filter;
350  if (pnh_.getParam("z_filter", z_filter))
351  {
352  const double odom_freq = 100.0;
353  if (0.0 < z_filter && z_filter < 1.0)
354  z_filter_timeconst_ = (1.0 / odom_freq) / (1.0 - z_filter);
355  }
356  ROS_ERROR(
357  "track_odometry: ~z_filter parameter (exponential filter (1 - alpha) value) is deprecated. "
358  "Use ~z_filter_timeconst (in seconds) instead. "
359  "Treated as z_filter_timeconst=%0.6f. (negative value means disabled)",
361  }
362  else
363  {
364  pnh_.param("z_filter_timeconst", z_filter_timeconst_, -1.0);
365  }
366  pnh_.param("tf_tolerance", tf_tolerance_, 0.01);
367  pnh_.param("use_kf", use_kf_, true);
368  pnh_.param("enable_negative_slip", negative_slip_, false);
369  pnh_.param("debug", debug_, false);
370  pnh_.param("publish_tf", publish_tf_, true);
371 
372  if (base_link_id_overwrite_.size() > 0)
373  {
375  }
376 
377  // sigma_odom_ [rad/s]: standard deviation of odometry angular vel on straight running
378  pnh_.param("sigma_odom", sigma_odom_, 0.005);
379  // sigma_predict_ [sigma/second]: prediction sigma of kalman filter
380  pnh_.param("sigma_predict", sigma_predict_, 0.5);
381  // predict_filter_tc_ [sec.]: LPF time-constant to forget estimated slip_ ratio
382  pnh_.param("predict_filter_tc", predict_filter_tc_, 1.0);
383 
384  has_imu_ = false;
385  has_odom_ = false;
386 
387  dist_ = 0;
388  slip_.set(0.0, 0.1);
389  }
390  void cbTimer(const ros::TimerEvent& event)
391  {
392  nav_msgs::Odometry::Ptr odom(new nav_msgs::Odometry);
393  odom->header.stamp = ros::Time::now();
394  odom->header.frame_id = odom_id_;
395  odom->child_frame_id = base_link_id_;
396  odom->pose.pose.orientation.w = 1.0;
397  cbOdom(odom);
398  }
399  void spin()
400  {
401  if (!without_odom_)
402  {
403  ros::spin();
404  }
405  else
406  {
407  ros::Timer timer = nh_.createTimer(
408  ros::Duration(1.0 / 50.0), &TrackOdometryNode::cbTimer, this);
409  ros::spin();
410  }
411  }
412 };
413 
414 int main(int argc, char* argv[])
415 {
416  ros::init(argc, argv, "track_odometry");
417 
418  TrackOdometryNode odom;
419 
420  odom.spin();
421 
422  return 0;
423 }
neonavigation_common::compat::getCompat
int getCompat()
ROS_ERROR_THROTTLE
#define ROS_ERROR_THROTTLE(period,...)
TrackOdometryNode::cbOdom
void cbOdom(const nav_msgs::Odometry::ConstPtr &msg)
Definition: track_odometry.cpp:207
ros::Publisher
message_filters::Synchronizer
TrackOdometryNode::base_link_id_overwrite_
std::string base_link_id_overwrite_
Definition: track_odometry.cpp:109
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
TrackOdometryNode::dist_
double dist_
Definition: track_odometry.cpp:123
tf2::Stamped::setData
void setData(const T &input)
tf2::fromMsg
void fromMsg(const A &, B &b)
TrackOdometryNode::negative_slip_
bool negative_slip_
Definition: track_odometry.cpp:119
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
track_odometry::KalmanFilter1::sigma_
double sigma_
Definition: kalman_filter1.h:41
TrackOdometryNode::cbTimer
void cbTimer(const ros::TimerEvent &event)
Definition: track_odometry.cpp:390
ros.h
TrackOdometryNode::nh_
ros::NodeHandle nh_
Definition: track_odometry.cpp:92
TrackOdometryNode::SyncPolicy
message_filters::sync_policies::ApproximateTime< nav_msgs::Odometry, sensor_msgs::Imu > SyncPolicy
Definition: track_odometry.cpp:90
TrackOdometryNode::sub_reset_z_
ros::Subscriber sub_reset_z_
Definition: track_odometry.cpp:100
track_odometry::KalmanFilter1
Definition: kalman_filter1.h:37
ros::TransportHints
TrackOdometryNode::tf_broadcaster_
tf2_ros::TransformBroadcaster tf_broadcaster_
Definition: track_odometry.cpp:104
TrackOdometryNode::tf_buffer_
tf2_ros::Buffer tf_buffer_
Definition: track_odometry.cpp:102
toEigen
Eigen::Vector3d toEigen(const geometry_msgs::Vector3 &a)
Definition: track_odometry.cpp:57
TrackOdometryNode::sub_imu_raw_
ros::Subscriber sub_imu_raw_
Definition: track_odometry.cpp:95
TrackOdometryNode::gyro_zero_
double gyro_zero_[3]
Definition: track_odometry.cpp:113
tf2::Stamped
main
int main(int argc, char *argv[])
Definition: track_odometry.cpp:414
compatibility.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::TransportHints::tcpNoDelay
TransportHints & tcpNoDelay(bool nodelay=true)
transform_broadcaster.h
TrackOdometryNode::sub_imu_
std::shared_ptr< message_filters::Subscriber< sensor_msgs::Imu > > sub_imu_
Definition: track_odometry.cpp:97
message_filters::Subscriber
tf2_ros::TransformListener
ros::TransportHints::reliable
TransportHints & reliable()
neonavigation_common::compat::subscribe
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, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const ros::VoidConstPtr &tracked_object=ros::VoidConstPtr(), const ros::TransportHints &transport_hints=ros::TransportHints())
TrackOdometryNode::publish_tf_
bool publish_tf_
Definition: track_odometry.cpp:130
message_filters::sync_policies::ApproximateTime
TrackOdometryNode::tf_listener_
tf2_ros::TransformListener tf_listener_
Definition: track_odometry.cpp:103
TrackOdometryNode::without_odom_
bool without_odom_
Definition: track_odometry.cpp:124
tf2_ros::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
toPoint
geometry_msgs::Point toPoint(const Eigen::Vector3d &a)
Definition: track_odometry.cpp:69
ROS_DEBUG
#define ROS_DEBUG(...)
TrackOdometryNode::sigma_odom_
double sigma_odom_
Definition: track_odometry.cpp:121
track_odometry::KalmanFilter1::predict
void predict(const double x_plus, const double sigma_plus)
Definition: kalman_filter1.h:54
tf2::Stamped::frame_id_
std::string frame_id_
subscriber.h
TrackOdometryNode::cbResetZ
void cbResetZ(const std_msgs::Float32::Ptr &msg)
Definition: track_odometry.cpp:132
neonavigation_common::compat::current_level
const int current_level
track_odometry::KalmanFilter1::measure
void measure(const double x_in, const double sigma_in)
Definition: kalman_filter1.h:59
TrackOdometryNode::pub_odom_
ros::Publisher pub_odom_
Definition: track_odometry.cpp:101
track_odometry::KalmanFilter1::x_
double x_
Definition: kalman_filter1.h:40
TrackOdometryNode::cbImu
void cbImu(const sensor_msgs::Imu::ConstPtr &msg)
Definition: track_odometry.cpp:145
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
tf2::Stamped::stamp_
ros::Time stamp_
TrackOdometryNode::odom_id_
std::string odom_id_
Definition: track_odometry.cpp:110
TrackOdometryNode::has_odom_
bool has_odom_
Definition: track_odometry.cpp:129
tf2_ros::Buffer
TrackOdometryNode::debug_
bool debug_
Definition: track_odometry.cpp:117
ros::TimerEvent
TrackOdometryNode::z_filter_timeconst_
double z_filter_timeconst_
Definition: track_odometry.cpp:114
TrackOdometryNode::slip_
track_odometry::KalmanFilter1 slip_
Definition: track_odometry.cpp:126
neonavigation_common::compat::checkCompatMode
void checkCompatMode()
transform_listener.h
TrackOdometryNode::cbOdomImu
void cbOdomImu(const nav_msgs::Odometry::ConstPtr &odom_msg, const sensor_msgs::Imu::ConstPtr &imu_msg)
Definition: track_odometry.cpp:136
TrackOdometryNode::sync_
std::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: track_odometry.cpp:98
TrackOdometryNode::has_imu_
bool has_imu_
Definition: track_odometry.cpp:128
ros::Time
tf2::doTransform
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
TrackOdometryNode::TrackOdometryNode
TrackOdometryNode()
Definition: track_odometry.cpp:295
TrackOdometryNode::sigma_predict_
double sigma_predict_
Definition: track_odometry.cpp:120
kalman_filter1.h
ROS_ERROR
#define ROS_ERROR(...)
tf2_ros::TransformBroadcaster
TrackOdometryNode::predict_filter_tc_
double predict_filter_tc_
Definition: track_odometry.cpp:122
TrackOdometryNode
Definition: track_odometry.cpp:86
TrackOdometryNode::odom_prev_
nav_msgs::Odometry odom_prev_
Definition: track_odometry.cpp:105
TrackOdometryNode::odomraw_prev_
nav_msgs::Odometry odomraw_prev_
Definition: track_odometry.cpp:106
angle
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
tf2::Quaternion
synchronizer.h
TrackOdometryNode::use_kf_
bool use_kf_
Definition: track_odometry.cpp:118
tf2_geometry_msgs.h
tf2::toMsg
B toMsg(const A &a)
approximate_time.h
ros::spin
ROSCPP_DECL void spin()
track_odometry::KalmanFilter1::set
void set(const double x0=0.0, const double sigma0=std::numeric_limits< double >::infinity())
Definition: kalman_filter1.h:43
TrackOdometryNode::imu_
sensor_msgs::Imu imu_
Definition: track_odometry.cpp:112
TrackOdometryNode::spin
void spin()
Definition: track_odometry.cpp:399
TrackOdometryNode::sub_odom_
std::shared_ptr< message_filters::Subscriber< nav_msgs::Odometry > > sub_odom_
Definition: track_odometry.cpp:96
TrackOdometryNode::base_link_id_
std::string base_link_id_
Definition: track_odometry.cpp:108
tf2::TransformException
TrackOdometryNode::tf_tolerance_
double tf_tolerance_
Definition: track_odometry.cpp:115
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
TrackOdometryNode::pnh_
ros::NodeHandle pnh_
Definition: track_odometry.cpp:93
ros::Duration
ros::Timer
tf2_ros::Buffer::lookupTransform
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
ros::NodeHandle
ros::Subscriber
toVector3
geometry_msgs::Vector3 toVector3(const Eigen::Vector3d &a)
Definition: track_odometry.cpp:77
ros::Time::now
static Time now()


track_odometry
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:18