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(), GetTreeElementSegment(tree.getRootSegment()->second).getName()),
00048 tree.getRootSegment(), flatten_tree);
00049
00050 return 0;
00051 }
00052
00053
00054
00055 void TreeFkSolverPosFull_recursive::addFrameToMap(const map<string, double>& q_in,
00056 map<string, tf::Stamped<Frame> >& p_out,
00057 const tf::Stamped<KDL::Frame>& previous_frame,
00058 const SegmentMap::const_iterator this_segment,
00059 bool flatten_tree)
00060 {
00061
00062 tf::Stamped<KDL::Frame> this_frame;
00063 double jnt_p = 0;
00064 if (GetTreeElementSegment(this_segment->second).getJoint().getType() != Joint::None){
00065 map<string, double>::const_iterator jnt_pos = q_in.find(GetTreeElementSegment(this_segment->second).getJoint().getName());
00066 if (jnt_pos == q_in.end()){
00067 ROS_DEBUG("Warning: TreeFKSolverPosFull Could not find value for joint '%s'. Skipping this tree branch", this_segment->first.c_str());
00068 return;
00069 }
00070 jnt_p = jnt_pos->second;
00071 }
00072 this_frame = tf::Stamped<KDL::Frame>(previous_frame * GetTreeElementSegment(this_segment->second).pose(jnt_p), ros::Time(), previous_frame.frame_id_);
00073
00074 if (this_segment->first != tree.getRootSegment()->first)
00075 p_out.insert(make_pair(this_segment->first, tf::Stamped<KDL::Frame>(this_frame, ros::Time(), previous_frame.frame_id_)));
00076
00077
00078 for (vector<SegmentMap::const_iterator>::const_iterator child = GetTreeElementChildren(this_segment->second).begin();
00079 child != GetTreeElementChildren(this_segment->second).end(); child++){
00080 if (flatten_tree)
00081 addFrameToMap(q_in, p_out, this_frame, *child, flatten_tree);
00082 else
00083 addFrameToMap(q_in, p_out, tf::Stamped<KDL::Frame>(KDL::Frame::Identity(), ros::Time(), this_segment->first), *child, flatten_tree);
00084 }
00085 }
00086
00087 }