diff --git a/.github/workflows/build-and-test.sh b/.github/workflows/build-and-test.sh new file mode 100755 index 0000000..4752164 --- /dev/null +++ b/.github/workflows/build-and-test.sh @@ -0,0 +1,33 @@ +#!/bin/bash +set -ev + +# Configuration. +export COLCON_WS=~/ws +export COLCON_WS_SRC=${COLCON_WS}/src +export DEBIAN_FRONTEND=noninteractive +export ROS_PYTHON_VERSION=3 + +apt update -qq +apt install -qq -y lsb-release wget curl build-essential + +# Dependencies. +echo "deb http://packages.ros.org/ros2-testing/ubuntu `lsb_release -cs` main" > /etc/apt/sources.list.d/ros2-testing.list +curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | apt-key add - +apt-get update -qq +apt-get install -y python3-colcon-common-extensions \ + python3-rosdep python3-vcstool python3-vcstools + +rosdep init +rosdep update + +# Build. +mkdir -p $COLCON_WS_SRC +cp -r $GITHUB_WORKSPACE $COLCON_WS_SRC +cd $COLCON_WS +rosdep install --from-paths ./ -i -y -r --rosdistro $ROS_DISTRO $ROSDEP_ARGS +source /opt/ros/$ROS_DISTRO/setup.bash +colcon build --event-handlers console_direct+ + +# Tests. +colcon test --event-handlers console_direct+ +colcon test-result diff --git a/.github/workflows/ros2-ci.yml b/.github/workflows/ros2-ci.yml new file mode 100644 index 0000000..6f9b172 --- /dev/null +++ b/.github/workflows/ros2-ci.yml @@ -0,0 +1,24 @@ +name: ROS2 CI + +on: [push, pull_request] + +jobs: + point_cloud_transport_tutorial_ci: + name: point_cloud_transport_tutorial CI + runs-on: ubuntu-latest + strategy: + fail-fast: false + matrix: + include: + - docker-image: "ubuntu:22.04" + ros-distro: "rolling" + container: + image: ${{ matrix.docker-image }} + steps: + - name: Checkout + uses: actions/checkout@v2 + - name: Build and Test + run: .github/workflows/build-and-test.sh + env: + DOCKER_IMAGE: ${{ matrix.docker-image }} + ROS_DISTRO: ${{ matrix.ros-distro }} diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md new file mode 100644 index 0000000..309be1e --- /dev/null +++ b/CONTRIBUTING.md @@ -0,0 +1,3 @@ +Any contribution that you make to this repository will +be under the 3-Clause BSD License, as dictated by that +[license](https://opensource.org/licenses/BSD-3-Clause). diff --git a/LICENSE b/LICENSE index 3f7c241..24d43da 100644 --- a/LICENSE +++ b/LICENSE @@ -1,30 +1,30 @@ -BSD 3-Clause License - -Copyright (c) Czech Technical University in Prague -Copyright (c) 2019, paplhjak All rights reserved. -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this - list of conditions and the following disclaimer. +Software License Agreement (BSD License 2.0) -2. 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. +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions +are met: -3. Neither the name of the copyright holder nor the names of its - contributors may be used to endorse or promote products derived from - this software without specific prior written permission. + * 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 copyright holder 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. +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 OWNER 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. diff --git a/src/my_encoder.cpp b/src/my_encoder.cpp index 4de177c..1265977 100644 --- a/src/my_encoder.cpp +++ b/src/my_encoder.cpp @@ -1,16 +1,37 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague .. 2019, paplhjak +// Copyright (c) 2023, Czech Technical University in Prague +// Copyright (c) 2023, Open Source Robotics Foundation, Inc. All rights reserved. +// +// 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 Willow Garage 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. -// This file is a simple example of how to use the C++ "PointCloudCodec" API of -// point_cloud_transport to encode/decode point clouds without needing to -// publish/subscribe to a topic. - -// for ros2 logging + reading rosbag #include #include #include #include -#include +#include #include #include @@ -59,13 +80,14 @@ int main(int /*argc*/, char ** /*argv*/) // Encode using C++ API // - // encode/decode communicate via a serialized message. This was done to support arbitrary encoding formats and to make it easy to bind - // to other languages (since the serialized message is simply a uchar buffer and its size) + // encode/decode communicate via a serialized message. This was done to support arbitrary + // encoding formats and to make it easy to bind to other languages (since the serialized + // message is simply a uchar buffer and its size) rclcpp::SerializedMessage compressed_msg; const bool encode_success = codec.encode(transport, cloud_msg, compressed_msg); - // BUT encodeTyped/decodeTyped are also available if you would rather work with the actual encoded message type - // (which may vary depending on the transport being used). + // BUT encodeTyped/decodeTyped are also available if you would rather work with the actual + // encoded message type (which may vary depending on the transport being used). if (encode_success) { RCLCPP_INFO( diff --git a/src/my_publisher.cpp b/src/my_publisher.cpp index 6b3530a..f9e6d88 100644 --- a/src/my_publisher.cpp +++ b/src/my_publisher.cpp @@ -1,20 +1,44 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague .. 2019, paplhjak +// Copyright (c) 2023, Czech Technical University in Prague +// Copyright (c) 2023, Open Source Robotics Foundation, Inc. All rights reserved. +// +// 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 Willow Garage 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. -// This file is a simple example of how to use the C++ "PointCloudTransport" API of -// point_cloud_transport to publish encoded point_cloud messages via ROS2. - -#include #include // for reading rosbag #include + +#include #include #include #include #include -#include +#include #include #include @@ -32,13 +56,11 @@ int main(int argc, char ** argv) "point_cloud_transport_tutorial"); std::string bag_file = shared_directory + "/resources/rosbag2_2023_08_05-16_08_51"; - if (argc > 1) - { + if (argc > 1) { bag_file = argv[1]; } - if (!rcpputils::fs::exists(bag_file)) - { + if (!rcpputils::fs::exists(bag_file)) { std::cout << "Not able to open file [" << bag_file << "]" << '\n'; return -1; } diff --git a/src/my_subscriber.cpp b/src/my_subscriber.cpp index 18f48ca..468d140 100644 --- a/src/my_subscriber.cpp +++ b/src/my_subscriber.cpp @@ -1,8 +1,32 @@ -// SPDX-License-Identifier: BSD-3-Clause -// SPDX-FileCopyrightText: Czech Technical University in Prague .. 2019, paplhjak +// Copyright (c) 2023, Czech Technical University in Prague +// Copyright (c) 2023, Open Source Robotics Foundation, Inc. All rights reserved. +// +// 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 Willow Garage 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. -// This file is a simple example of how to use the C++ "PointCloudTransport" API of -// point_cloud_transport to subscribe to and decode compressed point_cloud messages via ROS2. #include #include