Skip to content

Commit

Permalink
refactored cmakelists
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk committed Aug 15, 2023
1 parent 79d206a commit 370ae19
Show file tree
Hide file tree
Showing 2 changed files with 157 additions and 56 deletions.
196 changes: 147 additions & 49 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,20 +1,24 @@
cmake_minimum_required(VERSION 3.2.0)
cmake_minimum_required(VERSION 3.5)
project(mrs_gazebo_common_resources)

set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -Wall")

## 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
set(CATKIN_DEPENDENCIES
gazebo_plugins
gazebo_ros
geometry_msgs
roscpp
std_msgs
tf2
tf2_ros
tf2_msgs
geometry_msgs
std_msgs
gazebo_plugins
tf2_ros
)

## 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
${CATKIN_DEPENDENCIES}
)

# include Gazebo
Expand Down Expand Up @@ -72,12 +76,31 @@ set(CMAKE_CXX_EXTENSIONS OFF)
## catkin specific configuration ##
###################################

set(LIBRARIES
MrsGazeboCommonResources_GuiManager
MrsGazeboCommonResources_RvizCameraSynchronizer
MrsGazeboCommonResources_StaticTransformRepublisher
MrsGazeboCommonResources_RangefinderPlugin
MrsGazeboCommonResources_2DLidarPlugin
MrsGazeboCommonResources_3DLidarPlugin
MrsGazeboCommonResources_3DLidarGpuPlugin
MrsGazeboCommonResources_CameraPlugin
MrsGazeboCommonResources_RealsensePlugin
MrsGazeboCommonResources_ParachutePlugin
MrsGazeboCommonResources_WaterGunPlugin
MrsGazeboCommonResources_GPSPlugin
MrsGazeboCommonResources_MagnetometerPlugin
MrsGazeboCommonResources_LightPlugin
MrsGazeboCommonResources_ServoCameraPlugin
MrsGazeboCommonResources_DynamicModelPlugin
)

catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS geometry_msgs std_msgs tf2_msgs gazebo_plugins
CATKIN_DEPENDS ${CATKIN_DEPENDENCIES}
DEPENDS GAZEBO Qt5Widgets Boost Eigen OpenCV
LIBRARIES MRSGazeboGuiManager MRSGazeboRvizCameraSynchronizer MRSGazeboStaticTransformRepublisher MRSGazeboRangefinderPlugin MRSGazebo2DLidarPlugin MRSGazebo3DLidarPlugin MRSGazebo3DLidarGpuPlugin MRSGazeboCameraPlugin MRSGazeboRealsensePlugin MRSGazeboParachutePlugin MRSGazeboWaterGunPlugin MRSGazeboGPSPlugin MRSGazeboMagnetometerPlugin MRSGazeboLightPlugin MRSGazeboServoCameraPlugin MRSGazeboDynamicModelPlugin
)
LIBRARIES ${LIBRARIES}
)

