link_model.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, 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 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/robot_model/link_model.h>
00038 #include <moveit/robot_model/joint_model.h>
00039 #include <geometric_shapes/shape_operations.h>
00040 
00041 moveit::core::LinkModel::LinkModel(const std::string& name)
00042   : name_(name)
00043   , parent_joint_model_(NULL)
00044   , parent_link_model_(NULL)
00045   , is_parent_joint_fixed_(false)
00046   , joint_origin_transform_is_identity_(true)
00047   , first_collision_body_transform_index_(-1)
00048   , link_index_(-1)
00049 {
00050   joint_origin_transform_.setIdentity();
00051 }
00052 
00053 moveit::core::LinkModel::~LinkModel()
00054 {
00055 }
00056 
00057 void moveit::core::LinkModel::setJointOriginTransform(const Eigen::Affine3d& transform)
00058 {
00059   joint_origin_transform_ = transform;
00060   joint_origin_transform_is_identity_ =
00061       joint_origin_transform_.rotation().isIdentity() &&
00062       joint_origin_transform_.translation().norm() < std::numeric_limits<double>::epsilon();
00063 }
00064 
00065 void moveit::core::LinkModel::setParentJointModel(const JointModel* joint)
00066 {
00067   parent_joint_model_ = joint;
00068   is_parent_joint_fixed_ = joint->getType() == JointModel::FIXED;
00069 }
00070 
00071 void moveit::core::LinkModel::setGeometry(const std::vector<shapes::ShapeConstPtr>& shapes,
00072                                           const EigenSTL::vector_Affine3d& origins)
00073 {
00074   shapes_ = shapes;
00075   collision_origin_transform_ = origins;
00076   collision_origin_transform_is_identity_.resize(collision_origin_transform_.size());
00077 
00078   Eigen::Vector3d a = Eigen::Vector3d(0.0, 0.0, 0.0);
00079   Eigen::Vector3d b = Eigen::Vector3d(0.0, 0.0, 0.0);
00080 
00081   for (std::size_t i = 0; i < shapes_.size(); ++i)
00082   {
00083     collision_origin_transform_is_identity_[i] =
00084         (collision_origin_transform_[i].rotation().isIdentity() &&
00085          collision_origin_transform_[i].translation().norm() < std::numeric_limits<double>::epsilon()) ?
00086             1 :
00087             0;
00088     Eigen::Vector3d ei = shapes::computeShapeExtents(shapes_[i].get());
00089     Eigen::Vector3d p1 = collision_origin_transform_[i] * (-ei / 2.0);
00090     Eigen::Vector3d p2 = collision_origin_transform_[i] * (-p1);
00091 
00092     if (i == 0)
00093     {
00094       a = p1;
00095       b = p2;
00096     }
00097     else
00098     {
00099       for (int i = 0; i < 3; ++i)
00100         a[i] = std::min(a[i], p1[i]);
00101       for (int i = 0; i < 3; ++i)
00102         b[i] = std::max(b[i], p2[i]);
00103     }
00104   }
00105 
00106   shape_extents_ = b - a;
00107 }
00108 
00109 void moveit::core::LinkModel::setVisualMesh(const std::string& visual_mesh, const Eigen::Affine3d& origin,
00110                                             const Eigen::Vector3d& scale)
00111 {
00112   visual_mesh_filename_ = visual_mesh;
00113   visual_mesh_origin_ = origin;
00114   visual_mesh_scale_ = scale;
00115 }


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Jul 24 2017 02:20:44