Skip to content

Commit

Permalink
Add libftdi related packages (#114)
Browse files Browse the repository at this point in the history
* Add libftdi mapping

* kobuki and sainsmart-relay-usb

* Update vinca_linux_64.yaml

* Create ros-noetic-kobuki-ftdi.patch

* Fix patch

* Add sainsmart-relay-usb patch

* Update vinca_linux_64.yaml

* Update dependencies.yaml

* Update vinca_linux_64.yaml

* Update ros-noetic-sainsmart-relay-usb.patch

* Update vinca_linux_64.yaml

* Update vinca_linux_64.yaml

* Fixes
  • Loading branch information
Tobias-Fischer authored Apr 21, 2021
1 parent 6505517 commit bd97e94
Show file tree
Hide file tree
Showing 4 changed files with 38 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 @@ -722,3 +722,5 @@ python3-grpc-tools:
conda-forge: [grpcio-tools]
mosquitto:
conda-forge: [paho-mqtt]
libftdi-dev:
conda-forge: [libftdi]
2 changes: 2 additions & 0 deletions patch/dependencies.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -26,3 +26,5 @@ swri_image_util:
add: ["REQUIRE_OPENGL"]
posedetection_msgs:
add: ["REQUIRE_OPENGL"]
sainsmart_relay_usb:
add: [pkg-config]
30 changes: 30 additions & 0 deletions patch/ros-noetic-sainsmart-relay-usb.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 9bd1118..e9cc910 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -6,18 +6,23 @@ find_package(catkin REQUIRED COMPONENTS
std_msgs
)

+find_package(PkgConfig)
+pkg_check_modules(udev REQUIRED libudev)
+pkg_check_modules(ftdi REQUIRED libftdi1)
catkin_package()

include_directories(
${catkin_INCLUDE_DIRS}
+ ${ftdi_INCLUDE_DIRS}
+ ${udev_INCLUDE_DIRS}
)

add_executable(${PROJECT_NAME}_node src/RelayNode.cpp src/node.cpp)
-target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES} ftdi)
+target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES} ${ftdi_LIBRARIES} ${udev_LIBRARIES})
set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME relay_node PREFIX "")

add_executable(${PROJECT_NAME}_list src/list.cpp)
-target_link_libraries(${PROJECT_NAME}_list ${catkin_LIBRARIES} ftdi)
+target_link_libraries(${PROJECT_NAME}_list ${catkin_LIBRARIES} ${ftdi_LIBRARIES} ${udev_LIBRARIES})
set_target_properties(${PROJECT_NAME}_list PROPERTIES OUTPUT_NAME list PREFIX "")

install(TARGETS ${PROJECT_NAME}_node ${PROJECT_NAME}_list
5 changes: 4 additions & 1 deletion vinca_linux_64.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ packages_skip_by_deps:
packages_remove_from_deps:
- stage-ros
- stage
- kobuki-ftdi # needs too many patches for ftdi & usb

skip_existing:
- https://conda.anaconda.org/robostack/
Expand All @@ -32,7 +33,9 @@ packages_select_by_deps:
##
# TODO Linux
##
- mqtt_bridge
- kobuki_core
- sainsmart_relay_usb
# - mqtt_bridge
# - rtabmap
# - mapviz_plugins
# - swri_image_util
Expand Down

0 comments on commit bd97e94

Please sign in to comment.