diff --git a/moveit_core/planning_request_adapter/CMakeLists.txt b/moveit_core/planning_request_adapter/CMakeLists.txt index 87038c1d31..ee1bc41c2d 100644 --- a/moveit_core/planning_request_adapter/CMakeLists.txt +++ b/moveit_core/planning_request_adapter/CMakeLists.txt @@ -3,11 +3,18 @@ set(MOVEIT_LIB_NAME moveit_planning_request_adapter) add_library(${MOVEIT_LIB_NAME} src/planning_request_adapter.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_link_libraries(${MOVEIT_LIB_NAME} moveit_planning_scene ${catkin_LIBRARIES} ${urdfdom_LIBRARIES} ${urdfdom_headers_LIBRARIES} ${Boost_LIBRARIES}) -add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) +ament_target_dependencies(${MOVEIT_LIB_NAME} + "moveit_planning_scene" + "rclcpp" + "rmw_implementation" + "urdf" + "urdfdom" + "urdfdom_headers" + "visualization_msgs" +) install(TARGETS ${MOVEIT_LIB_NAME} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib) -install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) +install(DIRECTORY include/ DESTINATION include) diff --git a/moveit_core/planning_request_adapter/src/planning_request_adapter.cpp b/moveit_core/planning_request_adapter/src/planning_request_adapter.cpp index a62ac0acb3..22e4c8f747 100644 --- a/moveit_core/planning_request_adapter/src/planning_request_adapter.cpp +++ b/moveit_core/planning_request_adapter/src/planning_request_adapter.cpp @@ -37,11 +37,14 @@ #include #include #include +#include "rclcpp/rclcpp.hpp" // we could really use some c++11 lambda functions here :) namespace planning_request_adapter { +rclcpp::Logger LOGGER = rclcpp::get_logger("moveit").get_child("planning_request_adapter"); + namespace { bool callPlannerInterfaceSolve(const planning_interface::PlannerManager* planner, @@ -91,7 +94,7 @@ bool callAdapter1(const PlanningRequestAdapter* adapter, const planning_interfac } catch (std::exception& ex) { - ROS_ERROR_NAMED("planning_request_adapter", "Exception caught executing *final* adapter '%s': %s", + RCLCPP_ERROR(LOGGER, "Exception caught executing *final* adapter '%s': %s", adapter->getDescription().c_str(), ex.what()); added_path_index.clear(); return callPlannerInterfaceSolve(planner.get(), planning_scene, req, res); @@ -109,7 +112,7 @@ bool callAdapter2(const PlanningRequestAdapter* adapter, const PlanningRequestAd } catch (std::exception& ex) { - ROS_ERROR_NAMED("planning_request_adapter", "Exception caught executing *next* adapter '%s': %s", + RCLCPP_ERROR(LOGGER, "Exception caught executing *next* adapter '%s': %s", adapter->getDescription().c_str(), ex.what()); added_path_index.clear(); return planner(planning_scene, req, res); @@ -166,4 +169,4 @@ bool PlanningRequestAdapterChain::adaptAndPlan(const planning_interface::Planner } } -} // end of namespace planning_request_adapter \ No newline at end of file +} // end of namespace planning_request_adapter