imu_attitude_to_tf_node.cpp
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2012, Stefan Kohlbrecher, TU Darmstadt
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 Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 
30 #include "ros/ros.h"
32 #include "sensor_msgs/Imu.h"
33 
35 std::string p_base_frame_;
39 
40 #ifndef TF_MATRIX3x3_H
41  typedef btScalar tfScalar;
42  namespace tf { typedef btMatrix3x3 Matrix3x3; }
43 #endif
44 
45 void imuMsgCallback(const sensor_msgs::Imu& imu_msg)
46 {
47  tf::quaternionMsgToTF(imu_msg.orientation, tmp_);
48 
49  tfScalar yaw, pitch, roll;
50  tf::Matrix3x3(tmp_).getRPY(roll, pitch, yaw);
51 
52  tmp_.setRPY(roll, pitch, 0.0);
53 
54  transform_.setRotation(tmp_);
55 
56  transform_.stamp_ = imu_msg.header.stamp;
57 
58  tfB_->sendTransform(transform_);
59 }
60 
61 int main(int argc, char **argv) {
62  ros::init(argc, argv, ROS_PACKAGE_NAME);
63 
65  ros::NodeHandle pn("~");
66 
67  pn.param("base_stabilized_frame", p_base_stabilized_frame_, std::string("base_stabilized"));
68  pn.param("base_frame", p_base_frame_, std::string("base_link"));
69 
70  tfB_ = new tf::TransformBroadcaster();
71  transform_.getOrigin().setX(0.0);
72  transform_.getOrigin().setY(0.0);
73  transform_.getOrigin().setZ(0.0);
75  transform_.child_frame_id_ = p_base_frame_;
76 
77  ros::Subscriber imu_subscriber = n.subscribe("imu_topic", 10, imuMsgCallback);
78 
79  ros::spin();
80 
81  delete tfB_;
82 
83  return 0;
84 }
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
TFSIMD_FORCE_INLINE void setX(tfScalar x)
TFSIMD_FORCE_INLINE void setY(tfScalar y)
double tfScalar
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TFSIMD_FORCE_INLINE void setZ(tfScalar z)
std::string p_base_stabilized_frame_
btMatrix3x3 Matrix3x3
int main(int argc, char **argv)
btScalar tfScalar
ROSCPP_DECL void spin(Spinner &spinner)
tf::StampedTransform transform_
std::string child_frame_id_
std::string p_base_frame_
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void sendTransform(const StampedTransform &transform)
tf::TransformBroadcaster * tfB_
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void imuMsgCallback(const sensor_msgs::Imu &imu_msg)
tf::Quaternion tmp_
std::string frame_id_


hector_imu_attitude_to_tf
Author(s): Stefan Kohlbrecher
autogenerated on Sun Nov 3 2019 03:18:28