49 , parent_joint_model_(nullptr)
50 , parent_link_model_(nullptr)
51 , is_parent_joint_fixed_(false)
52 , joint_origin_transform_is_identity_(true)
53 , first_collision_body_transform_index_(-1)
56 joint_origin_transform_.setIdentity();
59 LinkModel::~LinkModel() =
default;
61 void LinkModel::setJointOriginTransform(
const Eigen::Isometry3d& transform)
65 joint_origin_transform_is_identity_ =
66 joint_origin_transform_.linear().isIdentity() &&
67 joint_origin_transform_.translation().norm() < std::numeric_limits<double>::epsilon();
70 void LinkModel::setParentJointModel(
const JointModel* joint)
72 parent_joint_model_ = joint;
73 is_parent_joint_fixed_ = joint->getType() == JointModel::FIXED;
79 collision_origin_transform_ = origins;
80 collision_origin_transform_is_identity_.resize(collision_origin_transform_.size());
84 for (std::size_t i = 0; i < shapes_.size(); ++i)
87 collision_origin_transform_is_identity_[i] =
88 (collision_origin_transform_[i].linear().isIdentity() &&
89 collision_origin_transform_[i].translation().norm() < std::numeric_limits<double>::epsilon()) ?
92 Eigen::Isometry3d
transform = collision_origin_transform_[i];
97 aabb.extendWithTransformedBox(transform, extents);
106 aabb.extend(transform * Eigen::Map<Eigen::Vector3d>(&mesh->
vertices[3 * j]));
111 centered_bounding_box_offset_ =
aabb.center();
113 shape_extents_.setZero();
115 shape_extents_ =
aabb.sizes();
118 void LinkModel::setVisualMesh(
const std::string& visual_mesh,
const Eigen::Isometry3d& origin,
121 visual_mesh_filename_ = visual_mesh;
122 visual_mesh_origin_ = origin;
123 visual_mesh_scale_ = scale;