Skip to content
This repository was archived by the owner on May 18, 2025. It is now read-only.
This repository was archived by the owner on May 18, 2025. It is now read-only.

When using an namespace for my omniroboter the controller_manager doesn't get an update_rate #366

Open
@AshBastian

Description

@AshBastian

Description of the bug
I'm trying to use mutiple omni-directional roboter with the ROS navigationstack 2 and therefore I need to setup my own controller. When I only spawn 1 roboter without a namespace, the controller_manager gets loaded without any problems, but as soon as I give the roboter an namespace, the controller_manager doesn't receive the update_parameter anymore and therefore the whole gazebo_plugin fails.

Steps to reproduce the behavior:

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import Node

def generate_launch_description():
    # Create the launch description and populate
    ld = LaunchDescription()

    bringup_dir = get_package_share_directory('gazebo_simulation')
    pkg_gazebo_ros = get_package_share_directory('gazebo_ros')

    urdf = os.path.join(bringup_dir, 'urdf', 'rs_robot.urdf')

    remappings = [('/tf', 'tf'),
                  ('/tf_static', 'tf_static')]
    
    start_gazebo_server_cmd = IncludeLaunchDescription(
            PythonLaunchDescriptionSource(
                os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')
            ),
            launch_arguments={'world': 'omni_nav_world2.model'}.items(),
        )

    start_gazebo_client_cmd = IncludeLaunchDescription(
            PythonLaunchDescriptionSource(
                os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')
            ),
        )

    omni_state_publisher = Node(
        package='robot_state_publisher',
        executable='robot_state_publisher',
        name='robot_state_publisher',
        namespace='',
        output='screen',
        parameters=[{'use_sim_time': False,
                        'publish_frequency': 10.0}],
        remappings=remappings,
        arguments=[urdf])
    
    spawn_omni = Node(
            package='gazebo_ros',
            executable='spawn_entity.py',
            arguments=[
                '-file', os.path.join(bringup_dir,'models', 'rs_robot/rs_robot.sdf'),
                '-entity', 'test',
                '-robot_namespace', '',
                '-x', '0.0', '-y', '0.0',
                '-z', '1.01', '-Y', '0.0',
                '-unpause',
            ],
            output='screen',
        )
    
    ld.add_action(start_gazebo_server_cmd)
    ld.add_action(start_gazebo_client_cmd)
    
    ld.add_action(omni_state_publisher)
    ld.add_action(spawn_omni)
    
    
    return ld

Change the namespace and -robot_namespace variable to something and the system fails

Expected behavior
The expected behavior would be, that the system loads the controller_manager into the namespace with all the parameter.

Code important for the Execution
My .yaml file that the system loads.

controller_manager:
  ros__parameters:
    update_rate: 1000  # Hz

    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

    forward_velocity_controller:
      type: forward_command_controller/ForwardCommandController

forward_velocity_controller:
  ros__parameters:
    joints:
      - first_wheel_joint
      - second_wheel_joint
      - third_wheel_joint
      - fourth_wheel_joint
    interface_name: velocity
    command_interfaces:
      - velocity
    state_interfaces:
      - velocity

The part in the .sdf file wäre the gazebo plugin is called:

<ros2_control name="GazeboSystem" type="system">
    <hardware>
      <plugin>gazebo_ros2_control/GazeboSystem</plugin>
    </hardware>
    
    <joint name="first_wheel_joint">
      <command_interface name="velocity">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <state_interface name="velocity"/>
    </joint>

    <joint name="second_wheel_joint">
      <command_interface name="velocity">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <state_interface name="velocity"/>
    </joint>

    <joint name="third_wheel_joint">
      <command_interface name="velocity">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <state_interface name="velocity"/>
    </joint>

    <joint name="fourth_wheel_joint">
      <command_interface name="velocity">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <state_interface name="velocity"/>
    </joint>
  </ros2_control>
	
    <plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
<parameters>/home/bastian/Documents/omni_navigation/install/gazebo_simulation/share/gazebo_simulation/models/rs_robot/config/controllers.yaml</parameters>
    </plugin>

Environment (please complete the following information):

  • OS: Ubuntu 22.04.4 LTS
  • Version Humble Version 16.0.10 (That is the version number of my rclcpp package)

Additional Points for what I already found
The system works as intended until the reset for the controller_manager in the gazebo_ros2_controll_plugin.cpp line 384
Here the systems doesn't load the update_rate and I believe the problem is in the executor that parses the information from the .yaml file incorrectly. Therefore the parameter for the update_rate is not set and the controller_manager therefore cannot set the value, which breaks the system. The arguments themself are given correctly to the executor in the lines 256 until 266 in the gazebo_ros2_controll_plugin.cpp.
Screenshot from 2024-08-13 13-33-02
Screenshot from 2024-08-13 13-33-22

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't working

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions