Skip to content

Commit

Permalink
Add patches
Browse files Browse the repository at this point in the history
  • Loading branch information
Tobias-Fischer committed Jul 6, 2021
1 parent c676025 commit 09f3d94
Show file tree
Hide file tree
Showing 7 changed files with 208 additions and 3 deletions.
37 changes: 34 additions & 3 deletions patch/dependencies.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -69,24 +69,26 @@ rosserial_python:
add_run: ["pyserial"]
mesh_client:
add_host: ["REQUIRE_OPENGL", "cgal-cpp"]
mesh_msgs_conversions:
add_host: ["pkg-config"]
map_organizer:
add_host: ["REQUIRE_OPENGL"]
libuvc_camera:
add_host: ["pkgconfig"]
toposens_markers:
add_host: [REQUIRE_OPENGL, libglib, glib, libxcb, pthread-stubs, xorg-libxau, xorg-libxi, xorg-libxrandr, xorg-libxcursor, xorg-libxtst, xorg-libxcomposite, xorg-libxdamage, xorg-libxinerama, xorg-xineramaproto]
audio_capture:
add_host: ["pkg-config"]
add_host: ["pkg-config", "libglib", "glib"]
audio_play:
add_host: ["pkg-config"]
add_host: ["pkg-config", "libglib", "glib"]
cob_object_detection_visualizer:
add_host: ["REQUIRE_OPENGL"]
grid_map_pcl:
add_host: ["REQUIRE_OPENGL"]
hdf5_map_io:
add_host: ["pkg-config"]
laser_scan_matcher:
add_host: ["REQUIRE_OPENGL"]
add_host: ["REQUIRE_OPENGL", "pkg-config"]
moveit_calibration_plugins:
add_host: ["libopencv"]
multisense_ros:
Expand All @@ -103,3 +105,32 @@ joint_trajectory_generator:
add_host: ["pkg-config"]
pr2_controller_manager:
add_host: ["pkg-config"]
cob_mimic:
add_host: ["pkg-config"]
cob_obstacle_distance:
add_host: ["pkg-config"]
cob_sound:
add_host: ["pkg-config"]
dataspeed_pds_lcm:
add_host: ["pkg-config"]
exotica_core:
add_host: ["pkg-config"]
face_detector:
add_host: ["yaml-cpp"]
fadecandy_driver:
add_host: ["pkg-config"]
gpsd_client:
add_host: ["pkg-config"]
people_tracking_filter:
add_host: ["pkg-config"]
points_preprocessor:
add_host: ["pkg-config"]
robot_pose_ekf:
add_host: ["pkg-config"]
rospilot:
add_host: ["pkg-config"]
nav_grid_server:
add_host: ["pkg-config"]
safety_limiter:
add_host: ["REQUIRE_OPENGL"]

30 changes: 30 additions & 0 deletions patch/ros-noetic-face-detector.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index e865b87..94b2d79 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -22,6 +22,8 @@ find_package(catkin REQUIRED COMPONENTS
tf
)

+find_package(yaml-cpp REQUIRED)
+
find_package(Boost REQUIRED COMPONENTS system thread)
find_package(OpenCV)

