Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Migrate master branch to ROS Jazzy #175

Merged
merged 15 commits into from
Sep 5, 2024
Merged
Show file tree
Hide file tree
Changes from 13 commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions .github/workflows/industrial_ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ jobs:
ANALYZER: sonarqube
TEST_COVERAGE: true
UPSTREAM_WORKSPACE: 'github:kroshu/kuka_robot_descriptions#master github:kroshu/kuka-external-control-sdk#master'
ROS_DISTRO: humble
ROS_DISTRO: jazzy
CCACHE_DIR: /github/home/.ccache # Directory for ccache (and how we enable ccache in industrial_ci)
EVENT_NAME: ${{ github.event_name }}
BRANCH: ${{ github.event.ref }}
Expand All @@ -43,7 +43,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:
- name: Reset ANALYZER for scheduled and push runs
run: |
Expand Down
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1 +1,2 @@
__pycache__/
.vscode
12 changes: 8 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,16 @@

This repository contains ROS2 drivers for all KUKA operating systems.

Github CI | SonarCloud
------------| ---------------
[![Build Status](https://github.com/kroshu//kuka_drivers/workflows/CI/badge.svg?branch=master)](https://github.com/kroshu/ros2_kuka_sunrise_fri_driver/actions) | [![Quality Gate Status](https://sonarcloud.io/api/project_badges/measure?project=kroshu_kuka_drivers&metric=alert_status)](https://sonarcloud.io/dashboard?id=kroshu_kuka_drivers)
ROS2 Distro | Branch | Github CI | SonarCloud
------------ | -------------- | -------------- | --------------
**Jazzy** | [`master`](https://github.com/kroshu/kuka_drivers/tree/master) | [![Build Status](https://github.com/kroshu//kuka_drivers/actions/workflows/industrial_ci.yml/badge.svg?branch=master)](https://github.com/kroshu/kuka_drivers/actions) | [![Quality Gate Status](https://sonarcloud.io/api/project_badges/measure?project=kroshu_kuka_drivers&metric=alert_status)](https://sonarcloud.io/dashboard?id=kroshu_kuka_drivers)
**Humble** | [`humble`](https://github.com/kroshu/kuka_drivers/tree/humble) | [![Build Status](https://github.com/kroshu//kuka_drivers/actions/workflows/industrial_ci.yml/badge.svg?branch=humble)](https://github.com/kroshu/kuka_drivers/actions) | [![Quality Gate Status](https://sonarcloud.io/api/project_badges/measure?project=kroshu_kuka_drivers&metric=alert_status&branch=humble)](https://sonarcloud.io/dashboard?id=kroshu_kuka_drivers)

# Requirements
The drivers require a system with ROS installed. It is recommended to use Ubuntu 22.04 with ROS humble. Iron Irwini has breaking changes in the moveit API, thus it is not yet supported.
The drivers require a system with ROS installed. It is recommended to use Ubuntu 24.04 with ROS Jazzy.

Additionally, there exists a ROS Humble version of the drivers, and its corresponding configuration can be found under the `humble` branch.

It is also recommended to use a client machine with a real-time kernel, as all three drivers require cyclic, real-time communication. Due to the real-time requirement, Windows systems are not recommended and covered in the documentation.


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ class MoveitExample : public rclcpp::Node
else
{
RCLCPP_INFO(LOGGER, "Planning successful");
return std::make_shared<moveit_msgs::msg::RobotTrajectory>(plan.trajectory_);
return std::make_shared<moveit_msgs::msg::RobotTrajectory>(plan.trajectory);
}
}

Expand All @@ -127,7 +127,7 @@ class MoveitExample : public rclcpp::Node
else
{
RCLCPP_INFO(LOGGER, "Planning successful");
return std::make_shared<moveit_msgs::msg::RobotTrajectory>(plan.trajectory_);
return std::make_shared<moveit_msgs::msg::RobotTrajectory>(plan.trajectory);
}
}

Expand All @@ -153,7 +153,7 @@ class MoveitExample : public rclcpp::Node
auto stop = std::chrono::high_resolution_clock::now();
auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(stop - start);
RCLCPP_INFO(LOGGER, "Planning successful after %li ms", duration.count());
return std::make_shared<moveit_msgs::msg::RobotTrajectory>(plan.trajectory_);
return std::make_shared<moveit_msgs::msg::RobotTrajectory>(plan.trajectory);
}

void AddObject(const moveit_msgs::msg::CollisionObject & object)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#ifndef KUKA_DRIVERS_CORE__CONTROL_MODE_HPP_
#define KUKA_DRIVERS_CORE__CONTROL_MODE_HPP_

#include <cstdint>

namespace kuka_drivers_core
{
/**
Expand Down
1 change: 0 additions & 1 deletion kuka_iiqka_eac_driver/test/test_driver_activation.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,6 @@ def generate_test_description():
class TestDriverActivation(unittest.TestCase):
def test_read_stdout(self, proc_output):
# Check for successful initialization
proc_output.assertWaitFor("got segment base", timeout=5)
proc_output.assertWaitFor(
"Successful initialization of hardware 'lbr_iisy3_r760'", timeout=5
)
Expand Down
1 change: 0 additions & 1 deletion kuka_iiqka_eac_driver/test/test_driver_startup.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,6 @@ def generate_test_description():
class TestDriverStartup(unittest.TestCase):
def test_read_stdout(self, proc_output):
# Check for successful initialization
proc_output.assertWaitFor("got segment base", timeout=5)
proc_output.assertWaitFor(
"Successful initialization of hardware 'lbr_iisy3_r760'", timeout=5
)
Expand Down
2 changes: 0 additions & 2 deletions kuka_iiqka_eac_driver/test/test_multi_robot_startup.py
Original file line number Diff line number Diff line change
Expand Up @@ -75,8 +75,6 @@ def generate_test_description():
class TestMultiStartup(unittest.TestCase):
def test_read_stdout(self, proc_output):
# Check for successful initialization
proc_output.assertWaitFor("got segment test1_base", timeout=20)
proc_output.assertWaitFor("got segment test2_base", timeout=20)
proc_output.assertWaitFor(
"Successful initialization of hardware 'test1_lbr_iisy3_r760'", timeout=20
)
Expand Down
1 change: 0 additions & 1 deletion kuka_kss_rsi_driver/test/test_driver_activation.py
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,6 @@ def generate_test_description():
class TestDriverActivation(unittest.TestCase):
def test_read_stdout(self, proc_output):
# Check for successful initialization
proc_output.assertWaitFor("got segment base", timeout=5)
proc_output.assertWaitFor(
"Successful initialization of hardware 'kr6_r700_sixx'", timeout=5
)
Expand Down
1 change: 0 additions & 1 deletion kuka_kss_rsi_driver/test/test_driver_startup.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,6 @@ def generate_test_description():
class TestDriverStartup(unittest.TestCase):
def test_read_stdout(self, proc_output):
# Check for successful initialization
proc_output.assertWaitFor("got segment base", timeout=5)
proc_output.assertWaitFor(
"Successful initialization of hardware 'kr6_r700_sixx'", timeout=5
)
Expand Down
2 changes: 0 additions & 2 deletions kuka_kss_rsi_driver/test/test_multi_robot_startup.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,6 @@ def generate_test_description():
class TestMultiStartup(unittest.TestCase):
def test_read_stdout(self, proc_output):
# Check for successful initialization
proc_output.assertWaitFor("got segment test1_base", timeout=20)
proc_output.assertWaitFor("got segment test2_base", timeout=20)
proc_output.assertWaitFor(
"Successful initialization of hardware 'test1_kr6_r700_sixx'", timeout=20
)
Expand Down
4 changes: 4 additions & 0 deletions kuka_rsi_simulator/setup.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,7 @@
script_dir=$base/lib/kuka_rsi_simulator
[install]
install_scripts=$base/lib/kuka_rsi_simulator
[tool:pytest]
minversion = 6.0
addopts = --strict-markers
norecursedirs = .git build dist
2 changes: 2 additions & 0 deletions kuka_rsi_simulator/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,4 +39,6 @@
entry_points={
"console_scripts": ["rsi_simulator = kuka_rsi_simulator.rsi_simulator:main"],
},
tests_require=["pytest"],
test_suite="test",
)
Empty file.
2 changes: 2 additions & 0 deletions kuka_rsi_simulator/test/test_dummy.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
def test_dummy():
pass
8 changes: 7 additions & 1 deletion kuka_sunrise_fri_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,14 @@ find_package(pluginlib REQUIRED)
find_package(controller_manager_msgs)
find_package(std_msgs)
find_package(std_srvs)
find_package(nanopb REQUIRED)

include_directories(include src/fri_client_sdk)
find_path(NANOPB_INCLUDE_DIR
NAMES pb.h
PATHS /usr/include/nanopb /usr/local/include/nanopb
)

include_directories(include src/fri_client_sdk ${NANOPB_INCLUDE_DIR})

add_library(fri_connection SHARED
src/connection_helpers/fri_connection.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <unistd.h>

#include <atomic>
#include <cstdint>
#include <functional>
#include <stdexcept>
#include <string>
Expand Down
1 change: 0 additions & 1 deletion kuka_sunrise_fri_driver/test/test_driver_activation.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,6 @@ def generate_test_description():
class TestDriverActivation(unittest.TestCase):
def test_read_stdout(self, proc_output):
# Check for successful initialization
proc_output.assertWaitFor("got segment base", timeout=5)
Svastits marked this conversation as resolved.
Show resolved Hide resolved
proc_output.assertWaitFor(
"Successful initialization of hardware 'lbr_iiwa14_r820'", timeout=5
)
Expand Down
1 change: 0 additions & 1 deletion kuka_sunrise_fri_driver/test/test_driver_startup.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,6 @@ def generate_test_description():
class TestDriverStartup(unittest.TestCase):
def test_read_stdout(self, proc_output):
# Check for successful initialization
proc_output.assertWaitFor("got segment base", timeout=5)
proc_output.assertWaitFor(
"Successful initialization of hardware 'lbr_iiwa14_r820'", timeout=5
)
Expand Down
2 changes: 0 additions & 2 deletions kuka_sunrise_fri_driver/test/test_multi_robot_startup.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,6 @@ def generate_test_description():
class TestMultiStartup(unittest.TestCase):
def test_read_stdout(self, proc_output):
# Check for successful initialization
proc_output.assertWaitFor("got segment test1_base", timeout=20)
proc_output.assertWaitFor("got segment test2_base", timeout=20)
proc_output.assertWaitFor(
"Successful initialization of hardware 'test1_lbr_iiwa14_r820'", timeout=20
)
Expand Down
Loading