Skip to content

Commit

Permalink
Add basic ROS 1 node, update CMakelists and package.xml
Browse files Browse the repository at this point in the history
Signed-off-by: Evan Flynn <[email protected]>
  • Loading branch information
evan-flynn-apexai authored and flynneva committed Nov 5, 2023
1 parent a34f2aa commit b1d5c4b
Show file tree
Hide file tree
Showing 4 changed files with 399 additions and 72 deletions.
171 changes: 111 additions & 60 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,16 +7,29 @@ if(NOT CMAKE_CXX_STANDARD)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic -Werror)
if($ENV{ROS_VERSION} EQUAL 2)
add_compile_options(-Wall -Wextra -Wpedantic -Werror)
endif()
endif()

find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()
# Remove once ROS 1 Noetic is deprecated
if($ENV{ROS_VERSION} EQUAL 1)
find_package(catkin REQUIRED COMPONENTS
cv_bridge
roscpp
std_msgs
std_srvs
sensor_msgs
camera_info_manager
image_transport)
else()
find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()
endif()

find_package(OpenCV REQUIRED)

find_package(PkgConfig REQUIRED)
pkg_check_modules(avcodec REQUIRED libavcodec)
pkg_check_modules(avutil REQUIRED libavutil)
pkg_check_modules(swscale REQUIRED libswscale)

Expand All @@ -40,6 +53,7 @@ add_library(${PROJECT_NAME} SHARED

target_include_directories(${PROJECT_NAME} PUBLIC
"include"
${OpenCV_INCLUDE_DIRS}
)

target_link_libraries(${PROJECT_NAME}
Expand All @@ -48,66 +62,103 @@ target_link_libraries(${PROJECT_NAME}
${swscale_LIBRARIES}
${OpenCV_LIBRARIES})

ament_export_libraries(${PROJECT_NAME})

## Declare a ROS 2 composible node as a library
ament_auto_add_library(${PROJECT_NAME}_node SHARED
src/usb_cam_node.cpp
)

target_link_libraries(${PROJECT_NAME}_node
${PROJECT_NAME})

## Use node to generate an executable
rclcpp_components_register_node(${PROJECT_NAME}_node
PLUGIN "usb_cam::UsbCamNode"
EXECUTABLE ${PROJECT_NAME}_node_exe
)
# Remove once ROS 1 Noetic is deprecated
if($ENV{ROS_VERSION} EQUAL 1)
catkin_package(
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME}
)

add_executable(${PROJECT_NAME}_node src/ros1/usb_cam_node.cpp)
target_link_libraries(${PROJECT_NAME}_node
${PROJECT_NAME}
${catkin_LIBRARIES}
)
target_include_directories(${PROJECT_NAME}_node PUBLIC
${catkin_INCLUDE_DIRS})
else()
ament_export_libraries(${PROJECT_NAME})

## Declare a ROS 2 composible node as a library
ament_auto_add_library(${PROJECT_NAME}_node SHARED
src/ros2/usb_cam_node.cpp
)

target_link_libraries(${PROJECT_NAME}_node
${PROJECT_NAME})

if(SANITIZE)
target_compile_options(${PROJECT_NAME} PUBLIC -fsanitize=address -fsanitize=leak)
target_link_libraries(${PROJECT_NAME} -fsanitize=address -fsanitize=leak)
target_compile_options(${PROJECT_NAME}_node PUBLIC -fsanitize=address -fsanitize=leak)
target_link_libraries(${PROJECT_NAME}_node -fsanitize=address -fsanitize=leak)
target_link_libraries(${PROJECT_NAME}_node_exe -fsanitize=address -fsanitize=leak)
## Use node to generate an executable
rclcpp_components_register_node(${PROJECT_NAME}_node
PLUGIN "usb_cam::UsbCamNode"
EXECUTABLE ${PROJECT_NAME}_node_exe
)
if(SANITIZE)
target_compile_options(${PROJECT_NAME} PUBLIC -fsanitize=address -fsanitize=leak)
target_link_libraries(${PROJECT_NAME} -fsanitize=address -fsanitize=leak)
target_compile_options(${PROJECT_NAME}_node PUBLIC -fsanitize=address -fsanitize=leak)
target_link_libraries(${PROJECT_NAME}_node -fsanitize=address -fsanitize=leak)
target_link_libraries(${PROJECT_NAME}_node_exe -fsanitize=address -fsanitize=leak)
endif()
endif()

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest)

