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>
31 #ifndef TF_MATRIX3x3_H
38 transforms.push_back(geometry_msgs::TransformStamped());
42 void sendTransform(geometry_msgs::Pose
const &pose,
const std_msgs::Header& header, std::string child_frame_id =
"")
44 std::vector<geometry_msgs::TransformStamped> transforms;
54 if (child_frame_id.empty()) child_frame_id =
"base_link";
66 tf.setOrigin(tf::Vector3(position.x(), position.y(), position.z() ));
74 tf.setOrigin(tf::Vector3(position.x(), position.y(), 0.0));
87 tf.setOrigin(tf::Vector3(0.0, 0.0, position.z()));
98 tf.setOrigin(position);
107 geometry_msgs::PoseStamped pose_stamped;
108 pose_stamped.pose = pose;
109 pose_stamped.header =
header;
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;
125 sendTransform(odometry.pose.pose, odometry.header, odometry.child_frame_id);
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;
143 std::vector<geometry_msgs::TransformStamped> transforms;
144 std::string child_frame_id;
147 tf.stamp_ = imu.header.stamp;
151 if (child_frame_id.empty()) child_frame_id =
"base_link";
162 tf.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
163 tf.setRotation(rollpitch);
171 geometry_msgs::PoseStamped pose_stamped;
172 pose_stamped.header.stamp = imu.header.stamp;
181 nav_msgs::Odometry::ConstPtr odom = input.
instantiate<nav_msgs::Odometry>();
186 if (input.
getDataType() ==
"geometry_msgs/PoseStamped") {
187 geometry_msgs::PoseStamped::ConstPtr pose = input.
instantiate<geometry_msgs::PoseStamped>();
193 sensor_msgs::Imu::ConstPtr imu = input.
instantiate<sensor_msgs::Imu>();
198 if (input.
getDataType() ==
"geometry_msgs/TransformStamped") {
199 geometry_msgs::TransformStamped::ConstPtr
tf = input.
instantiate<geometry_msgs::TransformStamped>();
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());
207 int main(
int argc,
char** argv) {
260 if (subscribers == 0) {
261 ROS_FATAL(
"Usage: rosrun message_to_tf message_to_tf <topic>");
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.");
269 bool publish_pose =
true;
270 priv_nh.
getParam(
"publish_pose", publish_pose);
272 std::string publish_pose_topic;
273 priv_nh.
getParam(
"publish_pose_topic", publish_pose_topic);
275 if (!publish_pose_topic.empty())
281 bool publish_euler =
true;
282 priv_nh.
getParam(
"publish_euler", publish_euler);
284 std::string publish_euler_topic;
285 priv_nh.
getParam(
"publish_euler_topic", publish_euler_topic);
287 if (!publish_euler_topic.empty())