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
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/robot_state/attached_body.h>
00038
00039 robot_state::AttachedBody::AttachedBody(const robot_model::LinkModel *parent_link_model,
00040 const std::string &id,
00041 const std::vector<shapes::ShapeConstPtr> &shapes,
00042 const EigenSTL::vector_Affine3d &attach_trans,
00043 const std::set<std::string> &touch_links,
00044 const sensor_msgs::JointState &detach_posture) :
00045 parent_link_model_(parent_link_model),
00046 id_(id),
00047 shapes_(shapes),
00048 attach_trans_(attach_trans),
00049 touch_links_(touch_links),
00050 detach_posture_(detach_posture)
00051 {
00052 global_collision_body_transforms_.resize(attach_trans.size());
00053 for(std::size_t i = 0 ; i < global_collision_body_transforms_.size() ; ++i)
00054 global_collision_body_transforms_[i].setIdentity();
00055 }
00056
00057 robot_state::AttachedBody::~AttachedBody()
00058 {
00059 }
00060
00061 void robot_state::AttachedBody::setScale(double scale)
00062 {
00063 for (std::size_t i = 0 ; i < shapes_.size() ; ++i)
00064 {
00065
00066 if (shapes_[i].unique())
00067 const_cast<shapes::Shape*>(shapes_[i].get())->scale(scale);
00068 else
00069 {
00070
00071 shapes::Shape *copy = shapes_[i]->clone();
00072 copy->scale(scale);
00073 shapes_[i].reset(copy);
00074 }
00075 }
00076 }
00077
00078 void robot_state::AttachedBody::setPadding(double padding)
00079 {
00080 for (std::size_t i = 0 ; i < shapes_.size() ; ++i)
00081 {
00082
00083 if (shapes_[i].unique())
00084 const_cast<shapes::Shape*>(shapes_[i].get())->padd(padding);
00085 else
00086 {
00087
00088 shapes::Shape *copy = shapes_[i]->clone();
00089 copy->padd(padding);
00090 shapes_[i].reset(copy);
00091 }
00092 }
00093 }
00094
00095 void robot_state::AttachedBody::computeTransform(const Eigen::Affine3d &parent_link_global_transform)
00096 {
00097 for(std::size_t i = 0; i < global_collision_body_transforms_.size() ; ++i)
00098 global_collision_body_transforms_[i] = parent_link_global_transform * attach_trans_[i];
00099 }