Skip to content
Closed
Show file tree
Hide file tree
Changes from all 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
7 changes: 5 additions & 2 deletions .github/workflows/nexus_integration_tests.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,9 @@ jobs:
- name: vcs
run: |
vcs import . < abb.repos
- name: rmw_zenoh_cpp source
run: |
git clone https://github.com/ros2/rmw_zenoh -b jazzy
- name: rosdep
run: |
apt update
Expand All @@ -38,6 +41,6 @@ jobs:
- name: build
run: /ros_entrypoint.sh colcon build --packages-up-to nexus_calibration nexus_gazebo nexus_demos nexus_motion_planner --mixin release lld --cmake-args -DCMAKE_CXX_COMPILER_LAUNCHER=ccache
- name: Test - Unit Tests
run: . ./install/setup.bash && RMW_IMPLEMENTATION=rmw_cyclonedds_cpp /ros_entrypoint.sh colcon test --packages-select nexus_motion_planner --event-handlers=console_direct+
run: . ./install/setup.bash && RMW_IMPLEMENTATION=rmw_zenoh_cpp /ros_entrypoint.sh colcon test --packages-select nexus_motion_planner --event-handlers=console_direct+
- name: Test - Integration Test
run: . ./install/setup.bash && cd nexus_demos && RMW_IMPLEMENTATION=rmw_cyclonedds_cpp /ros_entrypoint.sh python3 -m unittest
run: . ./install/setup.bash && cd nexus_demos && RMW_IMPLEMENTATION=rmw_zenoh_cpp /ros_entrypoint.sh python3 -m unittest
10 changes: 5 additions & 5 deletions nexus_demos/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@ The [launch.py script](launch/launch.py) will launch the system orchestrator and
>NOTE: The ROS_DOMAIN_ID occupied by the Zenoh bridges during launch time may be different from the `domain` values in the Zenoh bridge configurations. This is because the launch file overrides the domain ID of the zenoh bridges to ensure that it is same as that of the orchestrator.

