00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <ros/ros.h>
00031
00032 #include <tf2/utils.h>
00033 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
00034 #include <tf2_ros/transform_broadcaster.h>
00035 #include <tf2_ros/transform_listener.h>
00036
00037 #include <string>
00038
00039 #include <track_odometry/tf_projection.h>
00040
00041 class TfProjectionNode
00042 {
00043 private:
00044 ros::NodeHandle nh_;
00045 ros::NodeHandle pnh_;
00046 tf2_ros::Buffer tf_buffer_;
00047 tf2_ros::TransformListener tf_listener_;
00048 tf2_ros::TransformBroadcaster tf_broadcaster_;
00049
00050 double rate_;
00051 double tf_tolerance_;
00052 bool flat_;
00053 bool project_posture_;
00054
00055 std::string source_frame_;
00056 std::string projection_surface_frame_;
00057 std::string parent_frame_;
00058 std::string projected_frame_;
00059
00060 public:
00061 TfProjectionNode()
00062 : nh_()
00063 , pnh_("~")
00064 , tf_listener_(tf_buffer_)
00065 {
00066 if (pnh_.hasParam("base_link_frame") ||
00067 pnh_.hasParam("projection_frame") ||
00068 pnh_.hasParam("target_frame") ||
00069 pnh_.hasParam("frame"))
00070 {
00071 ROS_ERROR(
00072 "tf_projection parameters \"base_link_frame\", \"projection_frame\", \"target_frame\", and \"frame\" "
00073 "are replaced by \"source_frame\", \"projection_surface_frame\", \"parent_frame\", and \"projected_frame\"");
00074
00075 pnh_.param("base_link_frame", source_frame_, std::string("base_link"));
00076 pnh_.param("projection_frame", projection_surface_frame_, std::string("map"));
00077 pnh_.param("target_frame", parent_frame_, std::string("map"));
00078 pnh_.param("frame", projected_frame_, std::string("base_link_projected"));
00079 }
00080 else
00081 {
00082 pnh_.param("source_frame", source_frame_, std::string("base_link"));
00083 pnh_.param("projection_surface_frame", projection_surface_frame_, std::string("map"));
00084 pnh_.param("parent_frame", parent_frame_, std::string("map"));
00085 pnh_.param("projected_frame", projected_frame_, std::string("base_link_projected"));
00086 }
00087
00088 pnh_.param("hz", rate_, 10.0);
00089 pnh_.param("tf_tolerance", tf_tolerance_, 0.1);
00090 pnh_.param("flat", flat_, false);
00091 pnh_.param("project_posture", project_posture_, false);
00092 }
00093 void process()
00094 {
00095 tf2::Stamped<tf2::Transform> trans;
00096 tf2::Stamped<tf2::Transform> trans_target;
00097 try
00098 {
00099 tf2::fromMsg(
00100 tf_buffer_.lookupTransform(projection_surface_frame_, source_frame_, ros::Time(0), ros::Duration(0.1)),
00101 trans);
00102 tf2::fromMsg(
00103 tf_buffer_.lookupTransform(parent_frame_, projection_surface_frame_, trans.stamp_, ros::Duration(0.1)),
00104 trans_target);
00105 }
00106 catch (tf2::TransformException& e)
00107 {
00108 ROS_WARN_ONCE("%s", e.what());
00109 return;
00110 }
00111
00112 if (project_posture_)
00113 {
00114 const float yaw = tf2::getYaw(trans.getRotation());
00115 trans.setRotation(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), yaw));
00116 }
00117
00118 const tf2::Stamped<tf2::Transform> result(
00119 track_odometry::projectTranslation(trans, trans_target),
00120 trans.stamp_ + ros::Duration(tf_tolerance_),
00121 parent_frame_);
00122
00123 geometry_msgs::TransformStamped trans_out = tf2::toMsg(result);
00124 if (flat_)
00125 {
00126 const float yaw = tf2::getYaw(trans_out.transform.rotation);
00127 trans_out.transform.rotation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), yaw));
00128 }
00129 trans_out.child_frame_id = projected_frame_;
00130
00131 tf_broadcaster_.sendTransform(trans_out);
00132 }
00133 void cbTimer(const ros::TimerEvent& event)
00134 {
00135 process();
00136 }
00137 void spin()
00138 {
00139 ros::Timer timer = nh_.createTimer(
00140 ros::Duration(1.0 / rate_), &TfProjectionNode::cbTimer, this);
00141 ros::spin();
00142 }
00143 };
00144
00145 int main(int argc, char* argv[])
00146 {
00147 ros::init(argc, argv, "tf_projection");
00148
00149 TfProjectionNode proj;
00150 proj.spin();
00151
00152 return 0;
00153 }