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_ros
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(msg->header.frame_id, baseFrameId_, msg->header.stamp, tmp);
91  tf::Transform t = tmp.inverse()*st*tmp;
92  st.setRotation(t.getRotation());
94  }
95  catch(tf::TransformException & ex)
96  {
97  NODELET_ERROR("(getting transform %s -> %s) %s", baseFrameId_.c_str(), msg->header.frame_id.c_str(), ex.what());
98  return;
99  }
100  }
101  else
102  {
103  st.child_frame_id_ = msg->header.frame_id;
104  }
105  st.setOrigin(tf::Vector3(0,0,0));
106 
107  pub_.sendTransform(st);
108  }
109 
110 private:
113  std::string fixedFrameId_;
114  std::string baseFrameId_;
117 };
118 
119 
121 }
122 
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
tf::TransformBroadcaster pub_
Definition: imu_to_tf.cpp:112
#define NODELET_ERROR(...)
virtual void onInit()
Definition: imu_to_tf.cpp:52
Transform inverse() const
std::string fixedFrameId_
Definition: imu_to_tf.cpp:113
Quaternion getRotation() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::NodeHandle & getNodeHandle() const
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
std::string baseFrameId_
Definition: imu_to_tf.cpp:114
ros::NodeHandle & getPrivateNodeHandle() const
ros::Subscriber sub_
Definition: imu_to_tf.cpp:111
geometry_msgs::TransformStamped t
std::string child_frame_id_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
void sendTransform(const StampedTransform &transform)
tf::TransformListener tfListener_
Definition: imu_to_tf.cpp:115
#define NODELET_INFO(...)
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
std::string frame_id_
double waitForTransformDuration_
Definition: imu_to_tf.cpp:116
void imuCallback(const sensor_msgs::ImuConstPtr &msg)
Definition: imu_to_tf.cpp:66
q


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40