30 CHECK(model.
initFile(urdf_filename));
31 #if URDFDOM_HEADERS_HAS_SHARED_PTR_DEFS 32 std::vector<urdf::LinkSharedPtr> links;
34 std::vector<boost::shared_ptr<urdf::Link> > links;
36 model.getLinks(links);
37 std::vector<geometry_msgs::TransformStamped> transforms;
38 for (
const auto& link : links) {
39 if (!link->getParent() || link->parent_joint->type != urdf::Joint::FIXED) {
43 const urdf::Pose&
pose =
44 link->parent_joint->parent_to_joint_origin_transform;
45 geometry_msgs::TransformStamped transform;
48 Eigen::Vector3d(pose.position.x, pose.position.y, pose.position.z),
49 Eigen::Quaterniond(pose.rotation.w, pose.rotation.x,
50 pose.rotation.y, pose.rotation.z)));
51 transform.child_frame_id = link->name;
52 transform.header.frame_id = link->getParent()->name;
54 transforms.push_back(transform);
URDF_EXPORT bool initFile(const std::string &filename)
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
geometry_msgs::Transform ToGeometryMsgTransform(const Rigid3d &rigid3d)
std::vector< geometry_msgs::TransformStamped > ReadStaticTransformsFromUrdf(const string &urdf_filename, tf2_ros::Buffer *const tf_buffer)