imu_to_tf.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2019, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
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  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <ros/ros.h>
30 #include <nodelet/nodelet.h>
31 #include <sensor_msgs/Imu.h>
34 #include <tf/transform_listener.h>
35 
36 namespace rtabmap_util
37 {
38 
39 class ImuToTF : public nodelet::Nodelet
40 {
41 public:
42  ImuToTF() :
43  fixedFrameId_("odom"),
45  {}
46 
47  virtual ~ImuToTF()
48  {
49  }
50 
51 private:
52  virtual void onInit()
53  {
56 
57  pnh.param("fixed_frame_id", fixedFrameId_, fixedFrameId_);
58  pnh.param("base_frame_id", baseFrameId_, baseFrameId_);
59  pnh.param("wait_for_transform_duration", waitForTransformDuration_, waitForTransformDuration_);
60  NODELET_INFO("fixed_frame_id: %s", fixedFrameId_.c_str());
61  NODELET_INFO("base_frame_id: %s", baseFrameId_.c_str());
62 
63  sub_ = nh.subscribe<sensor_msgs::Imu>("imu/data", 1, &ImuToTF::imuCallback, this);
64  }
65 
66  void imuCallback(const sensor_msgs::ImuConstPtr & msg)
67  {
69  tf::quaternionMsgToTF(msg->orientation, q);
71  st.setRotation(q);
72 
74  st.stamp_ = msg->header.stamp;
75 
76  if(!baseFrameId_.empty() &&
77  baseFrameId_.compare(msg->header.frame_id) != 0)
78  {
79  try
80  {
81  std::string errorMsg;
82  if(!tfListener_.waitForTransform(baseFrameId_, msg->header.frame_id, msg->header.stamp, ros::Duration(waitForTransformDuration_), ros::Duration(0.01), &errorMsg))
83  {
84  NODELET_ERROR("Could not get transform from %s to %s after %f seconds (for stamp=%f)! Error=\"%s\".",
85  baseFrameId_.c_str(), msg->header.frame_id.c_str(), 0.1, msg->header.stamp.toSec(), errorMsg.c_str());
86  return;
87  }
88 
90  tfListener_.lookupTransform(baseFrameId_, msg->header.frame_id, msg->header.stamp, tmp);
92  q.setRPY(0.0,0.0,tf::getYaw(tmp.getRotation()));
93  tf::Transform t = tf::Transform(q)*st*tmp.inverse(); // base_frame orientation
94  st.setRotation(t.getRotation());
96  }
97  catch(tf::TransformException & ex)
98  {
99  NODELET_ERROR("(getting transform %s -> %s) %s", baseFrameId_.c_str(), msg->header.frame_id.c_str(), ex.what());
100  return;
101  }
102  }
103  else
104  {
105  st.child_frame_id_ = msg->header.frame_id;
106  }
107  st.setOrigin(tf::Vector3(0,0,0));
108 
109  pub_.sendTransform(st);
110  }
111 
112 private:
115  std::string fixedFrameId_;
116  std::string baseFrameId_;
119 };
120 
121 
123 }
124 
tf::Transform::getRotation
Quaternion getRotation() const
tf::StampedTransform::stamp_
ros::Time stamp_
NODELET_ERROR
#define NODELET_ERROR(...)
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
tf::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
rtabmap_util::ImuToTF::fixedFrameId_
std::string fixedFrameId_
Definition: imu_to_tf.cpp:115
tf::StampedTransform::child_frame_id_
std::string child_frame_id_
ros.h
rtabmap_util::ImuToTF::sub_
ros::Subscriber sub_
Definition: imu_to_tf.cpp:113
tf::quaternionMsgToTF
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
rtabmap_util::ImuToTF::ImuToTF
ImuToTF()
Definition: imu_to_tf.cpp:42
rtabmap_util::ImuToTF::waitForTransformDuration_
double waitForTransformDuration_
Definition: imu_to_tf.cpp:118
tf::StampedTransform
rtabmap_util
Definition: MapsManager.h:49
tf::StampedTransform::frame_id_
std::string frame_id_
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
transform_broadcaster.h
rtabmap_util::ImuToTF::imuCallback
void imuCallback(const sensor_msgs::ImuConstPtr &msg)
Definition: imu_to_tf.cpp:66
tf::getYaw
static double getYaw(const geometry_msgs::Quaternion &msg_q)
tf::Transform::inverse
Transform inverse() const
rtabmap_util::ImuToTF::baseFrameId_
std::string baseFrameId_
Definition: imu_to_tf.cpp:116
tf::Transform::setRotation
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
q
EIGEN_DEVICE_FUNC const Scalar & q
tf::TransformBroadcaster
rtabmap_util::ImuToTF::pub_
tf::TransformBroadcaster pub_
Definition: imu_to_tf.cpp:114
rtabmap_util::ImuToTF
Definition: imu_to_tf.cpp:39
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
rtabmap_util::ImuToTF::tfListener_
tf::TransformListener tfListener_
Definition: imu_to_tf.cpp:117
tf::Transformer::waitForTransform
bool waitForTransform(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::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
tf::Transform
tf::Transform::setOrigin
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
NODELET_INFO
#define NODELET_INFO(...)
transform_listener.h
rtabmap_util::PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(rtabmap_util::DisparityToDepth, nodelet::Nodelet)
nodelet::Nodelet
nodelet.h
republish_tf_static.msg
msg
Definition: republish_tf_static.py:5
class_list_macros.hpp
tf::TransformListener
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
rtabmap_util::ImuToTF::~ImuToTF
virtual ~ImuToTF()
Definition: imu_to_tf.cpp:47
tf::Transformer::lookupTransform
void 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, StampedTransform &transform) const
tf2::TransformException
t
Point2 t(10, 10)
rtabmap_util::ImuToTF::onInit
virtual void onInit()
Definition: imu_to_tf.cpp:52
ros::Duration
Matrix3x3.h
tf::Quaternion
ros::NodeHandle
ros::Subscriber


rtabmap_util
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:40:50