From 530d8b15e32e3212f24c191ada21e05a98895d28 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Tue, 21 May 2024 09:20:51 -0300 Subject: [PATCH] Add ROS 2 Jazzy to CI/CD and dev workflows (#378) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit ### Proposed changes Precisely what the title says. This patch also fixes the tests that started failing with the transition. #### Type of change - [ ] 🐛 Bugfix (change which fixes an issue) - [x] 🚀 Feature (change which adds functionality) - [ ] 📚 Documentation (change which fixes or extends documentation) ### Checklist - [x] Lint and unit tests (if any) pass locally with my changes - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have added necessary documentation (if appropriate) - [x] All commits have been signed for [DCO](https://developercertificate.org/) ### Additional comments Here we exclude `beluga_example` and `beluga_benchmark`, as we cannot yet satisfy nav2 dependencies. --------- Signed-off-by: Michel Hidalgo --- .github/workflows/ci_pipeline.yml | 2 + .github/workflows/docker_ci_pipeline.yml | 1 + .github/workflows/weekly_pipeline.yml | 1 + .../motion/test_differential_drive_model.cpp | 14 +-- .../test_omnidirectional_drive_model.cpp | 4 +- beluga_amcl/src/amcl_node.cpp | 23 ++-- beluga_amcl/test/test_amcl_node.cpp | 29 +++-- beluga_amcl/test/test_ndt_amcl_node.cpp | 19 ++- beluga_example/package.xml | 1 - docker/docker-compose.yml | 1 + docker/files/jazzy.repos | 1 + docker/images/jazzy/Dockerfile | 111 ++++++++++++++++++ tools/build-and-test.sh | 6 +- tools/run-clang-tidy.sh | 4 +- 14 files changed, 178 insertions(+), 39 deletions(-) create mode 100644 docker/files/jazzy.repos create mode 100644 docker/images/jazzy/Dockerfile diff --git a/.github/workflows/ci_pipeline.yml b/.github/workflows/ci_pipeline.yml index 476de1c3b..061b7a96d 100644 --- a/.github/workflows/ci_pipeline.yml +++ b/.github/workflows/ci_pipeline.yml @@ -38,6 +38,7 @@ jobs: - noetic - humble - iron + - jazzy include: - ros_distro: humble upload_artifacts: true @@ -92,6 +93,7 @@ jobs: - name: Perform static analysis working-directory: ${{ github.workspace }} run: ./src/beluga/tools/run-clang-tidy.sh + if: ${{ matrix.ros_distro != "jazzy" }} - name: Upload code coverage report uses: codecov/codecov-action@v3 diff --git a/.github/workflows/docker_ci_pipeline.yml b/.github/workflows/docker_ci_pipeline.yml index b143ae647..4f3d8ea95 100644 --- a/.github/workflows/docker_ci_pipeline.yml +++ b/.github/workflows/docker_ci_pipeline.yml @@ -20,6 +20,7 @@ jobs: - noetic - humble - iron + - jazzy - rolling steps: - name: Checkout repository diff --git a/.github/workflows/weekly_pipeline.yml b/.github/workflows/weekly_pipeline.yml index 0a7837279..fab4d28e2 100644 --- a/.github/workflows/weekly_pipeline.yml +++ b/.github/workflows/weekly_pipeline.yml @@ -24,6 +24,7 @@ jobs: - noetic - humble - iron + - jazzy - rolling container: image: ros:${{ matrix.ros_distro }}-ros-base diff --git a/beluga/test/beluga/motion/test_differential_drive_model.cpp b/beluga/test/beluga/motion/test_differential_drive_model.cpp index e35d60f26..c31fdc428 100644 --- a/beluga/test/beluga/motion/test_differential_drive_model.cpp +++ b/beluga/test/beluga/motion/test_differential_drive_model.cpp @@ -106,7 +106,7 @@ auto get_statistics(Range&& range) { } TEST(DifferentialDriveModelSamples, Translate) { - const double tolerance = 0.01; + const double tolerance = 0.015; const double alpha = 0.2; const double origin = 5.0; const double distance = 3.0; @@ -119,9 +119,9 @@ TEST(DifferentialDriveModelSamples, Translate) { const auto pose = SE2d{SO2d{0.0}, Vector2d{origin, 0.0}}; return state_sampling_function(pose, generator).translation().x(); }) | - ranges::views::take_exactly(1'000'000) | ranges::views::common; + ranges::views::take_exactly(100'000) | ranges::views::common; const auto [mean, stddev] = get_statistics(view); - ASSERT_NEAR(mean, origin + distance, 0.01); + ASSERT_NEAR(mean, origin + distance, tolerance); ASSERT_NEAR(stddev, std::sqrt(alpha * distance * distance), tolerance); } @@ -139,7 +139,7 @@ TEST(DifferentialDriveModelSamples, RotateFirstQuadrant) { const auto pose = SE2d{SO2d{initial_angle}, Vector2d{0.0, 0.0}}; return state_sampling_function(pose, generator).so2().log(); }) | - ranges::views::take_exactly(1'000'000) | ranges::views::common; + ranges::views::take_exactly(100'000) | ranges::views::common; const auto [mean, stddev] = get_statistics(view); ASSERT_NEAR(mean, initial_angle + motion_angle, tolerance); ASSERT_NEAR(stddev, std::sqrt(alpha * motion_angle * motion_angle), tolerance); @@ -159,7 +159,7 @@ TEST(DifferentialDriveModelSamples, RotateThirdQuadrant) { const auto pose = SE2d{SO2d{initial_angle}, Vector2d{0.0, 0.0}}; return state_sampling_function(pose, generator).so2().log(); }) | - ranges::views::take_exactly(1'000'000) | ranges::views::common; + ranges::views::take_exactly(100'000) | ranges::views::common; const auto [mean, stddev] = get_statistics(view); ASSERT_NEAR(mean, initial_angle + motion_angle, tolerance); @@ -180,7 +180,7 @@ TEST(DifferentialDriveModelSamples, RotateTranslateRotateFirstQuadrant) { const auto pose = SE2d{SO2d{0.0}, Vector2d{0.0, 0.0}}; return state_sampling_function(pose, generator).translation().norm(); }) | - ranges::views::take_exactly(1'000'000) | ranges::views::common; + ranges::views::take_exactly(100'000) | ranges::views::common; const auto [mean, stddev] = get_statistics(view); ASSERT_NEAR(mean, 1.41, tolerance); @@ -206,7 +206,7 @@ TEST(DifferentialDriveModelSamples, RotateTranslateRotateThirdQuadrant) { const auto pose = SE2d{SO2d{0.0}, Vector2d{0.0, 0.0}}; return state_sampling_function(pose, generator).translation().norm(); }) | - ranges::views::take_exactly(1'000'000) | ranges::views::common; + ranges::views::take_exactly(100'000) | ranges::views::common; const auto [mean, stddev] = get_statistics(view); ASSERT_NEAR(mean, 1.41, 0.01); diff --git a/beluga/test/beluga/motion/test_omnidirectional_drive_model.cpp b/beluga/test/beluga/motion/test_omnidirectional_drive_model.cpp index 28f2ecafb..db15ee43e 100644 --- a/beluga/test/beluga/motion/test_omnidirectional_drive_model.cpp +++ b/beluga/test/beluga/motion/test_omnidirectional_drive_model.cpp @@ -135,7 +135,7 @@ TEST(OmnidirectionalDriveModelSamples, RotateFirstQuadrant) { const auto pose = SE2d{SO2d{initial_angle}, Vector2d{0.0, 0.0}}; return state_sampling_function(pose, generator).so2().log(); }) | - ranges::views::take_exactly(1'000'000) | ranges::views::common; + ranges::views::take_exactly(100'000) | ranges::views::common; const auto [mean, stddev] = get_statistics(view); ASSERT_NEAR(mean, initial_angle + motion_angle, tolerance); ASSERT_NEAR(stddev, std::sqrt(alpha * motion_angle * motion_angle), tolerance); @@ -155,7 +155,7 @@ TEST(OmnidirectionalDriveModelSamples, RotateThirdQuadrant) { const auto pose = SE2d{SO2d{initial_angle}, Vector2d{0.0, 0.0}}; return state_sampling_function(pose, generator).so2().log(); }) | - ranges::views::take_exactly(1'000'000) | ranges::views::common; + ranges::views::take_exactly(100'000) | ranges::views::common; const auto [mean, stddev] = get_statistics(view); ASSERT_NEAR(mean, initial_angle + motion_angle, tolerance); diff --git a/beluga_amcl/src/amcl_node.cpp b/beluga_amcl/src/amcl_node.cpp index 33df09237..7549b05dc 100644 --- a/beluga_amcl/src/amcl_node.cpp +++ b/beluga_amcl/src/amcl_node.cpp @@ -560,18 +560,6 @@ void AmclNode::laser_callback(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_ return; } - const auto& [base_pose_in_map, base_pose_covariance] = last_known_estimate_.value(); - - // New pose messages are only published on updates to the filter. - if (new_estimate.has_value()) { - auto message = geometry_msgs::msg::PoseWithCovarianceStamped{}; - message.header.stamp = laser_scan->header.stamp; - message.header.frame_id = get_parameter("global_frame_id").as_string(); - tf2::toMsg(base_pose_in_map, message.pose.pose); - tf2::covarianceEigenToRowMajor(base_pose_covariance, message.pose.covariance); - pose_pub_->publish(message); - } - // Transforms are always published to keep them current. if (enable_tf_broadcast_ && get_parameter("tf_broadcast").as_bool()) { auto message = geometry_msgs::msg::TransformStamped{}; @@ -584,6 +572,17 @@ void AmclNode::laser_callback(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_ message.transform = tf2::toMsg(*last_known_odom_transform_in_map_); tf_broadcaster_->sendTransform(message); } + + // New pose messages are only published on updates to the filter. + if (new_estimate.has_value()) { + auto message = geometry_msgs::msg::PoseWithCovarianceStamped{}; + message.header.stamp = laser_scan->header.stamp; + message.header.frame_id = get_parameter("global_frame_id").as_string(); + const auto& [base_pose_in_map, base_pose_covariance] = new_estimate.value(); + tf2::toMsg(base_pose_in_map, message.pose.pose); + tf2::covarianceEigenToRowMajor(base_pose_covariance, message.pose.covariance); + pose_pub_->publish(message); + } } void AmclNode::initial_pose_callback(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr message) { diff --git a/beluga_amcl/test/test_amcl_node.cpp b/beluga_amcl/test/test_amcl_node.cpp index 75c4ef7db..5a2a00516 100644 --- a/beluga_amcl/test/test_amcl_node.cpp +++ b/beluga_amcl/test/test_amcl_node.cpp @@ -65,6 +65,11 @@ class BaseNodeFixture : public T { return spin_until([this] { return tester_node_->latest_pose().has_value(); }, 1000ms, amcl_node_, tester_node_); } + bool wait_for_transform(const std::string& target, const std::string& source) { + return spin_until( + [&, this] { return tester_node_->can_transform(target, source); }, 1000ms, amcl_node_, tester_node_); + } + bool wait_for_particle_cloud() { tester_node_->create_particle_cloud_subscriber(); return spin_until( @@ -255,8 +260,7 @@ TEST_F(TestNode, BroadcastWhenInitialPoseSet) { ASSERT_TRUE(wait_for_initialization()); ASSERT_FALSE(tester_node_->can_transform("map", "odom")); tester_node_->publish_laser_scan(); - ASSERT_TRUE(wait_for_pose_estimate()); - ASSERT_TRUE(tester_node_->can_transform("map", "odom")); + ASSERT_TRUE(wait_for_transform("map", "odom")); } TEST_F(TestNode, NoBroadcastWhenNoInitialPose) { @@ -267,7 +271,6 @@ TEST_F(TestNode, NoBroadcastWhenNoInitialPose) { ASSERT_TRUE(wait_for_initialization()); ASSERT_FALSE(tester_node_->can_transform("map", "odom")); tester_node_->publish_laser_scan(); - ASSERT_TRUE(wait_for_pose_estimate()); ASSERT_FALSE(tester_node_->can_transform("map", "odom")); } @@ -280,8 +283,7 @@ TEST_F(TestNode, BroadcastWithGlobalLocalization) { ASSERT_FALSE(tester_node_->can_transform("map", "odom")); ASSERT_TRUE(request_global_localization()); tester_node_->publish_laser_scan(); - ASSERT_TRUE(wait_for_pose_estimate()); - ASSERT_TRUE(tester_node_->can_transform("map", "odom")); + ASSERT_TRUE(wait_for_transform("map", "odom")); } TEST_F(TestNode, IgnoreGlobalLocalizationBeforeInitialize) { @@ -514,6 +516,7 @@ TEST_F(TestNode, InitialPoseBeforeInitialize) { amcl_node_->configure(); amcl_node_->activate(); tester_node_->publish_default_initial_pose(); + spin_for(10ms, amcl_node_); // ensure orderly processing tester_node_->publish_laser_scan(); ASSERT_FALSE(wait_for_pose_estimate()); } @@ -526,9 +529,10 @@ TEST_F(TestNode, InitialPoseAfterInitialize) { ASSERT_TRUE(wait_for_initialization()); ASSERT_FALSE(tester_node_->can_transform("map", "odom")); tester_node_->publish_default_initial_pose(); + spin_for(10ms, amcl_node_); // ensure orderly processing tester_node_->publish_laser_scan(); ASSERT_TRUE(wait_for_pose_estimate()); - ASSERT_TRUE(tester_node_->can_transform("map", "odom")); + ASSERT_TRUE(wait_for_transform("map", "odom")); } TEST_F(TestNode, InitialPoseWithWrongFrame) { @@ -539,6 +543,7 @@ TEST_F(TestNode, InitialPoseWithWrongFrame) { ASSERT_TRUE(wait_for_initialization()); ASSERT_FALSE(tester_node_->can_transform("map", "odom")); tester_node_->publish_initial_pose_with_wrong_frame(); + spin_for(10ms, amcl_node_); // ensure orderly processing tester_node_->publish_laser_scan(); ASSERT_TRUE(wait_for_pose_estimate()); ASSERT_FALSE(tester_node_->can_transform("map", "odom")); @@ -552,9 +557,10 @@ TEST_F(TestNode, CanUpdatePoseEstimate) { ASSERT_TRUE(wait_for_initialization()); ASSERT_FALSE(tester_node_->can_transform("map", "odom")); tester_node_->publish_default_initial_pose(); + spin_for(10ms, amcl_node_); // ensure orderly processing tester_node_->publish_laser_scan(); ASSERT_TRUE(wait_for_pose_estimate()); - ASSERT_TRUE(tester_node_->can_transform("map", "odom")); + ASSERT_TRUE(wait_for_transform("map", "odom")); { const auto [pose, _] = amcl_node_->estimate(); @@ -564,9 +570,10 @@ TEST_F(TestNode, CanUpdatePoseEstimate) { } tester_node_->publish_initial_pose(1., 1.); + spin_for(10ms, amcl_node_); // ensure orderly processing tester_node_->publish_laser_scan(); ASSERT_TRUE(wait_for_pose_estimate()); - ASSERT_TRUE(tester_node_->can_transform("map", "odom")); + ASSERT_TRUE(wait_for_transform("map", "odom")); { const auto [pose, _] = amcl_node_->estimate(); @@ -584,9 +591,10 @@ TEST_F(TestNode, CanForcePoseEstimate) { ASSERT_TRUE(wait_for_initialization()); ASSERT_FALSE(tester_node_->can_transform("map", "odom")); tester_node_->publish_default_initial_pose(); + spin_for(10ms, amcl_node_); // ensure orderly processing tester_node_->publish_laser_scan(); ASSERT_TRUE(wait_for_pose_estimate()); - ASSERT_TRUE(tester_node_->can_transform("map", "odom")); + ASSERT_TRUE(wait_for_transform("map", "odom")); { const auto [pose, _] = amcl_node_->estimate(); @@ -598,7 +606,7 @@ TEST_F(TestNode, CanForcePoseEstimate) { ASSERT_TRUE(request_nomotion_update()); tester_node_->publish_laser_scan(); ASSERT_TRUE(wait_for_pose_estimate()); - ASSERT_TRUE(tester_node_->can_transform("map", "odom")); + ASSERT_TRUE(wait_for_transform("map", "odom")); { const auto [pose, _] = amcl_node_->estimate(); @@ -677,6 +685,7 @@ TEST_F(TestNode, TransformValue) { ASSERT_NEAR(pose.translation().y(), 2.0, 0.01); ASSERT_NEAR(pose.so2().log(), Sophus::Constants::pi() / 3, 0.01); + ASSERT_TRUE(wait_for_transform("map", "odom")); const auto transform = tester_node_->lookup_transform("map", "odom"); EXPECT_NEAR(transform.translation().x(), -2.00, 0.01); EXPECT_NEAR(transform.translation().y(), -2.00, 0.01); diff --git a/beluga_amcl/test/test_ndt_amcl_node.cpp b/beluga_amcl/test/test_ndt_amcl_node.cpp index 83ca1b6ec..cce87d049 100644 --- a/beluga_amcl/test/test_ndt_amcl_node.cpp +++ b/beluga_amcl/test/test_ndt_amcl_node.cpp @@ -71,6 +71,11 @@ class BaseNodeFixture : public T { return spin_until([this] { return tester_node_->latest_pose().has_value(); }, 1000ms, ndt_amcl_node_, tester_node_); } + bool wait_for_transform(const std::string& target, const std::string& source) { + return spin_until( + [&, this] { return tester_node_->can_transform(target, source); }, 1000ms, ndt_amcl_node_, tester_node_); + } + bool wait_for_particle_cloud() { tester_node_->create_particle_cloud_subscriber(); return spin_until( @@ -233,7 +238,7 @@ TEST_F(TestNode, BroadcastWhenInitialPoseSet) { ASSERT_FALSE(tester_node_->can_transform("map", "odom")); tester_node_->publish_laser_scan(); ASSERT_TRUE(wait_for_pose_estimate()); - ASSERT_TRUE(tester_node_->can_transform("map", "odom")); + ASSERT_TRUE(wait_for_transform("map", "odom")); } TEST_F(TestNode, NoBroadcastWhenNoInitialPose) { @@ -385,6 +390,7 @@ TEST_F(TestNode, InitialPoseBeforeInitialize) { ndt_amcl_node_->activate(); ASSERT_FALSE(wait_for_pose_estimate()); tester_node_->publish_default_initial_pose(); + spin_for(10ms, ndt_amcl_node_); // ensure orderly processing tester_node_->publish_laser_scan(); ASSERT_TRUE(wait_for_pose_estimate()); } @@ -396,9 +402,10 @@ TEST_F(TestNode, InitialPoseAfterInitialize) { ASSERT_TRUE(wait_for_initialization()); ASSERT_FALSE(tester_node_->can_transform("map", "odom")); tester_node_->publish_default_initial_pose(); + spin_for(10ms, ndt_amcl_node_); // ensure orderly processing tester_node_->publish_laser_scan(); ASSERT_TRUE(wait_for_pose_estimate()); - ASSERT_TRUE(tester_node_->can_transform("map", "odom")); + ASSERT_TRUE(wait_for_transform("map", "odom")); } TEST_F(TestNode, InitialPoseWithWrongFrame) { @@ -408,6 +415,7 @@ TEST_F(TestNode, InitialPoseWithWrongFrame) { ASSERT_TRUE(wait_for_initialization()); ASSERT_FALSE(tester_node_->can_transform("map", "odom")); tester_node_->publish_initial_pose_with_wrong_frame(); + spin_for(10ms, ndt_amcl_node_); // ensure orderly processing tester_node_->publish_laser_scan(); ASSERT_FALSE(wait_for_pose_estimate()); ASSERT_FALSE(tester_node_->can_transform("map", "odom")); @@ -420,9 +428,10 @@ TEST_F(TestNode, CanUpdatePoseEstimate) { ASSERT_TRUE(wait_for_initialization()); ASSERT_FALSE(tester_node_->can_transform("map", "odom")); tester_node_->publish_default_initial_pose(); + spin_for(10ms, ndt_amcl_node_); // ensure orderly processing tester_node_->publish_laser_scan(); ASSERT_TRUE(wait_for_pose_estimate()); - ASSERT_TRUE(tester_node_->can_transform("map", "odom")); + ASSERT_TRUE(wait_for_transform("map", "odom")); { const auto [pose, _] = ndt_amcl_node_->estimate(); @@ -432,9 +441,10 @@ TEST_F(TestNode, CanUpdatePoseEstimate) { } tester_node_->publish_initial_pose(1., 1.); + spin_for(10ms, ndt_amcl_node_); // ensure orderly processing tester_node_->publish_laser_scan(); ASSERT_TRUE(wait_for_pose_estimate()); - ASSERT_TRUE(tester_node_->can_transform("map", "odom")); + ASSERT_TRUE(wait_for_transform("map", "odom")); { const auto [pose, _] = ndt_amcl_node_->estimate(); @@ -492,6 +502,7 @@ TEST_F(TestNode, TransformValue) { ASSERT_NEAR(pose.translation().y(), 2.0, 0.01); ASSERT_NEAR(pose.so2().log(), Sophus::Constants::pi() / 3, 0.01); + ASSERT_TRUE(wait_for_transform("map", "odom")); const auto transform = tester_node_->lookup_transform("map", "odom"); EXPECT_NEAR(transform.translation().x(), -2.00, 0.01); EXPECT_NEAR(transform.translation().y(), -2.00, 0.01); diff --git a/beluga_example/package.xml b/beluga_example/package.xml index 7aae03738..edcd9da90 100644 --- a/beluga_example/package.xml +++ b/beluga_example/package.xml @@ -24,7 +24,6 @@ nav2_amcl nav2_lifecycle_manager nav2_map_server - nav2_rviz_plugins rviz2 teleop_twist_keyboard diff --git a/docker/docker-compose.yml b/docker/docker-compose.yml index 6c6724a1c..4b877e53b 100644 --- a/docker/docker-compose.yml +++ b/docker/docker-compose.yml @@ -4,6 +4,7 @@ services: build: context: .. dockerfile: docker/images/${ROSDISTRO:-humble}/Dockerfile + image: ekumenlabs/beluga-${ROSDISTRO:-humble}-dev container_name: beluga-dev environment: - DISPLAY diff --git a/docker/files/jazzy.repos b/docker/files/jazzy.repos new file mode 100644 index 000000000..3c3a96bcb --- /dev/null +++ b/docker/files/jazzy.repos @@ -0,0 +1 @@ +repositories: {} diff --git a/docker/images/jazzy/Dockerfile b/docker/images/jazzy/Dockerfile new file mode 100644 index 000000000..221de9856 --- /dev/null +++ b/docker/images/jazzy/Dockerfile @@ -0,0 +1,111 @@ +FROM ros:jazzy-ros-base AS cacher + +WORKDIR /ws/src + +COPY docker/files/jazzy.repos . +RUN vcs import < jazzy.repos + +COPY . beluga/ + +RUN mkdir -p /tmp/ws/src \ + && find ./ -name "package.xml" | xargs cp --parents -t /tmp/ws/src \ + && find ./ -name "COLCON_IGNORE" | xargs cp --parents -t /tmp/ws/src \ + || true + +FROM ros:jazzy-ros-base AS timem-builder + +RUN apt-get update \ + && apt-get install --no-install-recommends -y \ + git \ + && rm -rf /var/lib/apt/lists/* + +WORKDIR /opt + +RUN git clone -b develop https://github.com/NERSC/timemory.git \ + && cd timemory \ + && git checkout 415650ee26f358218908983c87212b620c3a0328 \ + && cmake -B ./build \ + -DTIMEMORY_INSTALL_HEADERS=OFF \ + -DTIMEMORY_INSTALL_CONFIG=OFF \ + -DTIMEMORY_INSTALL_ALL=OFF \ + -DTIMEMORY_BUILD_TIMEM=ON \ + . \ + && cmake --build ./build --target timem + +FROM ros:jazzy-ros-base AS builder + +ENV DEBIAN_FRONTEND noninteractive + +RUN apt-get update \ + && apt-get install --no-install-recommends -y \ + ccache \ + curl \ + gdb \ + git \ + lcov \ + linux-cloud-tools-generic \ + linux-tools-common \ + linux-tools-generic \ + python3-colcon-coveragepy-result \ + python3-colcon-lcov-result \ + python3-pip \ + tmux \ + && rm -rf /var/lib/apt/lists/* + +ENV PIP_BREAK_SYSTEM_PACKAGES 1 +RUN pip install \ + evo==1.21.0 \ + pre-commit==2.20.0 + +COPY --from=timem-builder --chown=$USER:$GROUP /opt/timemory/ /opt/timemory +RUN cmake --build /opt/timemory/build --target install + +# Check if perf is working, if not replace it with the perf version available +RUN perf help || ( \ + mv /usr/bin/perf /usr/bin/perf.bkp && \ + ln -s $(ls -d /usr/lib/linux-tools/* | tail -n1)/perf /usr/bin/perf) + +ARG USER=developer +ARG GROUP=ekumen + +RUN addgroup --gid 1001 $GROUP \ + && adduser --uid 1001 --ingroup $GROUP --home /home/$USER --shell /bin/sh --disabled-password --gecos "" $USER \ + && adduser $USER sudo \ + && echo "$USER ALL=NOPASSWD: ALL" >> /etc/sudoers.d/$USER + +COPY docker/files/fixuid_config.yml /etc/fixuid/config.yml +RUN curl -SsL https://github.com/boxboat/fixuid/releases/download/v0.4/fixuid-0.4-linux-amd64.tar.gz | tar -C /usr/local/bin -xzf - \ + && chmod 4755 /usr/local/bin/fixuid \ + && cd /etc/fixuid \ + && sed -i "s/_USER_/$USER/" config.yml \ + && sed -i "s/_GROUP_/$GROUP/" config.yml + +RUN cd /opt && git clone https://github.com/brendangregg/FlameGraph + +USER $USER:$GROUP + +ENV USER_WS /ws + +WORKDIR $USER_WS + +RUN colcon mixin add default https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml \ + && colcon mixin update default +COPY --chown=$USER:$GROUP docker/files/colcon_defaults.yaml /home/$USER/.colcon/defaults.yaml +RUN mkdir -p /home/$USER/.ccache $USER_WS/src + +COPY --from=cacher --chown=$USER:$GROUP /tmp/ws/ $USER_WS/ + +RUN sudo apt-get update \ + && sudo apt-get -y dist-upgrade \ + && . /opt/ros/jazzy/setup.sh \ + && rosdep update \ + && rosdep install -i -y --from-path src --skip-keys 'turtlebot3_gazebo gazebo_ros_pkgs slam_toolbox nav2_amcl nav2_lifecycle_manager nav2_map_server' \ + && rosdep install -i -y --from-path src -t doc \ + && sudo rm -rf /var/lib/apt/lists/* + +COPY --from=cacher --chown=$USER:$GROUP /ws/ $USER_WS/ + +ENV WITHIN_DEV 1 + +ENV SHELL /bin/bash +ENTRYPOINT ["fixuid", "-q", "/ros_entrypoint.sh", "/bin/bash"] diff --git a/tools/build-and-test.sh b/tools/build-and-test.sh index db5f57820..f15a23748 100755 --- a/tools/build-and-test.sh +++ b/tools/build-and-test.sh @@ -23,7 +23,11 @@ SCRIPT_PATH=$(dirname "$(readlink -f "$0")") set -o errexit if [ "${ROS_DISTRO}" != "noetic" ]; then - ROS_PACKAGES="beluga beluga_ros beluga_amcl beluga_benchmark beluga_example beluga_system_tests" + if [ "${ROS_DISTRO}" != "jazzy" ] && [ "${ROS_DISTRO}" != "rolling" ]; then + ROS_PACKAGES="beluga beluga_ros beluga_amcl beluga_benchmark beluga_example beluga_system_tests" + else + ROS_PACKAGES="beluga beluga_ros beluga_amcl beluga_system_tests" + fi else ROS_PACKAGES="beluga beluga_ros beluga_amcl beluga_example" fi diff --git a/tools/run-clang-tidy.sh b/tools/run-clang-tidy.sh index 8e90e3d1c..57b5cad87 100755 --- a/tools/run-clang-tidy.sh +++ b/tools/run-clang-tidy.sh @@ -21,9 +21,9 @@ set -o errexit -o xtrace if [ "${ROS_DISTRO}" != "noetic" ]; then - ROS_PACKAGES="beluga beluga_amcl beluga_ros beluga_system_tests" + ROS_PACKAGES="beluga beluga_ros beluga_amcl beluga_system_tests" else - ROS_PACKAGES="beluga beluga_amcl" + ROS_PACKAGES="beluga beluga_ros beluga_amcl" fi source /opt/ros/${ROS_DISTRO}/setup.sh