From 9c69a95ce7008fe2b18e0146a02ad63d7e9c2a17 Mon Sep 17 00:00:00 2001 From: Elia Tarasov Date: Mon, 18 Jun 2018 18:48:03 +0300 Subject: [PATCH] modify target node name and add needed libs --- CMakeLists.txt | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8c541fe4bb3b..83bf780b6206 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -325,9 +325,10 @@ if (BUILD_ROS_INTERFACE) ${sensor_msgs_INCLUDE_DIRS} ${mav_msgs_INCLUDE_DIRS} ) - add_executable(gazebo_motor_failure_plugin + add_executable(gazebo_motor_failure_node src/gazebo_motor_failure_plugin.cpp ) + target_link_libraries(gazebo_motor_failure_node ${catkin_LIBRARIES} ${roscpp_LIBRARIES} ${GAZEBO_libraries}) add_dependencies(gazebo_motor_failure_plugin ${catkin_EXPORTED_TARGETS} @@ -338,6 +339,8 @@ if (BUILD_ROS_INTERFACE) target_link_libraries(gazebo_motor_failure_plugin ${catkin_LIBRARIES} ${mavros_LIBRARIES} + ${roscpp_LIBRARIES} + ${GAZEBO_libraries} ) message(STATUS "adding gazebo_motor_failure_plugin to build") endif()