message_to_tf.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <nav_msgs/Odometry.h>
3 #include <geometry_msgs/PoseStamped.h>
4 #include <geometry_msgs/Vector3Stamped.h>
5 #include <geometry_msgs/TransformStamped.h>
6 #include <sensor_msgs/Imu.h>
8 #include <tf/transform_listener.h> // for tf::getPrefixParam()
10 
12 
13 std::string g_odometry_topic;
14 std::string g_pose_topic;
15 std::string g_imu_topic;
16 std::string g_topic;
17 std::string g_frame_id;
19 std::string g_position_frame_id;
21 std::string g_child_frame_id;
22 
24 
25 std::string g_tf_prefix;
26 
30 
31 #ifndef TF_MATRIX3x3_H
32  typedef btScalar tfScalar;
33  namespace tf { typedef btMatrix3x3 Matrix3x3; }
34 #endif
35 
36 void addTransform(std::vector<geometry_msgs::TransformStamped>& transforms, const tf::StampedTransform& tf)
37 {
38  transforms.push_back(geometry_msgs::TransformStamped());
39  tf::transformStampedTFToMsg(tf, transforms.back());
40 }
41 
42 void sendTransform(geometry_msgs::Pose const &pose, const std_msgs::Header& header, std::string child_frame_id = "")
43 {
44  std::vector<geometry_msgs::TransformStamped> transforms;
45 
47  tf.stamp_ = header.stamp;
48 
49  tf.frame_id_ = header.frame_id;
50  if (!g_frame_id.empty()) tf.frame_id_ = g_frame_id;
52 
53  if (!g_child_frame_id.empty()) child_frame_id = g_child_frame_id;
54  if (child_frame_id.empty()) child_frame_id = "base_link";
55 
56  tf::Quaternion orientation;
57  tf::quaternionMsgToTF(pose.orientation, orientation);
58  tfScalar yaw, pitch, roll;
59  tf::Matrix3x3(orientation).getEulerYPR(yaw, pitch, roll);
60  tf::Point position;
61  tf::pointMsgToTF(pose.position, position);
62 
63  // position intermediate transform (x,y,z)
64  if( !g_position_frame_id.empty() && child_frame_id != g_position_frame_id) {
66  tf.setOrigin(tf::Vector3(position.x(), position.y(), position.z() ));
67  tf.setRotation(tf::Quaternion(0.0, 0.0, 0.0, 1.0));
68  addTransform(transforms, tf);
69  }
70 
71  // footprint intermediate transform (x,y,yaw)
72  if (!g_footprint_frame_id.empty() && child_frame_id != g_footprint_frame_id) {
74  tf.setOrigin(tf::Vector3(position.x(), position.y(), 0.0));
75  tf.setRotation(tf::createQuaternionFromRPY(0.0, 0.0, yaw));
76  addTransform(transforms, tf);
77 
78  yaw = 0.0;
79  position.setX(0.0);
80  position.setY(0.0);
82  }
83 
84  // stabilized intermediate transform (z)
85  if (!g_footprint_frame_id.empty() && child_frame_id != g_stabilized_frame_id) {
87  tf.setOrigin(tf::Vector3(0.0, 0.0, position.z()));
89  addTransform(transforms, tf);
90 
91  position.setZ(0.0);
93  }
94 
95  // base_link transform (roll, pitch)
97  tf.child_frame_id_ = tf::resolve(g_tf_prefix, child_frame_id);
98  tf.setOrigin(position);
99  tf.setRotation(tf::createQuaternionFromRPY(roll, pitch, yaw));
100  addTransform(transforms, tf);
101  }
102 
103  g_transform_broadcaster->sendTransform(transforms);
104 
105  // publish pose message
106  if (g_pose_publisher) {
107  geometry_msgs::PoseStamped pose_stamped;
108  pose_stamped.pose = pose;
109  pose_stamped.header = header;
110  g_pose_publisher.publish(pose_stamped);
111  }
112 
113  // publish pose message
114  if (g_euler_publisher) {
115  geometry_msgs::Vector3Stamped euler_stamped;
116  euler_stamped.vector.x = roll;
117  euler_stamped.vector.y = pitch;
118  euler_stamped.vector.z = yaw;
119  euler_stamped.header = header;
120  g_euler_publisher.publish(euler_stamped);
121  }
122 }
123 
124 void odomCallback(nav_msgs::Odometry const &odometry) {
125  sendTransform(odometry.pose.pose, odometry.header, odometry.child_frame_id);
126 }
127 
128 void poseCallback(geometry_msgs::PoseStamped const &pose) {
129  sendTransform(pose.pose, pose.header);
130 }
131 
132 void tfCallback(geometry_msgs::TransformStamped const &tf) {
133  geometry_msgs::Pose pose;
134  pose.position.x = tf.transform.translation.x;
135  pose.position.y = tf.transform.translation.y;
136  pose.position.z = tf.transform.translation.z;
137  pose.orientation = tf.transform.rotation;
138 
139  sendTransform(pose, tf.header);
140 }
141 
142 void imuCallback(sensor_msgs::Imu const &imu) {
143  std::vector<geometry_msgs::TransformStamped> transforms;
144  std::string child_frame_id;
145 
147  tf.stamp_ = imu.header.stamp;
148 
150  if (!g_child_frame_id.empty()) child_frame_id = g_child_frame_id;
151  if (child_frame_id.empty()) child_frame_id = "base_link";
152 
153  tf::Quaternion orientation;
154  tf::quaternionMsgToTF(imu.orientation, orientation);
155  tfScalar yaw, pitch, roll;
156  tf::Matrix3x3(orientation).getEulerYPR(yaw, pitch, roll);
157  tf::Quaternion rollpitch = tf::createQuaternionFromRPY(roll, pitch, 0.0);
158 
159  // base_link transform (roll, pitch)
160  if (g_publish_roll_pitch) {
161  tf.child_frame_id_ = tf::resolve(g_tf_prefix, child_frame_id);
162  tf.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
163  tf.setRotation(rollpitch);
164  addTransform(transforms, tf);
165  }
166 
167  if (!transforms.empty()) g_transform_broadcaster->sendTransform(transforms);
168 
169  // publish pose message
170  if (g_pose_publisher) {
171  geometry_msgs::PoseStamped pose_stamped;
172  pose_stamped.header.stamp = imu.header.stamp;
173  pose_stamped.header.frame_id = g_stabilized_frame_id;
174  tf::quaternionTFToMsg(rollpitch, pose_stamped.pose.orientation);
175  g_pose_publisher.publish(pose_stamped);
176  }
177 }
178 
180  if (input.getDataType() == "nav_msgs/Odometry") {
181  nav_msgs::Odometry::ConstPtr odom = input.instantiate<nav_msgs::Odometry>();
182  odomCallback(*odom);
183  return;
184  }
185 
186  if (input.getDataType() == "geometry_msgs/PoseStamped") {
187  geometry_msgs::PoseStamped::ConstPtr pose = input.instantiate<geometry_msgs::PoseStamped>();
188  poseCallback(*pose);
189  return;
190  }
191 
192  if (input.getDataType() == "sensor_msgs/Imu") {
193  sensor_msgs::Imu::ConstPtr imu = input.instantiate<sensor_msgs::Imu>();
194  imuCallback(*imu);
195  return;
196  }
197 
198  if (input.getDataType() == "geometry_msgs/TransformStamped") {
199  geometry_msgs::TransformStamped::ConstPtr tf = input.instantiate<geometry_msgs::TransformStamped>();
200  tfCallback(*tf);
201  return;
202  }
203 
204  ROS_ERROR_THROTTLE(1.0, "message_to_tf received a %s message. Supported message types: nav_msgs/Odometry geometry_msgs/PoseStamped geometry_msgs/TransformStamped sensor_msgs/Imu", input.getDataType().c_str());
205 }
206 
207 int main(int argc, char** argv) {
208  ros::init(argc, argv, "message_to_tf");
209 
210  g_footprint_frame_id = "base_footprint";
211  g_stabilized_frame_id = "base_stabilized";
212  // g_position_frame_id = "base_position";
213  // g_child_frame_id = "base_link";
214 
215  ros::NodeHandle priv_nh("~");
216  priv_nh.getParam("odometry_topic", g_odometry_topic);
217  priv_nh.getParam("pose_topic", g_pose_topic);
218  priv_nh.getParam("imu_topic", g_imu_topic);
219  priv_nh.getParam("topic", g_topic);
220  priv_nh.getParam("frame_id", g_frame_id);
221  priv_nh.getParam("footprint_frame_id", g_footprint_frame_id);
222  priv_nh.getParam("position_frame_id", g_position_frame_id);
223  priv_nh.getParam("stabilized_frame_id", g_stabilized_frame_id);
224  priv_nh.getParam("child_frame_id", g_child_frame_id);
225 
226  // get topic from the commandline
227  if (argc > 1) {
228  g_topic = argv[1];
229  g_odometry_topic.clear();
230  g_pose_topic.clear();
231  g_imu_topic.clear();
232  }
233 
234  g_publish_roll_pitch = true;
235  priv_nh.getParam("publish_roll_pitch", g_publish_roll_pitch);
236 
237  g_tf_prefix = tf::getPrefixParam(priv_nh);
238  g_transform_broadcaster = new tf::TransformBroadcaster;
239 
240  ros::NodeHandle node;
241  ros::Subscriber sub1, sub2, sub3, sub4;
242  int subscribers = 0;
243  if (!g_odometry_topic.empty()) {
244  sub1 = node.subscribe(g_odometry_topic, 10, &odomCallback);
245  subscribers++;
246  }
247  if (!g_pose_topic.empty()) {
248  sub2 = node.subscribe(g_pose_topic, 10, &poseCallback);
249  subscribers++;
250  }
251  if (!g_imu_topic.empty()) {
252  sub3 = node.subscribe(g_imu_topic, 10, &imuCallback);
253  subscribers++;
254  }
255  if (!g_topic.empty()) {
256  sub4 = node.subscribe(g_topic, 10, &multiCallback);
257  subscribers++;
258  }
259 
260  if (subscribers == 0) {
261  ROS_FATAL("Usage: rosrun message_to_tf message_to_tf <topic>");
262  return 1;
263  } else if (subscribers > 1) {
264  ROS_FATAL("More than one of the parameters odometry_topic, pose_topic, imu_topic and topic are set.\n"
265  "Please specify exactly one of them or simply add the topic name to the command line.");
266  return 1;
267  }
268 
269  bool publish_pose = true;
270  priv_nh.getParam("publish_pose", publish_pose);
271  if (publish_pose) {
272  std::string publish_pose_topic;
273  priv_nh.getParam("publish_pose_topic", publish_pose_topic);
274 
275  if (!publish_pose_topic.empty())
276  g_pose_publisher = node.advertise<geometry_msgs::PoseStamped>(publish_pose_topic, 10);
277  else
278  g_pose_publisher = priv_nh.advertise<geometry_msgs::PoseStamped>("pose", 10);
279  }
280 
281  bool publish_euler = true;
282  priv_nh.getParam("publish_euler", publish_euler);
283  if (publish_euler) {
284  std::string publish_euler_topic;
285  priv_nh.getParam("publish_euler_topic", publish_euler_topic);
286 
287  if (!publish_euler_topic.empty())
288  g_euler_publisher = node.advertise<geometry_msgs::Vector3Stamped>(publish_euler_topic, 10);
289  else
290  g_euler_publisher = priv_nh.advertise<geometry_msgs::Vector3Stamped>("euler", 10);
291  }
292 
293  ros::spin();
295  return 0;
296 }
int main(int argc, char **argv)
std::string g_imu_topic
static tf::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw)
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
#define ROS_FATAL(...)
std::string const & getDataType() const
static void pointMsgToTF(const geometry_msgs::Point &msg_v, Point &bt_v)
void publish(const boost::shared_ptr< M > &message) const
std::string getPrefixParam(ros::NodeHandle &nh)
TFSIMD_FORCE_INLINE void setX(tfScalar x)
std::string g_stabilized_frame_id
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())
std::string g_child_frame_id
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TFSIMD_FORCE_INLINE void setZ(tfScalar z)
btMatrix3x3 Matrix3x3
tf::TransformBroadcaster * g_transform_broadcaster
void imuCallback(sensor_msgs::Imu const &imu)
ros::Publisher g_pose_publisher
ROSCPP_DECL void spin(Spinner &spinner)
std::string g_pose_topic
std::string resolve(const std::string &prefix, const std::string &frame_name)
TFSIMD_FORCE_INLINE const tfScalar & x() const
#define ROS_ERROR_THROTTLE(rate,...)
std::string child_frame_id_
TFSIMD_FORCE_INLINE const tfScalar & z() const
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
void tfCallback(geometry_msgs::TransformStamped const &tf)
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void sendTransform(const StampedTransform &transform)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
TFSIMD_FORCE_INLINE void setBasis(const Matrix3x3 &basis)
boost::shared_ptr< M > instantiate() const
std::string g_frame_id
btScalar tfScalar
std::string g_footprint_frame_id
bool g_publish_roll_pitch
void sendTransform(geometry_msgs::Pose const &pose, const std_msgs::Header &header, std::string child_frame_id="")
std::string g_tf_prefix
bool getParam(const std::string &key, std::string &s) const
ros::Publisher g_euler_publisher
void addTransform(std::vector< geometry_msgs::TransformStamped > &transforms, const tf::StampedTransform &tf)
void poseCallback(geometry_msgs::PoseStamped const &pose)
static void transformStampedTFToMsg(const StampedTransform &bt, geometry_msgs::TransformStamped &msg)
std::string g_position_frame_id
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
static const Matrix3x3 & getIdentity()
void multiCallback(topic_tools::ShapeShifter const &input)
std::string frame_id_
void odomCallback(nav_msgs::Odometry const &odometry)
std::string g_odometry_topic
std::string g_topic


message_to_tf
Author(s): Johannes Meyer
autogenerated on Thu Feb 18 2021 03:29:40