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
00031
00032
00033
00034
00035
00036
00037 #include "robot_state_publisher/robot_state_publisher.h"
00038 #include <kdl/frames_io.hpp>
00039 #include <tf_conversions/tf_kdl.h>
00040
00041 using namespace std;
00042 using namespace ros;
00043 using namespace KDL;
00044
00045
00046
00047 namespace robot_state_publisher{
00048
00049 RobotStatePublisher::RobotStatePublisher(const Tree& tree)
00050 :tree_(tree)
00051 {
00052
00053 solver_.reset(new TreeFkSolverPosFull_recursive(tree_));
00054
00055
00056 ros::NodeHandle n_private("~");
00057 n_private.param("flatten_tree", flatten_tree_, false);
00058
00059
00060 NodeHandle n;
00061 tf_publisher_ = n.advertise<tf::tfMessage>("/tf", 5);
00062
00063
00064 SegmentMap::const_iterator root = tree.getRootSegment();
00065 root_ = root->first;
00066 }
00067
00068
00069
00070 bool RobotStatePublisher::publishTransforms(const map<string, double>& joint_positions, const Time& time)
00071 {
00072
00073 map<string, tf::Stamped<Frame> > link_poses;
00074 solver_->JntToCart(joint_positions, link_poses, flatten_tree_);
00075
00076 if (link_poses.empty()){
00077 ROS_ERROR("Could not compute link poses. The tree or the state is invalid.");
00078 return false;
00079 }
00080 transforms_.resize(link_poses.size());
00081
00082 unsigned int i = 0;
00083 tf::Transform tf_frame;
00084 for (map<string, tf::Stamped<Frame> >::const_iterator f=link_poses.begin(); f!=link_poses.end(); f++){
00085 tf::TransformKDLToTF(f->second, transforms_[i]);
00086 transforms_[i].stamp_ = time;
00087 transforms_[i].frame_id_ = f->second.frame_id_;
00088 transforms_[i].child_frame_id_ = f->first;
00089 i++;
00090 }
00091
00092 tf_broadcaster_.sendTransform(transforms_);
00093
00094 return true;
00095 }
00096 }
00097
00098
00099