@@ -57,6 +59,7 @@ include_directories(
${Boost_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
+ ${YAML_INCLUDE_DIRS}
)

add_executable(face_detector
@@ -64,7 +67,7 @@ add_executable(face_detector
src/faces.cpp)
add_dependencies(face_detector ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
target_link_libraries(face_detector
- yaml-cpp
+ ${YAML_CPP_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
${OpenCV_LIBRARIES})
31 changes: 31 additions & 0 deletions patch/ros-noetic-global-planner-tests.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 743db46e..5a66be87 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -4,6 +4,8 @@ set_directory_properties(PROPERTIES COMPILE_OPTIONS "-std=c++11;-Wall;-Werror")

find_package(catkin REQUIRED COMPONENTS map_server nav_core2 roscpp nav_msgs pluginlib)

+find_package(yaml-cpp REQUIRED)
+
catkin_package(
CATKIN_DEPENDS map_server nav_core2 roscpp nav_msgs pluginlib
INCLUDE_DIRS include
@@ -12,7 +14,7 @@ catkin_package(

add_library(${PROJECT_NAME} src/global_planner_tests.cpp src/easy_costmap.cpp src/many_map_test_suite.cpp src/util.cpp)
target_link_libraries(
- ${PROJECT_NAME} ${catkin_LIBRARIES} yaml-cpp
+ ${PROJECT_NAME} ${catkin_LIBRARIES} ${YAML_CPP_LIBRARIES}
)

add_executable(gpt_node src/gpt_node.cpp)
@@ -25,7 +27,7 @@ add_executable(many_map_node src/many_map_node.cpp)
target_link_libraries(many_map_node ${PROJECT_NAME} ${catkin_LIBRARIES})

include_directories(
- include ${catkin_INCLUDE_DIRS}
+ include ${catkin_INCLUDE_DIRS} ${YAML_INCLUDE_DIRS}
)

if(CATKIN_ENABLE_TESTING)
40 changes: 40 additions & 0 deletions patch/ros-noetic-grid-map-pcl.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index a8dc5573..2f9d44f2 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -45,6 +45,8 @@ find_package(catkin REQUIRED
${CATKIN_PACKAGE_DEPENDENCIES}
)

+find_package(yaml-cpp REQUIRED)
+
###################################
## catkin specific configuration ##
###################################
@@ -59,11 +61,11 @@ catkin_package(
include
LIBRARIES
${PROJECT_NAME}
- yaml-cpp
CATKIN_DEPENDS
${CATKIN_PACKAGE_DEPENDENCIES}
DEPENDS
PCL
+ YAML_CPP
)

###########
@@ -91,11 +93,12 @@ target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC
${PCL_KDTREE_INCLUDE_DIRS}
${PCL_SEGMENTATION_INCLUDE_DIRS}
${PCL_SURFACE_INCLUDE_DIRS}
+ ${YAML_INCLUDE_DIRS}
)
target_link_libraries(${PROJECT_NAME}
${catkin_LIBRARIES}
${OpenMP_CXX_LIBRARIES}
- yaml-cpp
+ ${YAML_CPP_LIBRARIES}
)


13 changes: 13 additions & 0 deletions patch/ros-noetic-moveit-calibration-plugins.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
diff --git a/handeye_calibration_solver/CMakeLists.txt b/handeye_calibration_solver/CMakeLists.txt
index cab8464..90bf930 100644
--- a/handeye_calibration_solver/CMakeLists.txt
+++ b/handeye_calibration_solver/CMakeLists.txt
@@ -13,7 +13,7 @@ find_package(PythonLibs 2.7 REQUIRED)
find_package(NumPy 1.7 REQUIRED)

#catkin_lint: ignore_once missing_directory
-include_directories(${CMAKE_CURRENT_BINARY_DIR} ${PYTHON_INCLUDE_DIRS})
+include_directories(${CMAKE_CURRENT_BINARY_DIR} ${PYTHON_INCLUDE_DIRS} ${NUMPY_INCLUDE_DIR})

# Plugin Source
set(SOURCE_FILES
22 changes: 22 additions & 0 deletions patch/ros-noetic-osqp-vendor.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 9ed7604..9062370 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -13,9 +13,9 @@ macro(build_osqp)
endif()

include(ExternalProject)
- externalproject_add(osqp-v0.6.1.dev0
+ externalproject_add(osqp-v0.6.2
GIT_REPOSITORY https://github.com/oxfordcontrol/osqp.git
- GIT_TAG v0.6.1.dev0
+ GIT_TAG v0.6.2
GIT_SHALLOW ON
TIMEOUT 60
CMAKE_ARGS
@@ -38,4 +38,4 @@ build_osqp()
catkin_package(
LIBRARIES osqp
DEPENDS osqp
- CFG_EXTRAS osqp_vendor-extras.cmake)
+ CFG_EXTRAS ${CMAKE_CURRENT_SOURCE_DIR}/osqp_vendor-extras.cmake)
38 changes: 38 additions & 0 deletions patch/ros-noetic-ublox-gps.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 264f2b1..8b95f86 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -16,8 +16,7 @@ catkin_package(

# include boost
find_package(Boost REQUIRED COMPONENTS system regex thread)
-link_directories(${Boost_LIBRARY_DIR})
-include_directories(${Boost_INCLUDE_DIR})
+include_directories(${Boost_INCLUDE_DIRS})

# include other ublox packages
include_directories(${PROJECT_SOURCE_DIR}/include)
@@ -32,21 +31,16 @@ add_library(ublox_gps src/gps.cpp)
# fix msg compile order bug
add_dependencies(ublox_gps ${catkin_EXPORTED_TARGETS})

-target_link_libraries(ublox_gps
- boost_system
- boost_regex
- boost_thread
-)
-
target_link_libraries(ublox_gps
${catkin_LIBRARIES}
+ ${Boost_LIBRARIES}
)

# build node
add_executable(ublox_gps_node src/node.cpp src/mkgmtime.c src/raw_data_pa.cpp)
set_target_properties(ublox_gps_node PROPERTIES OUTPUT_NAME ublox_gps)

-target_link_libraries(ublox_gps_node boost_system boost_regex boost_thread)
+target_link_libraries(ublox_gps_node ${Boost_LIBRARIES})
target_link_libraries(ublox_gps_node ${catkin_LIBRARIES})
target_link_libraries(ublox_gps_node ublox_gps)

0 comments on commit 09f3d94

Please sign in to comment.