# Unit tests
ament_add_gtest(test_usb_cam_utils
test/test_usb_cam_utils.cpp)
target_link_libraries(test_usb_cam_utils
${PROJECT_NAME})
ament_add_gtest(test_pixel_formats
test/test_pixel_formats.cpp)
target_link_libraries(test_pixel_formats
${PROJECT_NAME})
# TODO(flynneva): rewrite this test in another PR
# Integration tests
# ament_add_gtest(test_usb_cam_lib
# test/test_usb_cam_lib.cpp)
# target_link_libraries(test_usb_cam_lib
# ${PROJECT_NAME})
if($ENV{ROS_VERSION} EQUAL 2)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest)

# Unit tests
ament_add_gtest(test_usb_cam_utils
test/test_usb_cam_utils.cpp)
target_link_libraries(test_usb_cam_utils
${PROJECT_NAME})
ament_add_gtest(test_pixel_formats
test/test_pixel_formats.cpp)
target_link_libraries(test_pixel_formats
${PROJECT_NAME})
# TODO(flynneva): rewrite this test in another PR
# Integration tests
# ament_add_gtest(test_usb_cam_lib
# test/test_usb_cam_lib.cpp)
# target_link_libraries(test_usb_cam_lib
# ${PROJECT_NAME})
endif()
endif()

install(
PROGRAMS scripts/show_image.py
DESTINATION lib/${PROJECT_NAME})

install(TARGETS
${PROJECT_NAME}
${PROJECT_NAME}_node
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib
)
ament_auto_package(
INSTALL_TO_SHARE
launch
config
)
if($ENV{ROS_VERSION} EQUAL 1)
install(TARGETS ${PROJECT_NAME}_node ${PROJECT_NAME}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
)

## Copy launch files
install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
FILES_MATCHING PATTERN "*.launch"
)

install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp"
)
else()
install(
PROGRAMS scripts/show_image.py
DESTINATION lib/${PROJECT_NAME})

install(TARGETS
${PROJECT_NAME}
${PROJECT_NAME}_node
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib
)

ament_auto_package(
INSTALL_TO_SHARE
launch
config
)
endif()
29 changes: 17 additions & 12 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<package format="3">
<name>usb_cam</name>
<version>0.7.0</version>
<description>A ROS 2 Driver for V4L USB Cameras</description>
<description>A ROS Driver for V4L USB Cameras</description>

<maintainer email="[email protected]">Evan Flynn</maintainer>

Expand All @@ -13,11 +13,17 @@
<url type="bugtracker">https://github.com/ros-drivers/usb_cam/issues</url>
<url type="repository">https://github.com/ros-drivers/usb_cam</url>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend condition="$ROS_VERSION == 1">catkin</buildtool_depend>

<buildtool_depend condition="$ROS_VERSION == 2">ament_cmake_auto</buildtool_depend>
<buildtool_depend condition="$ROS_VERSION == 2">rosidl_default_generators</buildtool_depend>

<build_depend condition="$ROS_VERSION == 1">roscpp</build_depend>

<depend condition="$ROS_VERSION == 2">rclcpp</depend>
<depend condition="$ROS_VERSION == 2">rclcpp_components</depend>

<depend>cv_bridge</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>std_msgs</depend>
<depend>std_srvs</depend>
<depend>sensor_msgs</depend>
Expand All @@ -30,17 +36,16 @@
<!-- Only required for MJPEG to RGB converison -->
<depend>ffmpeg</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<test_depend condition="$ROS_VERSION == 2">ament_cmake_gtest</test_depend>
<test_depend condition="$ROS_VERSION == 2">ament_lint_auto</test_depend>
<test_depend condition="$ROS_VERSION == 2">ament_lint_common</test_depend>

<buildtool_depend>rosidl_default_generators</buildtool_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<exec_depend condition="$ROS_VERSION == 2">rosidl_default_runtime</exec_depend>

<member_of_group>rosidl_interface_packages</member_of_group>
<member_of_group condition="$ROS_VERSION == 2">rosidl_interface_packages</member_of_group>

<export>
<build_type>ament_cmake</build_type>
<build_type condition="$ROS_VERSION == 1">ament_cmake</build_type>
<build_type condition="$ROS_VERSION == 2">ament_cmake</build_type>
</export>
</package>
Loading

0 comments on commit b1d5c4b

Please sign in to comment.