Select Git revision
CMakeLists.txt

Johannes Mey authored
CMakeLists.txt 4.51 KiB
cmake_minimum_required(VERSION 3.0.2)
project(panda_mqtt_connector)
set(GCC_COVERAGE_COMPILE_FLAGS "-fpermissive")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GCC_COVERAGE_COMPILE_FLAGS} ${GAZEBO_CXX_FLAGS} -std=c++14")
# Find catkin macros and libraries if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) is used, also find other
# catkin packages
find_package(catkin REQUIRED COMPONENTS
controller_manager
effort_controllers
gazebo_ros
genmsg
joint_state_controller
joint_state_publisher
joint_trajectory_controller
robot_state_publisher
roscpp
std_msgs
tf
xacro
moveit_core
moveit_visual_tools
moveit_ros_planning
moveit_ros_planning_interface
controller_interface
hardware_interface
simulation_util
)
# System dependencies are found with CMake's conventions
find_package(Boost REQUIRED COMPONENTS filesystem)
find_package(Protobuf 3 REQUIRED)
include_directories(${Protobuf_INCLUDE_DIRS})
include_directories(${CMAKE_CURRENT_BINARY_DIR})
#protobuf_generate_cpp(PROTO_SRCS PROTO_HDRS proto/dataconfig.proto)
#protobuf_generate_cpp(PROTO_SRCS PROTO_HDRS proto/linkstate.proto)
#protobuf_generate_cpp(PROTO_SRCS PROTO_HDRS proto/robotconfig.proto)
protobuf_generate_cpp(PROTO_SRCS PROTO_HDRS proto/dataconfig.proto proto/linkstate.proto proto/robotconfig.proto proto/trajectory.proto)
SET_SOURCE_FILES_PROPERTIES(${PROTO_SRC} ${PROTO_HDRS} PROPERTIES GENERATED TRUE)
find_package(PkgConfig REQUIRED)
add_subdirectory(lib/paho.mqtt.c)
set(PAHO_MQTT_C_LIBRARIES "${panda_mqtt_connector_BINARY_DIR}/lib/paho.mqtt.c/src/libpaho-mqtt3a.so")
set(PAHO_MQTT_C_INCLUDE_DIRS "${PROJECT_SOURCE_DIR}/lib/paho.mqtt.c/src")
add_subdirectory(lib/paho.mqtt.cpp)
# ################################################################################################################################
# catkin specific configuration ##
# ################################################################################################################################
# The catkin_package macro generates cmake config files for your package Declare things to be passed to dependent projects
catkin_package(CATKIN_DEPENDS
moveit_core
moveit_visual_tools
moveit_ros_planning_interface
controller_interface
hardware_interface
pluginlib
simulation_util
DEPENDS
# system_lib
)
# ################################################################################################################################
# Build ##
# ################################################################################################################################
# Specify additional locations of header files Your package locations should be listed before other locations
include_directories(
lib/paho.mqtt.c/src
lib/paho.mqtt.cpp/src
${catkin_INCLUDE_DIRS}
)
add_dependencies(paho-mqttpp3 paho-mqtt3c)
add_library(TrajectoryUtil src/util/TrajectoryUtil.cpp src/util/TrajectoryUtil.h)
add_library(MqttUtil src/util/MqttUtil.cpp src/util/MqttUtil.h)
add_executable(RobotStateProvider src/RobotStateProvider.cpp ${PROTO_SRCS} ${PROTO_HDRS})
add_executable(TimedPlanner src/TimedPlanner.cpp)
add_executable(MqttToRosNode src/MqttToRosNode.cpp ${PROTO_SRCS} ${PROTO_HDRS})
add_executable(MqttRosConnectionTestNode src/MqttRosConnectionTestNode.cpp ${PROTO_SRCS} ${PROTO_HDRS})
add_executable(${PROJECT_NAME}_safety_zone_spawner src/safety_zone_spawner.cpp)
set_target_properties(${PROJECT_NAME}_safety_zone_spawner PROPERTIES OUTPUT_NAME safety_zone_spawner PREFIX "")
add_dependencies(${PROJECT_NAME}_safety_zone_spawner ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
# Specify libraries to link a library or executable target against
target_link_libraries(TrajectoryUtil
${catkin_LIBRARIES}
)
target_link_libraries(RobotStateProvider LINK_PUBLIC
MqttUtil
${catkin_LIBRARIES}
paho-mqttpp3
${Protobuf_LIBRARIES}
)
target_link_libraries(MqttToRosNode LINK_PUBLIC
MqttUtil
${catkin_LIBRARIES}
paho-mqttpp3
${Protobuf_LIBRARIES}
)
target_link_libraries(MqttRosConnectionTestNode LINK_PUBLIC
MqttUtil
${catkin_LIBRARIES}
paho-mqttpp3
${Protobuf_LIBRARIES}
)
target_link_libraries(TimedPlanner ${catkin_LIBRARIES} TrajectoryUtil)
target_link_libraries(${PROJECT_NAME}_safety_zone_spawner ${catkin_LIBRARIES})