### Method 1: Launch system orchestrator, IRB1300 workcell and IRB910SC Workcell together with Zenoh bridge
> NOTE: Before running any of these commands, you must set the rmw implmentation to cyclonedds with
`export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp`
> NOTE: Before running any of these commands, you must set the rmw implmentation to Zenoh with
`export RMW_IMPLEMENTATION=rmw_zenoh_cpp`
(If testing with real hardware, specify the arguments `use_fake_hardware=False`, `robot1_ip=<IP>` and `robot2_ip=<IP>`)
```bash
ros2 launch nexus_demos launch.py headless:=False
Expand All @@ -18,17 +18,17 @@ ros2 launch nexus_demos launch.py headless:=False
### Method 2: Launch System Orchestrator and 1 Workcell without Zenoh bridge (Same ROS_DOMAIN_ID)
Launch with Workcell 1
```bash
ros2 launch nexus_demos launch.py headless:=False use_zenoh_bridge:=False run_workcell_1:=true run_workcell_2:=false
ros2 launch nexus_demos launch.py headless:=False run_workcell_1:=true run_workcell_2:=false
```

Launch with Workcell 2
```bash
ros2 launch nexus_demos launch.py headless:=False use_zenoh_bridge:=False run_workcell_1:=false run_workcell_2:=true
ros2 launch nexus_demos launch.py headless:=False run_workcell_1:=false run_workcell_2:=true
```

Testing with real hardware
```bash
ros2 launch nexus_demos launch.py headless:=False use_zenoh_bridge:=False run_workcell_1:=True run_workcell_2:=False use_fake_hardware:=False robot1_ip:=<IP_ADDR>
ros2 launch nexus_demos launch.py headless:=False run_workcell_1:=True run_workcell_2:=False use_fake_hardware:=False robot1_ip:=<IP_ADDR>
```

## Launch Orchestrators individually
Expand Down
11 changes: 11 additions & 0 deletions nexus_demos/config/zenoh/system_orchestrator_router_config.json5
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
{
mode: "router",
connect: {
endpoints: [],
},
listen: {
endpoints: [
"tcp/[::]:7447"
],
},
}
25 changes: 25 additions & 0 deletions nexus_demos/config/zenoh/system_orchestrator_session_config.json5
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
{
mode: "peer",
connect: {
endpoints: {
router: [
// system orchestrator
"tcp/localhost:7447"
]
},
},

/// Configuration of data messages timestamps management.
timestamping: {
/// Whether data messages should be timestamped if not already.
/// Accepts a single boolean value or different values for router, peer and client.
///
/// ROS setting: PublicationCache which is required for transient_local durability
/// only works when time-stamping is enabled.
enabled: { router: true, peer: true, client: true },
/// Whether data messages with timestamps in the future should be dropped or not.
/// If set to false (default), messages with timestamps in the future are retimestamped.
/// Timestamps are ignored if timestamping is disabled.
drop_future_timestamp: false,
},
}
99 changes: 99 additions & 0 deletions nexus_demos/config/zenoh/workcell_1_router_config.json5
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
{
mode: "router",
connect: {
endpoints: [
// system orchestrator
"tcp/localhost:7447",
],
},
listen: {
endpoints: [
"tcp/[::]:7448"
],
},
access_control: {
"enabled": true,
"default_permission": "deny",
"rules":
[
{
"id": "liveliness_tokens",
"messages": [
"liveliness_token",
"liveliness_query",
"declare_liveliness_subscriber",
],
"flows": ["ingress", "egress"],
"permission": "allow",
"key_exprs": [
"@ros2_lv/**"
],
},
{
"id": "bridged_topics",
"messages": [
"put",
"declare_subscriber",
],
"flows": ["ingress", "egress"],
"permission": "allow",
"key_exprs": [
"*/workcell_1/workcell_state/**",
],
},
{
"id": "bridged_services",
"messages": [
"query",
"declare_queryable",
"reply",
],
"flows": ["ingress", "egress"],
"permission": "allow",
"key_exprs": [
"*/register_workcell/**",
"*/workcell_1/is_task_doable/**",
"*/workcell_1/queue_task/**",
"*/workcell_1/remove_pending_task/**",
"*/workcell_1/get_state/**",
"*/workcell_1/change_state/**",
"*/workcell_1/signal/**",
"*/workcell_1/pause/**",
],
},
{
"id": "bridged_actions",
"messages": [
"query",
"declare_queryable",
"reply",
"put",
"declare_subscriber",
],
"flows": ["ingress", "egress"],
"permission": "allow",
"key_exprs": [
"*/workcell_1/request/**",
],
},
],
"subjects":
[
{
"id": "all_subjects",
},
],
"policies":
[
{
"rules": [
"bridged_topics",
"bridged_services",
"bridged_actions",
"liveliness_tokens",
],
"subjects": ["all_subjects"],
},
]
},
}
23 changes: 23 additions & 0 deletions nexus_demos/config/zenoh/workcell_1_session_config.json5
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
{
mode: "peer",
connect: {
endpoints: [
// workcell orchestrator
"tcp/localhost:7448",
],
},

/// Configuration of data messages timestamps management.
timestamping: {
/// Whether data messages should be timestamped if not already.
/// Accepts a single boolean value or different values for router, peer and client.
///
/// ROS setting: PublicationCache which is required for transient_local durability
/// only works when time-stamping is enabled.
enabled: { router: true, peer: true, client: true },
/// Whether data messages with timestamps in the future should be dropped or not.
/// If set to false (default), messages with timestamps in the future are retimestamped.
/// Timestamps are ignored if timestamping is disabled.
drop_future_timestamp: false,
},
}
99 changes: 99 additions & 0 deletions nexus_demos/config/zenoh/workcell_2_router_config.json5
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
{
mode: "router",
connect: {
endpoints: [
// system orchestrator
"tcp/localhost:7447",
],
},
listen: {
endpoints: [
"tcp/[::]:7449"
],
},
access_control: {
"enabled": true,
"default_permission": "deny",
"rules":
[
{
"id": "liveliness_tokens",
"messages": [
"liveliness_token",
"liveliness_query",
"declare_liveliness_subscriber",
],
"flows": ["ingress", "egress"],
"permission": "allow",
"key_exprs": [
"@ros2_lv/**"
],
},
{
"id": "bridged_topics",
"messages": [
"put",
"declare_subscriber",
],
"flows": ["ingress", "egress"],
"permission": "allow",
"key_exprs": [
"*/workcell_2/workcell_state/**",
],
},
{
"id": "bridged_services",
"messages": [
"query",
"declare_queryable",
"reply",
],
"flows": ["ingress", "egress"],
"permission": "allow",
"key_exprs": [
"*/register_workcell/**",
"*/workcell_2/is_task_doable/**",
"*/workcell_2/queue_task/**",
"*/workcell_2/remove_pending_task/**",
"*/workcell_2/get_state/**",
"*/workcell_2/change_state/**",
"*/workcell_2/signal/**",
"*/workcell_2/pause/**",
],
},
{
"id": "bridged_actions",
"messages": [
"query",
"declare_queryable",
"reply",
"put",
"declare_subscriber",
],
"flows": ["ingress", "egress"],
"permission": "allow",
"key_exprs": [
"*/workcell_2/request/**",
],
},
],
"subjects":
[
{
"id": "all_subjects",
},
],
"policies":
[
{
"rules": [
"bridged_topics",
"bridged_services",
"bridged_actions",
"liveliness_tokens",
],
"subjects": ["all_subjects"],
},
]
},
}
23 changes: 23 additions & 0 deletions nexus_demos/config/zenoh/workcell_2_session_config.json5
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
{
mode: "peer",
connect: {
endpoints: [
// workcell orchestrator
"tcp/localhost:7449",
],
},

/// Configuration of data messages timestamps management.
timestamping: {
/// Whether data messages should be timestamped if not already.
/// Accepts a single boolean value or different values for router, peer and client.
///
/// ROS setting: PublicationCache which is required for transient_local durability
/// only works when time-stamping is enabled.
enabled: { router: true, peer: true, client: true },
/// Whether data messages with timestamps in the future should be dropped or not.
/// If set to false (default), messages with timestamps in the future are retimestamped.
/// Timestamps are ignored if timestamping is disabled.
drop_future_timestamp: false,
},
}
Loading