46 const std::vector<shapes::ShapeConstPtr>&
shapes,
47 const EigenSTL::vector_Isometry3d& shape_poses,
const std::set<std::string>& touch_links,
48 const trajectory_msgs::msg::JointTrajectory& detach_posture,
50 : parent_link_model_(parent)
54 , shape_poses_(shape_poses)
55 , touch_links_(touch_links)
56 , detach_posture_(detach_posture)
57 , subframe_poses_(subframe_poses)
58 , global_subframe_poses_(subframe_poses)
61 for (
const auto& t : shape_poses_)
65 for (
const auto& t : subframe_poses_)
67 ASSERT_ISOMETRY(t.second)
71 global_pose_.setIdentity();
72 global_collision_body_transforms_.resize(shape_poses.size());
73 for (Eigen::Isometry3d& global_collision_body_transform : global_collision_body_transforms_)
74 global_collision_body_transform.setIdentity();
76 shape_poses_in_link_frame_.clear();
77 shape_poses_in_link_frame_.reserve(shape_poses_.size());
78 for (
const auto& shape_pose : shape_poses_)
80 shape_poses_in_link_frame_.push_back(pose_ * shape_pose);
107 ASSERT_ISOMETRY(parent_link_global_transform)
108 global_pose_ = parent_link_global_transform * pose_;
111 for (std::size_t i = 0; i < global_collision_body_transforms_.size(); ++i)
112 global_collision_body_transforms_[i] = global_pose_ * shape_poses_[i];
115 for (
auto global = global_subframe_poses_.begin(), end = global_subframe_poses_.end(), local = subframe_poses_.begin();
116 global != end; ++global, ++local)
117 global->second = global_pose_ * local->second;
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)
void setPadding(double padding)
Set the padding for the shapes of this attached object.
bool hasSubframeTransform(const std::string &frame_name) const
Check whether a subframe of given @frame_name is present in this object.
void computeTransform(const Eigen::Isometry3d &parent_link_global_transform)
Recompute global_collision_body_transform given the transform of the parent link.
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::msg::JointTrajectory &detach_posture, const moveit::core::FixedTransformsMap &subframe_poses=moveit::core::FixedTransformsMap())
Construct an attached body for a specified link.
void setScale(double scale)
Set the scale for the shapes of this attached object.
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....
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...