domain_bridge icon indicating copy to clipboard operation
domain_bridge copied to clipboard

Actions, Services not bridging on Turtlebot4 w/ Humble

Open civerachb-cpr opened this issue 7 months ago • 4 comments

I'm working in a slightly odd setup with a Turtlebot 4 and the domain_bridge node running inside a docker container. I can see the topics from my Create3 platform (running on domain ID 3) being bridged into my Raspberry Pi (running on domain ID 0). However, the robot's actions & services are not visible when running ros2 service list or ros2 action list.

If I open a shell in my container I can see the actions & services on domain 3 inside the container. But they don't appear to be bridged into domain 0 properly.

My current configuration yaml file:

name: create3_bridge
from_domain: 3
to_domain: 0
topics:
  battery_state:
    type: sensor_msgs/msg/BatteryState
    bidirectional: true
  cliff_intensity:
    type: irobot_create_msgs/msg/IrIntensityVector
    bidirectional: true
  cmd_audio:
    type: irobot_create_msgs/msg/AudioNoteVector
    bidirectional: true
  cmd_lightring:
    type: irobot_create_msgs/msg/LightringLeds
    bidirectional: true
  cmd_vel:
    type: geometry_msgs/msg/Twist
    bidirectional: true
  dock_status:
    type: irobot_create_msgs/msg/DockStatus
    bidirectional: true
  hazard_detection:
    type: irobot_create_msgs/msg/HazardDetectionVector
    bidirectional: true
  imu:
    type: sensor_msgs/msg/Imu
    bidirectional: true
  interface_buttons:
    type: irobot_create_msgs/msg/InterfaceButtons
    bidirectional: true
  ir_intensity:
    type: irobot_create_msgs/msg/IrIntensityVector
    bidirectional: true
  ir_opcode:
    type: irobot_create_msgs/msg/IrOpcode
    bidirectional: true
  kidnap_status:
    type: irobot_create_msgs/msg/KidnapStatus
    bidirectional: true
  mobility_monitor/transition_event:
    type: lifecycle_msgs/msg/TransitionEvent
    bidirectional: true
  mouse:
    type: irobot_create_msgs/msg/Mouse
    bidirectional: true
  odom:
    type: nav_msgs/msg/Odometry
    bidirectional: true
  robot_state/transition_event:
    type: lifecycle_msgs/msg/TransitionEvent
    bidirectional: true
  slip_status:
    type: irobot_create_msgs/msg/SlipStatus
    bidirectional: true
  static_transform/transition_event:
    type: lifecycle_msgs/msg/TransitionEvent
    bidirectional: true
  stop_status:
    type: irobot_create_msgs/msg/StopStatus
    bidirectional: true
  tf:
    type: tf2_msgs/msg/TFMessage
    bidirectional: true
  tf_static:
    type: tf2_msgs/msg/TFMessage
    bidirectional: true
  wheel_status:
    type: irobot_create_msgs/msg/WheelStatus
    bidirectional: true
  wheel_ticks:
    type: irobot_create_msgs/msg/WheelTicks
    bidirectional: true
  wheel_vels:
    type: irobot_create_msgs/msg/WheelVels
    bidirectional: true
