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