48 , parent_joint_model_(nullptr)
49 , parent_link_model_(nullptr)
50 , is_parent_joint_fixed_(false)
51 , joint_origin_transform_is_identity_(true)
52 , first_collision_body_transform_index_(-1)
82 for (std::size_t i = 0; i <
shapes_.size(); ++i)
103 aabb.extend(transform * Eigen::Map<Eigen::Vector3d>(&mesh->
vertices[3 * j]));
116 const Eigen::Vector3d& scale)
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
void setJointOriginTransform(const Eigen::Affine3d &transform)
Eigen::Vector3d visual_mesh_scale_
Scale factor associated with the visual geometry mesh of this link.
const JointModel * parent_joint_model_
JointModel that connects this link to the parent link.
std::vector< int > collision_origin_transform_is_identity_
Flag indicating if the constant transform applied to the collision geometry of the link (local) is id...
unsigned int vertex_count
void extendWithTransformedBox(const Eigen::Affine3d &transform, const Eigen::Vector3d &box)
Extend with a box transformed by the given transform.
Eigen::Affine3d visual_mesh_origin_
The additional origin transform for the mesh.
A joint from the robot. Models the transform that this joint applies in the kinematic chain...
Eigen::Vector3d shape_extents_
The extents of shape (dimensions of axis aligned bounding box when shape is at origin).
bool joint_origin_transform_is_identity_
True of the joint origin transform is identity.
void setGeometry(const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Affine3d &origins)
Eigen::Vector3d centered_bounding_box_offset_
Center of the axis aligned bounding box with size shape_extents_ (zero if symmetric along all axes)...
std::string visual_mesh_filename_
Filename associated with the visual geometry mesh of this link. If empty, no mesh was used...
Eigen::Affine3d joint_origin_transform_
The constant transform applied to the link (local)
EigenSTL::vector_Affine3d collision_origin_transform_
The constant transform applied to the collision geometry of the link (local)
void setParentJointModel(const JointModel *joint)
Main namespace for MoveIt!
Eigen::Vector3d computeShapeExtents(const ShapeMsg &shape_msg)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW LinkModel(const std::string &name)
JointType getType() const
Get the type of joint.
void setVisualMesh(const std::string &visual_mesh, const Eigen::Affine3d &origin, const Eigen::Vector3d &scale)
std::vector< shapes::ShapeConstPtr > shapes_
The collision geometry of the link.
Represents an axis-aligned bounding box.
bool is_parent_joint_fixed_
True if the parent joint of this link is fixed.