treefksolverjointposaxis.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00037 #include <collision_proximity_planner/treefksolverjointposaxis.hpp>
00038 #include <iostream>
00039 
00040 using namespace std;
00041 
00042 namespace KDL {
00043 
00044 TreeFkSolverJointPosAxis::TreeFkSolverJointPosAxis(const Tree& tree, const std::string& reference_frame):
00045   tree_(tree),
00046   reference_frame_(reference_frame)
00047 {
00048   segment_names_.clear();
00049   assignSegmentNumber(tree_.getRootSegment());
00050   std::map<std::string, int>::iterator reference_frame_it = segment_name_to_index_.find(reference_frame);
00051   if (reference_frame_it == segment_name_to_index_.end())
00052   {
00053     cout << "TreeFkSolverJointPosAxis: Reference frame " << reference_frame << " could not be found! Forward kinematics will be performed in world frame.";
00054   }
00055   else
00056   {
00057     reference_frame_index_ = reference_frame_it->second;
00058   }
00059   num_segments_ = segment_names_.size();
00060   num_joints_ = tree_.getNrOfJoints();
00061 }
00062 
00063 TreeFkSolverJointPosAxis::~TreeFkSolverJointPosAxis()
00064 {
00065 }
00066 
00067 int TreeFkSolverJointPosAxis::JntToCart(const JntArray& q_in, std::vector<Vector>& joint_pos, std::vector<Vector>& joint_axis, std::vector<Frame>& segment_frames) const
00068 {
00069   joint_pos.resize(num_joints_);
00070   joint_axis.resize(num_joints_);
00071   segment_frames.resize(num_segments_);
00072 
00073   // start the recursion
00074   treeRecursiveFK(q_in, joint_pos, joint_axis, segment_frames, Frame::Identity(), tree_.getRootSegment(), 0);
00075 
00076   // get the inverse reference frame:
00077   Frame inv_ref_frame = segment_frames[reference_frame_index_].Inverse();
00078 
00079   // convert all the frames into the reference frame:
00080   for (int i=0; i<num_segments_; i++)
00081   {
00082     segment_frames[i] = inv_ref_frame * segment_frames[i];
00083   }
00084 
00085   // convert all joint positions and axes into reference frame:
00086   for (int i=0; i<num_joints_; i++)
00087   {
00088     joint_axis[i] = inv_ref_frame * joint_axis[i];
00089     joint_pos[i] = inv_ref_frame * joint_pos[i];
00090   }
00091 
00092   return 0;
00093 }
00094 
00095 int TreeFkSolverJointPosAxis::treeRecursiveFK(const JntArray& q_in, std::vector<Vector>& joint_pos, std::vector<Vector>& joint_axis, std::vector<Frame>& segment_frames,
00096     const Frame& previous_frame, const SegmentMap::const_iterator this_segment, int segment_nr) const
00097 {
00098   Frame this_frame = previous_frame;
00099 
00100   // get the joint angle:
00101   double jnt_p = 0;
00102   if (this_segment->second.segment.getJoint().getType() != Joint::None)
00103   {
00104     int q_nr = this_segment->second.q_nr;
00105     jnt_p = q_in(q_nr);
00106     joint_pos[q_nr] = this_frame * this_segment->second.segment.getJoint().JointOrigin();
00107     joint_axis[q_nr] = this_frame.M * this_segment->second.segment.getJoint().JointAxis();
00108   }
00109 
00110   // do the FK:
00111   this_frame = this_frame * this_segment->second.segment.pose(jnt_p);
00112   segment_frames[segment_nr] = this_frame;
00113   segment_nr++;
00114 
00115   // get poses of child segments
00116   for (vector<SegmentMap::const_iterator>::const_iterator child=this_segment->second.children.begin(); child !=this_segment->second.children.end(); child++)
00117     segment_nr = treeRecursiveFK(q_in, joint_pos, joint_axis, segment_frames, this_frame, *child, segment_nr);
00118   return segment_nr;
00119 }
00120 
00121 void TreeFkSolverJointPosAxis::assignSegmentNumber(const SegmentMap::const_iterator this_segment)
00122 {
00123   int num = segment_names_.size();
00124   segment_names_.push_back(this_segment->first);
00125   segment_name_to_index_[this_segment->first] = num;
00126 
00127   // add the child segments recursively
00128   for (vector<SegmentMap::const_iterator>::const_iterator child=this_segment->second.children.begin(); child !=this_segment->second.children.end(); child++)
00129   {
00130     assignSegmentNumber(*child);
00131   }
00132 }
00133 
00134 const std::vector<std::string> TreeFkSolverJointPosAxis::getSegmentNames() const
00135 {
00136   return segment_names_;
00137 }
00138 
00139 const std::map<std::string, int> TreeFkSolverJointPosAxis::getSegmentNameToIndex() const
00140 {
00141   return segment_name_to_index_;
00142 }
00143 
00144 int TreeFkSolverJointPosAxis::segmentNameToIndex(std::string name) const
00145 {
00146   return segment_name_to_index_.find(name)->second;
00147 }
00148 
00149 } // namespace KDL


collision_proximity_planner
Author(s): Sachin Chitta
autogenerated on Thu Dec 12 2013 11:09:38