49 , link_index_(link_index)
50 , parent_joint_model_(nullptr)
51 , parent_link_model_(nullptr)
52 , is_parent_joint_fixed_(false)
53 , joint_origin_transform_is_identity_(true)
54 , first_collision_body_transform_index_(-1)
56 joint_origin_transform_.setIdentity();
63 ASSERT_ISOMETRY(transform)
64 joint_origin_transform_ = transform;
65 joint_origin_transform_is_identity_ =
66 joint_origin_transform_.linear().isIdentity() &&
67 joint_origin_transform_.translation().norm() < std::numeric_limits<double>::epsilon();
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)
86 ASSERT_ISOMETRY(collision_origin_transform_[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];
94 if (shapes_[i]->type != shapes::MESH)
96 Eigen::Vector3d extents = shapes::computeShapeExtents(shapes_[i].get());
103 const shapes::Mesh* mesh =
dynamic_cast<const shapes::Mesh*
>(shapes_[i].get());
104 for (
unsigned int j = 0; j < mesh->vertex_count; ++j)
106 aabb.extend(transform * Eigen::Map<Eigen::Vector3d>(&mesh->vertices[3 * j]));
111 centered_bounding_box_offset_ = aabb.center();
114 shape_extents_.setZero();
118 shape_extents_ = aabb.sizes();
123 const Eigen::Vector3d& scale)
125 visual_mesh_filename_ = visual_mesh;
126 visual_mesh_origin_ = origin;
127 visual_mesh_scale_ = scale;