Skip to content

Commit

Permalink
add patches for roscpp rt and swri-yaml-util
Browse files Browse the repository at this point in the history
  • Loading branch information
wolfv committed Apr 1, 2021
1 parent f644211 commit 3625a8e
Show file tree
Hide file tree
Showing 4 changed files with 37 additions and 1 deletion.
2 changes: 2 additions & 0 deletions conda-forge.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -711,3 +711,5 @@ flex:
conda-forge: [flex]
ignition-gazebo3:
conda-forge: [libignition-gazebo4]
libgdal-dev:
conda-forge: [libgdal]
4 changes: 3 additions & 1 deletion patch/dependencies.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,4 +15,6 @@ gazebo_pkgs:
ros_ign_gazebo:
add: ["REQUIRE_OPENGL"]
apriltag:
add: ["REQUIRE_OPENGL"]
add: ["REQUIRE_OPENGL"]
lvr2:
add: [libgdal-dev]
19 changes: 19 additions & 0 deletions patch/ros-noetic-roscpp.linux.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index fe506f1ffc..783dae7e34 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -53,9 +53,13 @@ if(CMAKE_THREAD_LIBS_INIT)
endif()
endif()

+if (UNIX AND NOT APPLE)
+ set(RT_LIB rt)
+endif()
+
catkin_package(
INCLUDE_DIRS include ${CATKIN_DEVEL_PREFIX}/${CATKIN_GLOBAL_INCLUDE_DESTINATION}/ros
- LIBRARIES roscpp ${PTHREAD_LIB}
+ LIBRARIES roscpp ${PTHREAD_LIB} ${RT_LIB}
CATKIN_DEPENDS cpp_common message_runtime rosconsole roscpp_serialization roscpp_traits rosgraph_msgs rostime std_msgs xmlrpcpp
DEPENDS Boost
)
13 changes: 13 additions & 0 deletions patch/ros-noetic-swri-yaml-util.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 628d70846..cc668b01f 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -29,7 +29,7 @@ include_directories(include)
include_directories(SYSTEM
${catkin_INCLUDE_DIRS}
${CATKIN_DEVEL_PREFIX}/${CATKIN_GLOBAL_INCLUDE_DESTINATION}
- ${YamlCpp_INCLUDE_DIR}
+ ${YamlCpp_INCLUDE_DIRS}
)

add_library(${PROJECT_NAME}

0 comments on commit 3625a8e

Please sign in to comment.