Fixes urdfdom_headers version compatibility (#162)
Urdf changed their shared ptr type from boost to std. This PR detects which version of urdf is installed and uses the correct ptr type.master
parent
e8b5dd6465
commit
22d8573bd0
|
@ -53,6 +53,13 @@ find_package(PCL REQUIRED COMPONENTS common io)
|
||||||
find_package(Eigen3 REQUIRED)
|
find_package(Eigen3 REQUIRED)
|
||||||
find_package(Boost REQUIRED COMPONENTS system iostreams)
|
find_package(Boost REQUIRED COMPONENTS system iostreams)
|
||||||
|
|
||||||
|
find_package(urdfdom_headers REQUIRED)
|
||||||
|
if(DEFINED urdfdom_headers_VERSION)
|
||||||
|
if(${urdfdom_headers_VERSION} GREATER 0.4.1)
|
||||||
|
add_definitions(-DURDFDOM_HEADERS_HAS_SHARED_PTR_DEFS)
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
add_subdirectory("cartographer_ros")
|
add_subdirectory("cartographer_ros")
|
||||||
|
|
||||||
install(DIRECTORY launch urdf configuration_files
|
install(DIRECTORY launch urdf configuration_files
|
||||||
|
|
|
@ -69,7 +69,11 @@ void ReadStaticTransformsFromUrdf(const string& urdf_filename,
|
||||||
::tf2_ros::Buffer* const buffer) {
|
::tf2_ros::Buffer* const buffer) {
|
||||||
urdf::Model model;
|
urdf::Model model;
|
||||||
CHECK(model.initFile(urdf_filename));
|
CHECK(model.initFile(urdf_filename));
|
||||||
|
#if URDFDOM_HEADERS_HAS_SHARED_PTR_DEFS
|
||||||
|
std::vector<urdf::LinkSharedPtr> links;
|
||||||
|
#else
|
||||||
std::vector<boost::shared_ptr<urdf::Link>> links;
|
std::vector<boost::shared_ptr<urdf::Link>> links;
|
||||||
|
#endif
|
||||||
model.getLinks(links);
|
model.getLinks(links);
|
||||||
for (const auto& link : links) {
|
for (const auto& link : links) {
|
||||||
if (!link->getParent() || link->parent_joint->type != urdf::Joint::FIXED) {
|
if (!link->getParent() || link->parent_joint->type != urdf::Joint::FIXED) {
|
||||||
|
|
Loading…
Reference in New Issue