00001 #include <ros/ros.h>
00002 #include <nav_msgs/Odometry.h>
00003 #include <geometry_msgs/PoseStamped.h>
00004 #include <geometry_msgs/Vector3Stamped.h>
00005 #include <sensor_msgs/Imu.h>
00006 #include <tf/transform_broadcaster.h>
00007 #include <tf/transform_datatypes.h>
00008
00009 #include <topic_tools/shape_shifter.h>
00010
00011 std::string g_odometry_topic;
00012 std::string g_pose_topic;
00013 std::string g_imu_topic;
00014 std::string g_topic;
00015 std::string g_frame_id;
00016 std::string g_footprint_frame_id;
00017 std::string g_position_frame_id;
00018 std::string g_stabilized_frame_id;
00019 std::string g_child_frame_id;
00020
00021 tf::TransformBroadcaster *g_transform_broadcaster;
00022 ros::Publisher g_pose_publisher;
00023 ros::Publisher g_euler_publisher;
00024
00025 #ifndef TF_MATRIX3x3_H
00026 typedef btScalar tfScalar;
00027 namespace tf { typedef btMatrix3x3 Matrix3x3; }
00028 #endif
00029
00030 void addTransform(std::vector<geometry_msgs::TransformStamped>& transforms, const tf::StampedTransform& tf)
00031 {
00032 transforms.resize(transforms.size()+1);
00033 tf::transformStampedTFToMsg(tf, transforms.back());
00034 }
00035
00036 void sendTransform(geometry_msgs::Pose const &pose, const std_msgs::Header& header, std::string child_frame_id = "")
00037 {
00038 std::vector<geometry_msgs::TransformStamped> transforms;
00039
00040 tf::StampedTransform tf;
00041 tf.frame_id_ = header.frame_id;
00042 if (!g_frame_id.empty()) tf.frame_id_ = g_frame_id;
00043 tf.stamp_ = header.stamp;
00044 if (!g_child_frame_id.empty()) child_frame_id = g_child_frame_id;
00045 if (child_frame_id.empty()) child_frame_id = "base_link";
00046
00047 tf::Quaternion orientation;
00048 tf::quaternionMsgToTF(pose.orientation, orientation);
00049 tfScalar yaw, pitch, roll;
00050 tf::Matrix3x3(orientation).getEulerYPR(yaw, pitch, roll);
00051 tf::Point position;
00052 tf::pointMsgToTF(pose.position, position);
00053
00054
00055 if( !g_position_frame_id.empty() && child_frame_id != g_position_frame_id) {
00056 tf.child_frame_id_ = g_position_frame_id;
00057 tf.setOrigin(tf::Vector3(position.x(), position.y(), position.z() ));
00058 tf.setRotation(tf::Quaternion(0.0, 0.0, 0.0, 1.0));
00059 addTransform(transforms, tf);
00060 }
00061
00062
00063 if (!g_footprint_frame_id.empty() && child_frame_id != g_footprint_frame_id) {
00064 tf.child_frame_id_ = g_footprint_frame_id;
00065 tf.setOrigin(tf::Vector3(position.x(), position.y(), 0.0));
00066 tf.setRotation(tf::createQuaternionFromRPY(0.0, 0.0, yaw));
00067 addTransform(transforms, tf);
00068
00069 yaw = 0.0;
00070 position.setX(0.0);
00071 position.setY(0.0);
00072 tf.frame_id_ = g_footprint_frame_id;
00073 }
00074
00075
00076 if (!g_footprint_frame_id.empty() && child_frame_id != g_stabilized_frame_id) {
00077 tf.child_frame_id_ = g_stabilized_frame_id;
00078 tf.setOrigin(tf::Vector3(0.0, 0.0, position.z()));
00079 tf.setBasis(tf::Matrix3x3::getIdentity());
00080 addTransform(transforms, tf);
00081
00082 position.setZ(0.0);
00083 tf.frame_id_ = g_stabilized_frame_id;
00084 }
00085
00086
00087 tf.child_frame_id_ = child_frame_id;
00088 tf.setOrigin(position);
00089 tf.setRotation(tf::createQuaternionFromRPY(roll, pitch, yaw));
00090 addTransform(transforms, tf);
00091
00092 g_transform_broadcaster->sendTransform(transforms);
00093
00094
00095 if (g_pose_publisher) {
00096 geometry_msgs::PoseStamped pose_stamped;
00097 pose_stamped.pose = pose;
00098 pose_stamped.header = header;
00099 g_pose_publisher.publish(pose_stamped);
00100 }
00101
00102
00103 if (g_euler_publisher) {
00104 geometry_msgs::Vector3Stamped euler_stamped;
00105 euler_stamped.vector.x = roll;
00106 euler_stamped.vector.y = pitch;
00107 euler_stamped.vector.z = yaw;
00108 euler_stamped.header = header;
00109 g_euler_publisher.publish(euler_stamped);
00110 }
00111 }
00112
00113 void odomCallback(nav_msgs::Odometry const &odometry) {
00114 sendTransform(odometry.pose.pose, odometry.header, odometry.child_frame_id);
00115 }
00116
00117 void poseCallback(geometry_msgs::PoseStamped const &pose) {
00118 sendTransform(pose.pose, pose.header);
00119 }
00120
00121 void imuCallback(sensor_msgs::Imu const &imu) {
00122 std::vector<geometry_msgs::TransformStamped> transforms;
00123 std::string child_frame_id;
00124
00125 tf::StampedTransform tf;
00126 tf.frame_id_ = g_stabilized_frame_id;
00127 tf.stamp_ = imu.header.stamp;
00128 if (!g_child_frame_id.empty()) child_frame_id = g_child_frame_id;
00129 if (child_frame_id.empty()) child_frame_id = "base_link";
00130
00131 tf::Quaternion orientation;
00132 tf::quaternionMsgToTF(imu.orientation, orientation);
00133 tfScalar yaw, pitch, roll;
00134 tf::Matrix3x3(orientation).getEulerYPR(yaw, pitch, roll);
00135
00136
00137 tf.child_frame_id_ = child_frame_id;
00138 tf.setRotation(tf::createQuaternionFromRPY(roll, pitch, 0.0));
00139 addTransform(transforms, tf);
00140
00141 g_transform_broadcaster->sendTransform(transforms);
00142
00143
00144 if (g_pose_publisher) {
00145 geometry_msgs::PoseStamped pose_stamped;
00146 pose_stamped.header.stamp = imu.header.stamp;
00147 pose_stamped.header.frame_id = g_stabilized_frame_id;
00148 tf::quaternionTFToMsg(tf.getRotation(), pose_stamped.pose.orientation);
00149 g_pose_publisher.publish(pose_stamped);
00150 }
00151 }
00152
00153 void multiCallback(topic_tools::ShapeShifter const &input) {
00154 if (input.getDataType() == "nav_msgs/Odometry") {
00155 nav_msgs::Odometry::ConstPtr odom = input.instantiate<nav_msgs::Odometry>();
00156 odomCallback(*odom);
00157 return;
00158 }
00159
00160 if (input.getDataType() == "geometry_msgs/PoseStamped") {
00161 geometry_msgs::PoseStamped::ConstPtr pose = input.instantiate<geometry_msgs::PoseStamped>();
00162 poseCallback(*pose);
00163 return;
00164 }
00165
00166 if (input.getDataType() == "sensor_msgs/Imu") {
00167 sensor_msgs::Imu::ConstPtr imu = input.instantiate<sensor_msgs::Imu>();
00168 imuCallback(*imu);
00169 return;
00170 }
00171
00172 ROS_ERROR_THROTTLE(1.0, "message_to_tf received a %s message. Supported message types: nav_msgs/Odometry geometry_msgs/PoseStamped sensor_msgs/Imu", input.getDataType().c_str());
00173 }
00174
00175 int main(int argc, char** argv) {
00176 ros::init(argc, argv, "message_to_tf");
00177
00178 g_footprint_frame_id = "base_footprint";
00179 g_stabilized_frame_id = "base_stabilized";
00180
00181
00182 ros::NodeHandle priv_nh("~");
00183 priv_nh.getParam("odometry_topic", g_odometry_topic);
00184 priv_nh.getParam("pose_topic", g_pose_topic);
00185 priv_nh.getParam("imu_topic", g_imu_topic);
00186 priv_nh.getParam("topic", g_topic);
00187 priv_nh.getParam("frame_id", g_frame_id);
00188 priv_nh.getParam("footprint_frame_id", g_footprint_frame_id);
00189 priv_nh.getParam("position_frame_id", g_position_frame_id);
00190 priv_nh.getParam("stabilized_frame_id", g_stabilized_frame_id);
00191 priv_nh.getParam("child_frame_id", g_child_frame_id);
00192
00193 g_transform_broadcaster = new tf::TransformBroadcaster;
00194
00195 ros::NodeHandle node;
00196 ros::Subscriber sub1, sub2, sub3, sub4;
00197 if (!g_odometry_topic.empty()) sub1 = node.subscribe(g_odometry_topic, 10, &odomCallback);
00198 if (!g_pose_topic.empty()) sub2 = node.subscribe(g_pose_topic, 10, &poseCallback);
00199 if (!g_imu_topic.empty()) sub3 = node.subscribe(g_imu_topic, 10, &imuCallback);
00200 if (!g_topic.empty()) sub4 = node.subscribe(g_topic, 10, &multiCallback);
00201
00202 if (!sub1 && !sub2 && !sub3 && !sub4) {
00203 ROS_FATAL("Params odometry_topic, pose_topic, imu_topic and topic are empty... nothing to do for me!");
00204 return 1;
00205 }
00206
00207 bool publish_pose = true;
00208 priv_nh.getParam("publish_pose", publish_pose);
00209 if (publish_pose) {
00210 std::string publish_pose_topic;
00211 priv_nh.getParam("publish_pose_topic", publish_pose_topic);
00212
00213 if (!publish_pose_topic.empty())
00214 g_pose_publisher = node.advertise<geometry_msgs::PoseStamped>(publish_pose_topic, 10);
00215 else
00216 g_pose_publisher = priv_nh.advertise<geometry_msgs::PoseStamped>("pose", 10);
00217 }
00218
00219 bool publish_euler = true;
00220 priv_nh.getParam("publish_euler", publish_euler);
00221 if (publish_euler) {
00222 std::string publish_euler_topic;
00223 priv_nh.getParam("publish_euler_topic", publish_euler_topic);
00224
00225 if (!publish_euler_topic.empty())
00226 g_euler_publisher = node.advertise<geometry_msgs::Vector3Stamped>(publish_euler_topic, 10);
00227 else
00228 g_euler_publisher = priv_nh.advertise<geometry_msgs::Vector3Stamped>("euler", 10);
00229 }
00230
00231 ros::spin();
00232 delete g_transform_broadcaster;
00233 return 0;
00234 }