###########
## Build ##
Expand All @@ -100,128 +123,203 @@ include_directories(
link_directories(${GAZEBO_LIBRARY_DIRS})

## GUI plugins
add_library(MRSGazeboGuiManager SHARED src/gui_plugins/gui_manager.cpp)
target_link_libraries(MRSGazeboGuiManager

add_library(MrsGazeboCommonResources_GuiManager SHARED
src/gui_plugins/gui_manager.cpp
)

target_link_libraries(MrsGazeboCommonResources_GuiManager
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Qt5Widgets_LIBRARIES}
)

## world plugins
add_library(MRSGazeboRvizCameraSynchronizer SHARED src/world_plugins/rviz_cam_synchronizer.cpp)
target_link_libraries(MRSGazeboRvizCameraSynchronizer

add_library(MrsGazeboCommonResources_RvizCameraSynchronizer SHARED
src/world_plugins/rviz_cam_synchronizer.cpp
)

target_link_libraries(MrsGazeboCommonResources_RvizCameraSynchronizer
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
)

add_library(MRSGazeboStaticTransformRepublisher SHARED src/world_plugins/static_transform_republisher.cpp)
target_link_libraries(MRSGazeboStaticTransformRepublisher
add_library(MrsGazeboCommonResources_StaticTransformRepublisher SHARED
src/world_plugins/static_transform_republisher.cpp
)

target_link_libraries(MrsGazeboCommonResources_StaticTransformRepublisher
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
)

## sensor and model plugins
add_library(MRSGazeboRangefinderPlugin SHARED src/sensor_and_model_plugins/rangefinder_plugin.cpp)
target_link_libraries(MRSGazeboRangefinderPlugin

add_library(MrsGazeboCommonResources_RangefinderPlugin SHARED
src/sensor_and_model_plugins/rangefinder_plugin.cpp
)

target_link_libraries(MrsGazeboCommonResources_RangefinderPlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
RayPlugin
)

add_library(MRSGazebo2DLidarPlugin SHARED src/sensor_and_model_plugins/2dlidar_plugin.cpp)
target_link_libraries(MRSGazebo2DLidarPlugin
add_library(MrsGazeboCommonResources_2DLidarPlugin SHARED
src/sensor_and_model_plugins/2dlidar_plugin.cpp
)

target_link_libraries(MrsGazeboCommonResources_2DLidarPlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
RayPlugin
)

add_library(MRSGazebo3DLidarPlugin SHARED src/sensor_and_model_plugins/3dlidar_plugin.cpp)
target_link_libraries(MRSGazebo3DLidarPlugin
add_library(MrsGazeboCommonResources_3DLidarPlugin SHARED
src/sensor_and_model_plugins/3dlidar_plugin.cpp
)

target_link_libraries(MrsGazeboCommonResources_3DLidarPlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
RayPlugin
)

add_library(MRSGazebo3DLidarGpuPlugin SHARED src/sensor_and_model_plugins/3dlidar_plugin.cpp)
target_link_libraries(MRSGazebo3DLidarGpuPlugin
add_library(MrsGazeboCommonResources_3DLidarGpuPlugin SHARED
src/sensor_and_model_plugins/3dlidar_plugin.cpp
)

target_link_libraries(MrsGazeboCommonResources_3DLidarGpuPlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
GpuRayPlugin
)
target_compile_definitions(MRSGazebo3DLidarGpuPlugin PRIVATE GAZEBO_GPU_RAY=1)

add_library(MRSGazeboCameraPlugin SHARED src/sensor_and_model_plugins/camera_plugin.cpp)
target_link_libraries(MRSGazeboCameraPlugin
target_compile_definitions(MrsGazeboCommonResources_3DLidarGpuPlugin PRIVATE GAZEBO_GPU_RAY=1)

add_library(MrsGazeboCommonResources_CameraPlugin SHARED
src/sensor_and_model_plugins/camera_plugin.cpp
)

target_link_libraries(MrsGazeboCommonResources_CameraPlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
CameraPlugin
)

add_library(MRSGazeboRealsensePlugin SHARED src/sensor_and_model_plugins/realsense_plugin.cpp src/common/perlin_noise.cpp)
target_link_libraries(MRSGazeboRealsensePlugin
# RealsensePlugin

add_library(MrsGazeboCommonResources_RealsensePlugin SHARED
src/sensor_and_model_plugins/realsense_plugin.cpp
src/common/perlin_noise.cpp
)

target_link_libraries(MrsGazeboCommonResources_RealsensePlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
${OpenCV_LIBRARIES}
)

add_library(MRSGazeboParachutePlugin SHARED src/sensor_and_model_plugins/parachute_plugin.cpp)
target_link_libraries(MRSGazeboParachutePlugin
# ParachutePlugin

add_library(MrsGazeboCommonResources_ParachutePlugin SHARED
src/sensor_and_model_plugins/parachute_plugin.cpp
)

target_link_libraries(MrsGazeboCommonResources_ParachutePlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
)

add_library(MRSGazeboWaterGunPlugin SHARED src/sensor_and_model_plugins/water_gun_plugin.cpp)
target_link_libraries(MRSGazeboWaterGunPlugin
# WaterGunPlugin

add_library(MrsGazeboCommonResources_WaterGunPlugin SHARED
src/sensor_and_model_plugins/water_gun_plugin.cpp
)

target_link_libraries(MrsGazeboCommonResources_WaterGunPlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
)

add_library(MRSGazeboGPSPlugin SHARED src/sensor_and_model_plugins/gps_plugin.cpp ${SEN_PROTO_SRCS})
target_link_libraries(MRSGazeboGPSPlugin
# GPSPlugin

add_library(MrsGazeboCommonResources_GPSPlugin SHARED
src/sensor_and_model_plugins/gps_plugin.cpp
${SEN_PROTO_SRCS}
)

target_link_libraries(MrsGazeboCommonResources_GPSPlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
)

add_library(MRSGazeboMagnetometerPlugin SHARED src/sensor_and_model_plugins/magnetometer_plugin.cpp src/common/geo_mag_declination.cpp ${SEN_PROTO_SRCS})
target_link_libraries(MRSGazeboMagnetometerPlugin
# MagnetometerPlugin

add_library(MrsGazeboCommonResources_MagnetometerPlugin SHARED
src/sensor_and_model_plugins/magnetometer_plugin.cpp
src/common/geo_mag_declination.cpp ${SEN_PROTO_SRCS}
)

target_link_libraries(MrsGazeboCommonResources_MagnetometerPlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
)

## model plugins
add_library(MRSGazeboLightPlugin SHARED src/sensor_and_model_plugins/light_plugin.cpp)
target_link_libraries(MRSGazeboLightPlugin
# LightPlugin

add_library(MrsGazeboCommonResources_LightPlugin SHARED
src/sensor_and_model_plugins/light_plugin.cpp
)

target_link_libraries(MrsGazeboCommonResources_LightPlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
)

add_library(MRSGazeboServoCameraPlugin SHARED src/sensor_and_model_plugins/servo_camera_plugin.cpp)
target_link_libraries(MRSGazeboServoCameraPlugin
# ServoCameraPlugin

add_library(MrsGazeboCommonResources_ServoCameraPlugin SHARED
src/sensor_and_model_plugins/servo_camera_plugin.cpp
)

target_link_libraries(MrsGazeboCommonResources_ServoCameraPlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
)

add_library(MRSGazeboDynamicModelPlugin SHARED src/sensor_and_model_plugins/dynamic_model_plugin.cpp)
target_link_libraries(MRSGazeboDynamicModelPlugin
# DynamicModelPlugin

add_library(MrsGazeboCommonResources_DynamicModelPlugin SHARED
src/sensor_and_model_plugins/dynamic_model_plugin.cpp
)

target_link_libraries(MrsGazeboCommonResources_DynamicModelPlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
)

add_library(MRSSafetyLedPlugin SHARED src/sensor_and_model_plugins/safety_led_plugin.cpp)
target_link_libraries(MRSSafetyLedPlugin
# SafetyLedPlugin

add_library(MrsGazeboCommonResources_SafetyLedPlugin SHARED
src/sensor_and_model_plugins/safety_led_plugin.cpp
)

target_link_libraries(MrsGazeboCommonResources_SafetyLedPlugin
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
Expand All @@ -231,7 +329,7 @@ target_link_libraries(MRSSafetyLedPlugin
## | Install |
## --------------------------------------------------------------

install(TARGETS MRSGazeboGuiManager MRSGazeboRvizCameraSynchronizer MRSGazeboStaticTransformRepublisher MRSGazeboRangefinderPlugin MRSGazebo2DLidarPlugin MRSGazebo3DLidarPlugin MRSGazebo3DLidarGpuPlugin MRSGazeboCameraPlugin MRSGazeboRealsensePlugin MRSGazeboParachutePlugin MRSGazeboWaterGunPlugin MRSGazeboGPSPlugin MRSGazeboMagnetometerPlugin MRSGazeboLightPlugin MRSGazeboServoCameraPlugin MRSGazeboDynamicModelPlugin
install(TARGETS ${LIBRARIES}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
Expand Down
17 changes: 10 additions & 7 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6,21 +6,24 @@

<author email="[email protected]">Vojtech Spurny</author>
<maintainer email="[email protected]">Vojtech Spurny</maintainer>
<maintainer email="[email protected]">Tomas Baca</maintainer>

<license>BSD 3-Clause</license>

<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_export_depend>boost</build_export_depend>

<depend>gazebo_plugins</depend>
<depend>gazebo_ros</depend>
<depend>geometry_msgs</depend>
<depend>roscpp</depend>
<depend>std_msgs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tf2_msgs</depend>
<depend>std_msgs</depend>
<depend>libqt5-widgets</depend>
<depend>tf2_ros</depend>

<depend>gazebo</depend>
<depend>gazebo_ros</depend>
<depend>gazebo_plugins</depend>
<depend>boost</depend>
<depend>libqt5-widgets</depend>

<export>
<!-- gazebo_ros_paths_plugin automatically adds these to
Expand Down

0 comments on commit 370ae19

Please sign in to comment.