From e170f3d086a44670bc005b85ce5eaee50889350c Mon Sep 17 00:00:00 2001 From: PetoAdam Date: Mon, 2 Sep 2024 13:23:26 +0200 Subject: [PATCH 1/3] update industrial ci to use jazzy and ubuntu-24.04 --- .github/workflows/industrial_ci.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/industrial_ci.yml b/.github/workflows/industrial_ci.yml index cc67d02..07f9f00 100644 --- a/.github/workflows/industrial_ci.yml +++ b/.github/workflows/industrial_ci.yml @@ -35,7 +35,7 @@ jobs: env: - ROS_REPO: ros BUILDER: colcon - ROS_DISTRO: humble + ROS_DISTRO: jazzy env: CCACHE_DIR: /github/home/.ccache # Directory for ccache (and how we enable ccache in industrial_ci) EVENT_NAME: ${{ github.event_name }} @@ -45,7 +45,7 @@ jobs: PR_NUMBER: ${{ github.event.number }} ANALYZER_TOKEN: ${{ secrets.ANALYZER_TOKEN }} DEBUG_BASH: true - runs-on: ubuntu-latest + runs-on: ubuntu-24.04 steps: - uses: actions/checkout@v2 with: From a31b2c42eb7b07d3f94afb84920324354d3bada1 Mon Sep 17 00:00:00 2001 From: PetoAdam Date: Wed, 4 Sep 2024 13:45:53 +0200 Subject: [PATCH 2/3] update hardware_interface.hpp with ros2_control changes --- .../kuka_mock_hardware_interface/hardware_interface.hpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/kuka_mock_hardware_interface/include/kuka_mock_hardware_interface/hardware_interface.hpp b/kuka_mock_hardware_interface/include/kuka_mock_hardware_interface/hardware_interface.hpp index 64c7898..8f70b76 100644 --- a/kuka_mock_hardware_interface/include/kuka_mock_hardware_interface/hardware_interface.hpp +++ b/kuka_mock_hardware_interface/include/kuka_mock_hardware_interface/hardware_interface.hpp @@ -37,8 +37,7 @@ static constexpr size_t POSITION_INTERFACE_INDEX = 0; static constexpr size_t VELOCITY_INTERFACE_INDEX = 1; static constexpr size_t ACCELERATION_INTERFACE_INDEX = 2; -class HARDWARE_INTERFACE_PUBLIC KukaMockHardwareInterface -: public hardware_interface::SystemInterface +class KukaMockHardwareInterface : public hardware_interface::SystemInterface { public: CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override; From 1963128e05eda625f387edc50312d1d9c13cda72 Mon Sep 17 00:00:00 2001 From: PetoAdam Date: Wed, 4 Sep 2024 14:05:30 +0200 Subject: [PATCH 3/3] update stdout tests for new standard as alredy done on kuka_drivers on jazzy --- kuka_agilus_support/test/test_kr_agilus.py | 6 ++---- kuka_cybertech_support/test/test_kr_cybertech.py | 6 ++---- kuka_fortec_support/test/test_kr_fortec.py | 6 ++---- kuka_iontec_support/test/test_kr_iontec.py | 6 ++---- kuka_lbr_iisy_support/test/test_lbr_iisy.py | 6 ++---- kuka_lbr_iiwa_support/test/test_lbr_iiwa.py | 6 ++---- kuka_quantec_support/test/test_kr_quantec.py | 6 ++---- 7 files changed, 14 insertions(+), 28 deletions(-) diff --git a/kuka_agilus_support/test/test_kr_agilus.py b/kuka_agilus_support/test/test_kr_agilus.py index ad2b5ac..5bbb746 100644 --- a/kuka_agilus_support/test/test_kr_agilus.py +++ b/kuka_agilus_support/test/test_kr_agilus.py @@ -56,7 +56,5 @@ def generate_test_description(test_file): class TestModels(unittest.TestCase): def test_read_stdout(self, proc_output): - # Check for frames defined by ROS-Industrial - proc_output.assertWaitFor("got segment base", timeout=5) - proc_output.assertWaitFor("got segment flange", timeout=5) - proc_output.assertWaitFor("got segment tool0", timeout=5) + # Check for robot initialization + proc_output.assertWaitFor("Robot initialized", timeout=5) diff --git a/kuka_cybertech_support/test/test_kr_cybertech.py b/kuka_cybertech_support/test/test_kr_cybertech.py index 2ad7cc8..93784fd 100644 --- a/kuka_cybertech_support/test/test_kr_cybertech.py +++ b/kuka_cybertech_support/test/test_kr_cybertech.py @@ -56,7 +56,5 @@ def generate_test_description(test_file): class TestModels(unittest.TestCase): def test_read_stdout(self, proc_output): - # Check for frames defined by ROS-Industrial - proc_output.assertWaitFor("got segment base", timeout=5) - proc_output.assertWaitFor("got segment flange", timeout=5) - proc_output.assertWaitFor("got segment tool0", timeout=5) + # Check for robot initialization + proc_output.assertWaitFor("Robot initialized", timeout=5) diff --git a/kuka_fortec_support/test/test_kr_fortec.py b/kuka_fortec_support/test/test_kr_fortec.py index 2f48798..4815110 100644 --- a/kuka_fortec_support/test/test_kr_fortec.py +++ b/kuka_fortec_support/test/test_kr_fortec.py @@ -60,7 +60,5 @@ def generate_test_description(test_file): class TestModels(unittest.TestCase): def test_read_stdout(self, proc_output): - # Check for frames defined by ROS-Industrial - proc_output.assertWaitFor("got segment base", timeout=5) - proc_output.assertWaitFor("got segment flange", timeout=5) - proc_output.assertWaitFor("got segment tool0", timeout=5) + # Check for robot initialization + proc_output.assertWaitFor("Robot initialized", timeout=5) diff --git a/kuka_iontec_support/test/test_kr_iontec.py b/kuka_iontec_support/test/test_kr_iontec.py index 9e5bbe0..ef17bf8 100644 --- a/kuka_iontec_support/test/test_kr_iontec.py +++ b/kuka_iontec_support/test/test_kr_iontec.py @@ -60,7 +60,5 @@ def generate_test_description(test_file): class TestModels(unittest.TestCase): def test_read_stdout(self, proc_output): - # Check for frames defined by ROS-Industrial - proc_output.assertWaitFor("got segment base", timeout=5) - proc_output.assertWaitFor("got segment flange", timeout=5) - proc_output.assertWaitFor("got segment tool0", timeout=5) + # Check for robot initialization + proc_output.assertWaitFor("Robot initialized", timeout=5) diff --git a/kuka_lbr_iisy_support/test/test_lbr_iisy.py b/kuka_lbr_iisy_support/test/test_lbr_iisy.py index 7a71fdd..21e6237 100644 --- a/kuka_lbr_iisy_support/test/test_lbr_iisy.py +++ b/kuka_lbr_iisy_support/test/test_lbr_iisy.py @@ -56,7 +56,5 @@ def generate_test_description(test_file): class TestModels(unittest.TestCase): def test_read_stdout(self, proc_output): - # Check for frames defined by ROS-Industrial - proc_output.assertWaitFor("got segment base", timeout=5) - proc_output.assertWaitFor("got segment flange", timeout=5) - proc_output.assertWaitFor("got segment tool0", timeout=5) + # Check for robot initialization + proc_output.assertWaitFor("Robot initialized", timeout=5) diff --git a/kuka_lbr_iiwa_support/test/test_lbr_iiwa.py b/kuka_lbr_iiwa_support/test/test_lbr_iiwa.py index 92d9176..26b9d10 100644 --- a/kuka_lbr_iiwa_support/test/test_lbr_iiwa.py +++ b/kuka_lbr_iiwa_support/test/test_lbr_iiwa.py @@ -56,7 +56,5 @@ def generate_test_description(test_file): class TestModels(unittest.TestCase): def test_read_stdout(self, proc_output): - # Check for frames defined by ROS-Industrial - proc_output.assertWaitFor("got segment base", timeout=5) - proc_output.assertWaitFor("got segment flange", timeout=5) - proc_output.assertWaitFor("got segment tool0", timeout=5) + # Check for robot initialization + proc_output.assertWaitFor("Robot initialized", timeout=5) diff --git a/kuka_quantec_support/test/test_kr_quantec.py b/kuka_quantec_support/test/test_kr_quantec.py index e00a6bb..aab5416 100644 --- a/kuka_quantec_support/test/test_kr_quantec.py +++ b/kuka_quantec_support/test/test_kr_quantec.py @@ -56,7 +56,5 @@ def generate_test_description(test_file): class TestModels(unittest.TestCase): def test_read_stdout(self, proc_output): - # Check for frames defined by ROS-Industrial - proc_output.assertWaitFor("got segment base", timeout=5) - proc_output.assertWaitFor("got segment flange", timeout=5) - proc_output.assertWaitFor("got segment tool0", timeout=5) + # Check for robot initialization + proc_output.assertWaitFor("Robot initialized", timeout=5)