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 <iostream>
00024 #include <cstdio>
00025
00026 #include <ros/ros.h>
00027
00028 #include "robot_state_publisher/treefksolverposfull_recursive.hpp"
00029
00030 using namespace std;
00031
00032 namespace KDL {
00033
00034 TreeFkSolverPosFull_recursive::TreeFkSolverPosFull_recursive(const Tree& _tree):
00035 tree(_tree)
00036 {
00037 }
00038
00039 TreeFkSolverPosFull_recursive::~TreeFkSolverPosFull_recursive()
00040 {
00041 }
00042
00043
00044 int TreeFkSolverPosFull_recursive::JntToCart(const map<string, double>& q_in, map<string, tf2::Stamped<Frame> >& p_out, bool flatten_tree)
00045 {
00046
00047 p_out.clear();
00048
00049 addFrameToMap(q_in, p_out, tf2::Stamped<KDL::Frame>(KDL::Frame::Identity(), ros::Time(),
00050 GetTreeElementSegment(tree.getRootSegment()->second).getName()),
00051 tree.getRootSegment(), flatten_tree);
00052
00053 return 0;
00054 }
00055
00056
00057 void TreeFkSolverPosFull_recursive::addFrameToMap(const map<string, double>& q_in,
00058 map<string, tf2::Stamped<Frame> >& p_out,
00059 const tf2::Stamped<KDL::Frame>& previous_frame,
00060 const SegmentMap::const_iterator this_segment,
00061 bool flatten_tree)
00062 {
00063
00064 tf2::Stamped<KDL::Frame> this_frame;
00065 double jnt_p = 0;
00066 if (GetTreeElementSegment(this_segment->second).getJoint().getType() != Joint::None) {
00067 map<string, double>::const_iterator jnt_pos = q_in.find(GetTreeElementSegment(this_segment->second).getJoint().getName());
00068 if (jnt_pos == q_in.end()) {
00069 ROS_DEBUG("Warning: TreeFKSolverPosFull Could not find value for joint '%s'. Skipping this tree branch", this_segment->first.c_str());
00070 return;
00071 }
00072 jnt_p = jnt_pos->second;
00073 }
00074 this_frame = tf2::Stamped<KDL::Frame>(previous_frame * GetTreeElementSegment(this_segment->second).pose(jnt_p), ros::Time(), previous_frame.frame_id_);
00075
00076 if (this_segment->first != tree.getRootSegment()->first) {
00077 p_out.insert(make_pair(this_segment->first, tf2::Stamped<KDL::Frame>(this_frame, ros::Time(), previous_frame.frame_id_)));
00078 }
00079
00080
00081 for (vector<SegmentMap::const_iterator>::const_iterator child = GetTreeElementChildren(this_segment->second).begin();
00082 child != GetTreeElementChildren(this_segment->second).end(); child++) {
00083 if (flatten_tree) {
00084 addFrameToMap(q_in, p_out, this_frame, *child, flatten_tree);
00085 }
00086 else {
00087 addFrameToMap(q_in, p_out, tf2::Stamped<KDL::Frame>(KDL::Frame::Identity(), ros::Time(), this_segment->first), *child, flatten_tree);
00088 }
00089 }
00090 }
00091
00092 }