treefksolverjointposaxis_partial.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_partial.hpp>
00038 #include <iostream>
00039 
00040 using namespace std;
00041 
00042 namespace KDL {
00043 
00044 TreeFkSolverJointPosAxisPartial::TreeFkSolverJointPosAxisPartial(const Tree& tree, const std::string& reference_frame, const std::vector<bool>& active_joints):
00045   tree_(tree),
00046   reference_frame_(reference_frame),
00047   active_joints_(active_joints)
00048 {
00049   segment_names_.clear();
00050   assignSegmentNumber(tree_.getRootSegment());
00051   std::map<std::string, int>::iterator reference_frame_it = segment_name_to_index_.find(reference_frame);
00052   if (reference_frame_it == segment_name_to_index_.end())
00053   {
00054     cout << "TreeFkSolverJointPosAxisPartial: Reference frame " << reference_frame << " could not be found! Forward kinematics will be performed in world frame.";
00055   }
00056   else
00057   {
00058     reference_frame_index_ = reference_frame_it->second;
00059   }
00060   num_segments_ = segment_names_.size();
00061   num_joints_ = tree_.getNrOfJoints();
00062   segment_frames_.resize(num_segments_);
00063   segment_parent_frame_nr_.resize(num_segments_);
00064   segment_parent_.resize(num_segments_, NULL);
00065   joint_parent_frame_nr_.resize(num_joints_);
00066   joint_parent_.resize(num_joints_, NULL);
00067   segment_evaluation_order_.clear();
00068   joint_calc_pos_axis_.clear();
00069   joint_calc_pos_axis_.resize(num_joints_, false);
00070 }
00071 
00072 TreeFkSolverJointPosAxisPartial::~TreeFkSolverJointPosAxisPartial()
00073 {
00074 }
00075 
00076 int TreeFkSolverJointPosAxisPartial::JntToCartFull(const JntArray& q_in, std::vector<Vector>& joint_pos, std::vector<Vector>& joint_axis, std::vector<Frame>& segment_frames)
00077 {
00078   joint_pos.resize(num_joints_);
00079   joint_axis.resize(num_joints_);
00080   segment_frames.resize(num_segments_);
00081 
00082   segment_evaluation_order_.clear();
00083 
00084   // start the recursion
00085   treeRecursiveFK(q_in, joint_pos, joint_axis, segment_frames, Frame::Identity(), tree_.getRootSegment(), 0, -1, false);
00086 
00087   // get the inverse reference frame:
00088   Frame inv_ref_frame = segment_frames[reference_frame_index_].Inverse();
00089 
00090   // convert all the frames into the reference frame:
00091   for (int i=0; i<num_segments_; i++)
00092   {
00093     segment_frames[i] = inv_ref_frame * segment_frames[i];
00094   }
00095 
00096   // convert all joint positions and axes into reference frame:
00097   for (int i=0; i<num_joints_; i++)
00098   {
00099     joint_axis[i] = inv_ref_frame * joint_axis[i];
00100     joint_pos[i] = inv_ref_frame * joint_pos[i];
00101   }
00102 
00103   segment_frames_ = segment_frames;
00104 
00105   return 0;
00106 }
00107 
00108 int TreeFkSolverJointPosAxisPartial::JntToCartPartial(const JntArray& q_in, std::vector<Vector>& joint_pos, std::vector<Vector>& joint_axis, std::vector<Frame>& segment_frames) const
00109 {
00110   joint_pos.resize(num_joints_);
00111   joint_axis.resize(num_joints_);
00112   segment_frames.resize(num_segments_);
00113 
00114   // first solve for all segments
00115   for (size_t i=0; i<segment_evaluation_order_.size(); ++i)
00116   {
00117     int segment_nr = segment_evaluation_order_[i];
00118     const TreeElement* parent_segment = segment_parent_[segment_nr];
00119     double jnt_p = 0;
00120     if (parent_segment->segment.getJoint().getType() != Joint::None)
00121     {
00122       jnt_p = q_in(parent_segment->q_nr);
00123     }
00124 
00125     segment_frames[segment_nr] =  segment_frames[segment_parent_frame_nr_[segment_nr]] * parent_segment->segment.pose(jnt_p);
00126   }
00127 
00128   // now solve for joint positions and axes:
00129   for (int i=0; i<num_joints_; ++i)
00130   {
00131     if (joint_calc_pos_axis_[i])
00132     {
00133       Frame& frame = segment_frames[joint_parent_frame_nr_[i]];
00134       const TreeElement* parent_segment = joint_parent_[i];
00135       joint_pos[i] = frame * parent_segment->segment.getJoint().JointOrigin();
00136       joint_axis[i] = frame.M * parent_segment->segment.getJoint().JointAxis();
00137     }
00138   }
00139   return 0;
00140 }
00141 
00142 int TreeFkSolverJointPosAxisPartial::treeRecursiveFK(const JntArray& q_in, std::vector<Vector>& joint_pos, std::vector<Vector>& joint_axis, std::vector<Frame>& segment_frames,
00143     const Frame& previous_frame, const SegmentMap::const_iterator this_segment, int segment_nr, int parent_segment_nr, bool active)
00144 {
00145   Frame this_frame = previous_frame;
00146 
00147   // get the joint angle:
00148   double jnt_p = 0;
00149   if (this_segment->second.segment.getJoint().getType() != Joint::None)
00150   {
00151     int q_nr = this_segment->second.q_nr;
00152     jnt_p = q_in(q_nr);
00153     joint_parent_frame_nr_[q_nr] = parent_segment_nr;
00154     joint_parent_[q_nr] = &(this_segment->second);
00155     joint_pos[q_nr] = this_frame * this_segment->second.segment.getJoint().JointOrigin();
00156     joint_axis[q_nr] = this_frame.M * this_segment->second.segment.getJoint().JointAxis();
00157     if (active && active_joints_[q_nr])
00158       joint_calc_pos_axis_[q_nr] = true;
00159     if (active_joints_[q_nr])
00160       active = true;
00161   }
00162 
00163   // do the FK:
00164   if (active)
00165     segment_evaluation_order_.push_back(segment_nr);
00166   segment_parent_frame_nr_[segment_nr] = parent_segment_nr;
00167   segment_parent_[segment_nr] = &(this_segment->second);
00168   this_frame = this_frame * this_segment->second.segment.pose(jnt_p);
00169   segment_frames[segment_nr] = this_frame;
00170 
00171   int par_seg_nr = segment_nr;
00172   segment_nr++;
00173 
00174   // get poses of child segments
00175   for (vector<SegmentMap::const_iterator>::const_iterator child=this_segment->second.children.begin(); child !=this_segment->second.children.end(); child++)
00176     segment_nr = treeRecursiveFK(q_in, joint_pos, joint_axis, segment_frames, this_frame, *child, segment_nr, par_seg_nr, active);
00177   return segment_nr;
00178 }
00179 
00180 void TreeFkSolverJointPosAxisPartial::assignSegmentNumber(const SegmentMap::const_iterator this_segment)
00181 {
00182   int num = segment_names_.size();
00183   segment_names_.push_back(this_segment->first);
00184   segment_name_to_index_[this_segment->first] = num;
00185 
00186   // add the child segments recursively
00187   for (vector<SegmentMap::const_iterator>::const_iterator child=this_segment->second.children.begin(); child !=this_segment->second.children.end(); child++)
00188   {
00189     assignSegmentNumber(*child);
00190   }
00191 }
00192 
00193 const std::vector<std::string> TreeFkSolverJointPosAxisPartial::getSegmentNames() const
00194 {
00195   return segment_names_;
00196 }
00197 
00198 const std::map<std::string, int> TreeFkSolverJointPosAxisPartial::getSegmentNameToIndex() const
00199 {
00200   return segment_name_to_index_;
00201 }
00202 
00203 int TreeFkSolverJointPosAxisPartial::segmentNameToIndex(std::string name) const
00204 {
00205   return segment_name_to_index_.find(name)->second;
00206 }
00207 
00208 } // namespace KDL
00209 


collision_proximity_planner
Author(s): Sachin Chitta
autogenerated on Fri Dec 6 2013 21:13:39