47 active_links.push_back(urdf_link->name);
48 for (
const auto& child_link : urdf_link->child_links)
55 for (std::size_t i = 0; i < urdf_link->child_links.size(); ++i)
57 const urdf::LinkConstSharedPtr child_link = urdf_link->child_links[i];
58 if ((child_link->parent_joint) && (child_link->parent_joint->type != urdf::Joint::FIXED))
72 shapes::Shape* result =
nullptr;
75 case urdf::Geometry::SPHERE:
76 result =
new shapes::Sphere(
static_cast<const urdf::Sphere*
>(geom)->radius);
78 case urdf::Geometry::BOX:
80 urdf::Vector3 dim =
static_cast<const urdf::Box*
>(geom)->dim;
81 result =
new shapes::Box(dim.x, dim.y, dim.z);
84 case urdf::Geometry::CYLINDER:
85 result =
new shapes::Cylinder(
static_cast<const urdf::Cylinder*
>(geom)->radius,
86 static_cast<const urdf::Cylinder*
>(geom)->length);
88 case urdf::Geometry::MESH:
90 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(geom);
91 if (!mesh->filename.empty())
93 Eigen::Vector3d scale(mesh->scale.x, mesh->scale.y, mesh->scale.z);
94 shapes::Mesh* m = shapes::createMeshFromResource(mesh->filename, scale);
100 RCLCPP_ERROR(
getLogger(),
"Unknown geometry type: %d",
static_cast<int>(geom->type));
104 return shapes::ShapePtr(result);
109 Eigen::Quaterniond q(pose.rotation.w, pose.rotation.x, pose.rotation.y, pose.rotation.z);
110 Eigen::Isometry3d result;
111 result.translation() = Eigen::Vector3d(pose.position.x, pose.position.y, pose.position.z);
112 result.linear() = q.toRotationMatrix();