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


message_to_tf
Author(s): Johannes Meyer
autogenerated on Mon Oct 6 2014 00:24:11