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


message_to_tf
Author(s): Johannes Meyer
autogenerated on Fri Aug 28 2015 10:59:51