attached_body.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
39 
40 moveit::core::AttachedBody::AttachedBody(const LinkModel* parent_link_model, const std::string& id,
41  const std::vector<shapes::ShapeConstPtr>& shapes,
42  const EigenSTL::vector_Affine3d& attach_trans,
43  const std::set<std::string>& touch_links,
44  const trajectory_msgs::JointTrajectory& detach_posture)
45  : parent_link_model_(parent_link_model)
46  , id_(id)
47  , shapes_(shapes)
48  , attach_trans_(attach_trans)
49  , touch_links_(touch_links)
50  , detach_posture_(detach_posture)
51 {
52  global_collision_body_transforms_.resize(attach_trans.size());
53  for (std::size_t i = 0; i < global_collision_body_transforms_.size(); ++i)
54  global_collision_body_transforms_[i].setIdentity();
55 }
56 
58 
60 {
61  for (std::size_t i = 0; i < shapes_.size(); ++i)
62  {
63  // if this shape is only owned here (and because this is a non-const function), we can safely const-cast:
64  if (shapes_[i].unique())
65  const_cast<shapes::Shape*>(shapes_[i].get())->scale(scale);
66  else
67  {
68  // if the shape is owned elsewhere, we make a copy:
69  shapes::Shape* copy = shapes_[i]->clone();
70  copy->scale(scale);
71  shapes_[i].reset(copy);
72  }
73  }
74 }
75 
77 {
78  for (std::size_t i = 0; i < shapes_.size(); ++i)
79  {
80  // if this shape is only owned here (and because this is a non-const function), we can safely const-cast:
81  if (shapes_[i].unique())
82  const_cast<shapes::Shape*>(shapes_[i].get())->padd(padding);
83  else
84  {
85  // if the shape is owned elsewhere, we make a copy:
86  shapes::Shape* copy = shapes_[i]->clone();
87  copy->padd(padding);
88  shapes_[i].reset(copy);
89  }
90  }
91 }
void scale(double scale)
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
std::vector< shapes::ShapeConstPtr > shapes_
The geometries of the attached body.
void padd(double padding)
EigenSTL::vector_Affine3d global_collision_body_transforms_
The global transforms for these attached bodies (computed by forward kinematics)
AttachedBody(const LinkModel *link, const std::string &id, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Affine3d &attach_trans, const std::set< std::string > &touch_links, const trajectory_msgs::JointTrajectory &attach_posture)
Construct an attached body for a specified link. The name of this body is id and it consists of shape...
A link from the robot. Contains the constant transform applied to the link and its geometry...
Definition: link_model.h:72
void setScale(double scale)
Set the scale for the shapes of this attached object.
void setPadding(double padding)
Set the padding for the shapes of this attached object.


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Oct 18 2020 13:16:33