Go to the documentation of this file.
40 #include <boost/algorithm/string/predicate.hpp>
47 const std::vector<shapes::ShapeConstPtr>&
shapes,
49 const trajectory_msgs::JointTrajectory& detach_posture,
51 : parent_link_model_(parent)
55 , shape_poses_(shape_poses)
56 , touch_links_(touch_links)
57 , detach_posture_(detach_posture)
58 , subframe_poses_(subframe_poses)
59 , global_subframe_poses_(subframe_poses)
62 for (
const auto& t : shape_poses_)
66 for (
const auto& t : subframe_poses_)
72 global_pose_.setIdentity();
73 global_collision_body_transforms_.resize(shape_poses.size());
74 for (Eigen::Isometry3d& global_collision_body_transform : global_collision_body_transforms_)
75 global_collision_body_transform.setIdentity();
77 shape_poses_in_link_frame_.clear();
78 shape_poses_in_link_frame_.reserve(shape_poses_.size());
79 for (
const auto& shape_pose : shape_poses_)
81 shape_poses_in_link_frame_.push_back(
pose_ * shape_pose);
115 global != end; ++global, ++local)
138 if (boost::starts_with(frame_name,
id_) && frame_name[
id_.length()] ==
'/')
148 static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
151 return IDENTITY_TRANSFORM;
156 if (boost::starts_with(frame_name,
id_) && frame_name[
id_.length()] ==
'/')
166 static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
169 return IDENTITY_TRANSFORM;
void computeTransform(const Eigen::Isometry3d &parent_link_global_transform)
Recompute global_collision_body_transform given the transform of the parent link.
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
const Eigen::Isometry3d & getGlobalSubframeTransform(const std::string &frame_name, bool *found=nullptr) const
Get the fixed transform to a named subframe on this body, relative to the world frame....
AttachedBody(const LinkModel *parent, const std::string &id, const Eigen::Isometry3d &pose, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &shape_poses, const std::set< std::string > &touch_links, const trajectory_msgs::JointTrajectory &detach_posture, const moveit::core::FixedTransformsMap &subframe_poses=moveit::core::FixedTransformsMap())
Construct an attached body for a specified link.
moveit::core::FixedTransformsMap subframe_poses_
Transforms to subframes on the object, relative to the object's pose.
moveit::core::FixedTransformsMap global_subframe_poses_
Transforms to subframes on the object, relative to the model frame.
void padd(double padding)
void setScale(double scale)
Set the scale for the shapes of this attached object.
std::string id_
string id for reference
void setPadding(double padding)
Set the padding for the shapes of this attached object.
EigenSTL::vector_Isometry3d shape_poses_
The transforms from the object's pose to the object's geometries.
bool hasSubframeTransform(const std::string &frame_name) const
Check whether a subframe of given.
#define ASSERT_ISOMETRY(transform)
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
const Eigen::Isometry3d & getSubframeTransform(const std::string &frame_name, bool *found=nullptr) const
Get the fixed transform to a named subframe on this body (relative to the body's pose)
const geometry_msgs::Pose * pose_
Main namespace for MoveIt.
Eigen::Isometry3d pose_
The transform from the parent link to the attached body's pose.
EigenSTL::vector_Isometry3d global_collision_body_transforms_
The global transforms for the attached bodies (computed by forward kinematics)
virtual Shape * clone() const=0
std::shared_ptr< const Shape > ShapeConstPtr
std::vector< shapes::ShapeConstPtr > shapes_
The geometries of the attached body.
geometry_msgs::TransformStamped t
Eigen::Isometry3d global_pose_
The transform from the model frame to the attached body's pose
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Thu Nov 21 2024 03:23:41