Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023 #include "robot_state_publisher/treefksolverposfull_recursive.hpp"
00024 #include <ros/ros.h>
00025 #include <iostream>
00026 #include <cstdio>
00027
00028 using namespace std;
00029
00030 namespace KDL {
00031
00032 TreeFkSolverPosFull_recursive::TreeFkSolverPosFull_recursive(const Tree& _tree):
00033 tree(_tree)
00034 {
00035 }
00036
00037 TreeFkSolverPosFull_recursive::~TreeFkSolverPosFull_recursive()
00038 {
00039 }
00040
00041
00042 int TreeFkSolverPosFull_recursive::JntToCart(const map<string, double>& q_in, map<string, tf::Stamped<Frame> >& p_out, bool flatten_tree)
00043 {
00044
00045 p_out.clear();
00046
00047 addFrameToMap(q_in, p_out, tf::Stamped<KDL::Frame>(KDL::Frame::Identity(), ros::Time(), tree.getRootSegment()->second.segment.getName()), tree.getRootSegment(), flatten_tree);
00048
00049 return 0;
00050 }
00051
00052
00053
00054 void TreeFkSolverPosFull_recursive::addFrameToMap(const map<string, double>& q_in,
00055 map<string, tf::Stamped<Frame> >& p_out,
00056 const tf::Stamped<KDL::Frame>& previous_frame,
00057 const SegmentMap::const_iterator this_segment,
00058 bool flatten_tree)
00059 {
00060
00061 tf::Stamped<KDL::Frame> this_frame;
00062 double jnt_p = 0;
00063 if (this_segment->second.segment.getJoint().getType() != Joint::None){
00064 map<string, double>::const_iterator jnt_pos = q_in.find(this_segment->second.segment.getJoint().getName());
00065 if (jnt_pos == q_in.end()){
00066 ROS_DEBUG("Warning: TreeFKSolverPosFull Could not find value for joint '%s'. Skipping this tree branch", this_segment->first.c_str());
00067 return;
00068 }
00069 jnt_p = jnt_pos->second;
00070 }
00071 this_frame = tf::Stamped<KDL::Frame>(previous_frame * this_segment->second.segment.pose(jnt_p), ros::Time(), previous_frame.frame_id_);
00072
00073 if (this_segment->first != tree.getRootSegment()->first)
00074 p_out.insert(make_pair(this_segment->first, tf::Stamped<KDL::Frame>(this_frame, ros::Time(), previous_frame.frame_id_)));
00075
00076
00077 for (vector<SegmentMap::const_iterator>::const_iterator child=this_segment->second.children.begin(); child !=this_segment->second.children.end(); child++){
00078 if (flatten_tree)
00079 addFrameToMap(q_in, p_out, this_frame, *child, flatten_tree);
00080 else
00081 addFrameToMap(q_in, p_out, tf::Stamped<KDL::Frame>(KDL::Frame::Identity(), ros::Time(), this_segment->first), *child, flatten_tree);
00082 }
00083 }
00084
00085 }