Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer_ros/urdf_reader.h"
00018
00019 #include <string>
00020 #include <vector>
00021
00022 #include "cartographer_ros/msg_conversion.h"
00023 #include "urdf/model.h"
00024
00025 namespace cartographer_ros {
00026
00027 std::vector<geometry_msgs::TransformStamped> ReadStaticTransformsFromUrdf(
00028 const std::string& urdf_filename, tf2_ros::Buffer* const tf_buffer) {
00029 urdf::Model model;
00030 CHECK(model.initFile(urdf_filename));
00031 #if URDFDOM_HEADERS_HAS_SHARED_PTR_DEFS
00032 std::vector<urdf::LinkSharedPtr> links;
00033 #else
00034 std::vector<boost::shared_ptr<urdf::Link> > links;
00035 #endif
00036 model.getLinks(links);
00037 std::vector<geometry_msgs::TransformStamped> transforms;
00038 for (const auto& link : links) {
00039 if (!link->getParent() || link->parent_joint->type != urdf::Joint::FIXED) {
00040 continue;
00041 }
00042
00043 const urdf::Pose& pose =
00044 link->parent_joint->parent_to_joint_origin_transform;
00045 geometry_msgs::TransformStamped transform;
00046 transform.transform =
00047 ToGeometryMsgTransform(cartographer::transform::Rigid3d(
00048 Eigen::Vector3d(pose.position.x, pose.position.y, pose.position.z),
00049 Eigen::Quaterniond(pose.rotation.w, pose.rotation.x,
00050 pose.rotation.y, pose.rotation.z)));
00051 transform.child_frame_id = link->name;
00052 transform.header.frame_id = link->getParent()->name;
00053 tf_buffer->setTransform(transform, "urdf", true );
00054 transforms.push_back(transform);
00055 }
00056 return transforms;
00057 }
00058
00059 }