services:
  e_stop:
    type: irobot_create_msgs/srv/EStop
    bidirectional: true
  motion_control/describe_parameters:
    type: rcl_interfaces/srv/DescribeParameters
    bidirectional: true
  motion_control/get_parameter_types:
    type: rcl_interfaces/srv/GetParameterTypes
    bidirectional: true
  motion_control/get_parameters:
    type: rcl_interfaces/srv/GetParameters
    bidirectional: true
  motion_control/list_parameters:
    type: rcl_interfaces/srv/ListParameters
    bidirectional: true
  motion_control/set_parameters:
    type: rcl_interfaces/srv/SetParameters
    bidirectional: true
  motion_control/set_parameters_atomically:
    type: rcl_interfaces/srv/SetParametersAtomically
    bidirectional: true
  reset_pose:
    type: irobot_create_msgs/srv/ResetPose
    bidirectional: true
  robot_power:
    type: irobot_create_msgs/srv/RobotPower
    bidirectional: true
  robot_state/describe_parameters:
    type: rcl_interfaces/srv/DescribeParameters
    bidirectional: true
  robot_state/get_parameter_types:
    type: rcl_interfaces/srv/GetParameterTypes
    bidirectional: true
  robot_state/get_parameters:
    type: rcl_interfaces/srv/GetParameters
    bidirectional: true
  robot_state/list_parameters:
    type: rcl_interfaces/srv/ListParameters
    bidirectional: true
  robot_state/set_parameters:
    type: rcl_interfaces/srv/SetParameters
    bidirectional: true
  robot_state/set_parameters_atomically:
    type: rcl_interfaces/srv/SetParametersAtomically
    bidirectional: true
  static_transform/describe_parameters:
    type: rcl_interfaces/srv/DescribeParameters
    bidirectional: true
  static_transform/get_parameter_types:
    type: rcl_interfaces/srv/GetParameterTypes
    bidirectional: true
  static_transform/get_parameters:
    type: rcl_interfaces/srv/GetParameters
    bidirectional: true
  static_transform/list_parameters:
    type: rcl_interfaces/srv/ListParameters
    bidirectional: true
  static_transform/set_parameters:
    type: rcl_interfaces/srv/SetParameters
    bidirectional: true
  static_transform/set_parameters_atomically:
    type: rcl_interfaces/srv/SetParametersAtomically
    bidirectional: true
  ui_mgr/describe_parameters:
    type: rcl_interfaces/srv/DescribeParameters
    bidirectional: true
  ui_mgr/get_parameter_types:
    type: rcl_interfaces/srv/GetParameterTypes
    bidirectional: true
  ui_mgr/get_parameters:
    type: rcl_interfaces/srv/GetParameters
    bidirectional: true
  ui_mgr/list_parameters:
    type: rcl_interfaces/srv/ListParameters
    bidirectional: true
  ui_mgr/set_parameters:
    type: rcl_interfaces/srv/SetParameters
    bidirectional: true
  ui_mgr/set_parameters_atomically:
    type: rcl_interfaces/srv/SetParametersAtomically
    bidirectional: true
actions:
  audio_note_sequence:
    type: irobot_create_msgs/action/AudioNoteSequence
    bidirectional: true
  dock:
    type: irobot_create_msgs/action/Dock
    bidirectional: true
  drive_arc:
    type: irobot_create_msgs/action/DriveArc
    bidirectional: true
  drive_distance:
    type: irobot_create_msgs/action/DriveDistance
    bidirectional: true
  led_animation:
    type: irobot_create_msgs/action/LedAnimation
    bidirectional: true
  navigate_to_position:
    type: irobot_create_msgs/action/NavigateToPosition
    bidirectional: true
  rotate_angle:
    type: irobot_create_msgs/action/RotateAngle
    bidirectional: true
  undock:
    type: irobot_create_msgs/action/Undock
    bidirectional: true
  wall_follow:
    type: irobot_create_msgs/action/WallFollow
    bidirectional: true

I've tried removing the bidirectional flags, but that didn't seem to have any effect; the topics remain visible but the actions & services are not.

If I add the hidden _action topics to the topics configuration I do see the actions with ros2 action list, but sending a goal hangs on waiting for the action server to become available. Services remain unbridged in this setup.

Am I doing something wrong with the configuration? Or do I need to build the package from source rather than installing the debian package? (If that's the case, will the recent changes be bloomed sometime soon?)

Docker configuration

Dockerfile

FROM ros:humble

# install ros package
RUN apt-get update && apt-get install -y \
      ros-${ROS_DISTRO}-irobot-create-msgs \
      ros-${ROS_DISTRO}-domain-bridge && \
    rm -rf /var/lib/apt/lists/*

docker-compose.yml

services:
  create3-bridge:
    image: create3-bridge:latest
    restart: always
    env_file:
      - config/create3.env
    command: ros2 run domain_bridge domain_bridge /opt/config/create3_bridge.yaml
    profiles:
      - create3
    volumes:
      - ./config/:/opt/config
    network_mode: host

config/create3.env

ROS_DOMAIN_ID=3
FASTRTPS_DEFAULT_PROFILES_FILE=/opt/config/fastrtps-profile.xml

config/fastrtps-profile.xml

<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles" >
    <transport_descriptors>
        <transport_descriptor>
            <transport_id>CustomUdpTransport</transport_id>
            <type>UDPv4</type>
        </transport_descriptor>
    </transport_descriptors>

    <participant profile_name="participant_profile" is_default_profile="true">
        <rtps>
            <userTransports>
                <transport_id>CustomUdpTransport</transport_id>
            </userTransports>

            <useBuiltinTransports>false</useBuiltinTransports>
        </rtps>
    </participant>
</profiles>

(This was done to work around the shared memory issues described here: https://answers.ros.org/question/370595/ros2-foxy-nodes-cant-communicate-through-docker-container-border/)

civerachb-cpr avatar Jun 28 '24 19:06 civerachb-cpr