43#include <Eigen/Geometry>
44#include <eigen_stl_containers/eigen_stl_vector_container.h>
46#include <geometric_shapes/check_isometry.h>
67using LinkTransformMap = std::map<const LinkModel*, Eigen::Isometry3d, std::less<const LinkModel*>,
68 Eigen::aligned_allocator<std::pair<const LinkModel* const, Eigen::Isometry3d> > >;
82 LinkModel(
const std::string& name,
size_t link_index);
99 return first_collision_body_transform_index_;
104 first_collision_body_transform_index_ = index;
110 return parent_joint_model_;
119 return parent_link_model_;
124 parent_link_model_ = link;
130 return child_joint_models_;
135 child_joint_models_.push_back(joint);
145 return joint_origin_transform_;
150 return joint_origin_transform_is_identity_;
155 return is_parent_joint_fixed_;
166 return collision_origin_transform_;
172 return collision_origin_transform_is_identity_;
176 const std::vector<shapes::ShapeConstPtr>&
getShapes()
const
181 void setGeometry(
const std::vector<shapes::ShapeConstPtr>&
shapes,
const EigenSTL::vector_Isometry3d& origins);
188 return shape_extents_;
194 return centered_bounding_box_offset_;
201 return associated_fixed_transforms_;
207 ASSERT_ISOMETRY(transform);
208 associated_fixed_transforms_[link_model] = transform;
214 return visual_mesh_filename_;
220 return visual_mesh_scale_;
226 return visual_mesh_origin_;
229 void setVisualMesh(
const std::string& visual_mesh,
const Eigen::Isometry3d& origin,
const Eigen::Vector3d& scale);
245 std::vector<const JointModel*> child_joint_models_;
248 bool is_parent_joint_fixed_;
251 bool joint_origin_transform_is_identity_;
254 Eigen::Isometry3d joint_origin_transform_;
257 EigenSTL::vector_Isometry3d collision_origin_transform_;
261 std::vector<int> collision_origin_transform_is_identity_;
267 std::vector<shapes::ShapeConstPtr> shapes_;
270 Eigen::Vector3d shape_extents_;
273 Eigen::Vector3d centered_bounding_box_offset_;
276 std::string visual_mesh_filename_;
279 Eigen::Isometry3d visual_mesh_origin_;
282 Eigen::Vector3d visual_mesh_scale_;
286 int first_collision_body_transform_index_;
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
#define MOVEIT_CLASS_FORWARD(C)
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
A link from the robot. Contains the constant transform applied to the link and its geometry.
int getFirstCollisionBodyTransformIndex() const
const std::string & getName() const
The name of this link.
void addAssociatedFixedTransform(const LinkModel *link_model, const Eigen::Isometry3d &transform)
Remember that link_model is attached to this link using a fixed transform.
bool jointOriginTransformIsIdentity() const
const Eigen::Isometry3d & getVisualMeshOrigin() const
Get the transform for the visual mesh origin.
const std::string & getVisualMeshFilename() const
Get the filename of the mesh resource used for visual display of this link.
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
const Eigen::Vector3d & getVisualMeshScale() const
Get the scale of the mesh resource for this link.
const Eigen::Vector3d & getCenteredBoundingBoxOffset() const
Get the offset of the center of the bounding box of this link when the link is positioned at origin.
void setFirstCollisionBodyTransformIndex(int index)
const EigenSTL::vector_Isometry3d & getCollisionOriginTransforms() const
In addition to the link transform, the geometry of a link that is used for collision checking may hav...
void addChildJointModel(const JointModel *joint)
void setGeometry(const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &origins)
void setParentLinkModel(const LinkModel *link)
bool parentJointIsFixed() const
void setParentJointModel(const JointModel *joint)
const LinkModel * getParentLinkModel() const
Get the link model whose child this link is (through some joint). There may not always be a parent li...
const std::vector< int > & areCollisionOriginTransformsIdentity() const
Return flags for each transform specifying whether they are identity or not.
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
const Eigen::Isometry3d & getJointOriginTransform() const
When transforms are computed for this link, they are usually applied to the link's origin....
void setVisualMesh(const std::string &visual_mesh, const Eigen::Isometry3d &origin, const Eigen::Vector3d &scale)
void setJointOriginTransform(const Eigen::Isometry3d &transform)
const std::vector< const JointModel * > & getChildJointModels() const
A link may have 0 or more child joints. From those joints there will certainly be other descendant li...
const Eigen::Vector3d & getShapeExtentsAtOrigin() const
Get the extents of the link's geometry (dimensions of axis-aligned bounding box around all shapes tha...
const LinkTransformMap & getAssociatedFixedTransforms() const
Get the set of links that are attached to this one via fixed transforms. The returned transforms are ...
size_t getLinkIndex() const
The index of this joint when traversing the kinematic tree in depth first fashion.
std::map< const LinkModel *, Eigen::Isometry3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Isometry3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
std::map< std::string, const LinkModel * > LinkModelMapConst
Map of names to const instances for LinkModel.
std::map< std::string, LinkModel * > LinkModelMap
Map of names to instances for LinkModel.
Main namespace for MoveIt.