Skip to content

Commit

Permalink
fix bad yaml-cpp usage in certain conditions
Browse files Browse the repository at this point in the history
fixes #24
  • Loading branch information
vrabaud committed Sep 20, 2014
1 parent 483312b commit ba1f2cc
Showing 1 changed file with 7 additions and 5 deletions.
12 changes: 7 additions & 5 deletions camera_calibration_parsers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,18 +12,20 @@ catkin_package(
)

find_package(PkgConfig)
pkg_check_modules(NEW_YAMLCPP yaml-cpp>=0.5)
if(NEW_YAMLCPP_FOUND)
add_definitions(-DHAVE_NEW_YAMLCPP)
endif(NEW_YAMLCPP_FOUND)
pkg_check_modules(YAML_CPP yaml-cpp)
if(${YAML_CPP_VERSION} VERSION_GREATER 0.5)
add_definitions(-DHAVE_NEW_YAMLCPP)
endif()
include_directories(${YAML_CPP_INCLUDE_DIRS})
link_directories(${YAML_CPP_LIBRARY_DIRS})

# define the library
add_library(${PROJECT_NAME}
src/parse.cpp
src/parse_ini.cpp
src/parse_yml.cpp
)
target_link_libraries(${PROJECT_NAME} yaml-cpp ${catkin_LIBRARIES})
target_link_libraries(${PROJECT_NAME} yaml-cpp ${catkin_LIBRARIES} ${YAML_CPP_LIBRARIES})
add_dependencies(${PROJECT_NAME} sensor_msgs_gencpp)

install(
Expand Down

0 comments on commit ba1f2cc

Please sign in to comment.