鱼香ROS社区
    • 版块
    • 最新
    • 未解决
    • 已解决
    • 群组
    • 注册
    • 登录
    紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
    提问前必看的发帖注意事项: 社区问答规则(小鱼个人)更新 | 高质量帖子发布指南

    在命名空间下加载两轮差速控制器controller_manager加载失败

    已定时 已固定 已锁定 已移动 已解决
    综合问题
    控制器 gazebo 仿真 差速控制
    2
    7
    658
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • 2
      2118561423
      最后由 编辑

      在launch文件中加载命名空间下的gazebo机器人模型时控制器无法获取update_rate参数,但是在yaml文件中正常设置了该参数,且在其他非命名空间下的launch文件进行启动就不会有该问题能够正常启动,鱼哥,这是什么问题呢

      日志:

      [gzserver-2] [INFO] [1743648186.768197312] [robot2.gazebo_ros2_control]: connected to service!! robot_state_publisher
      [gzserver-2] [INFO] [1743648186.774441017] [robot2.gazebo_ros2_control]: Received urdf from param server, parsing...
      [gzserver-2] [INFO] [1743648186.774570288] [robot2.gazebo_ros2_control]: Loading parameter files /home/chen/Program/test_car/test_car_ws/install/car_description/share/car_description/config/track_car_ros2_controller.yaml
      [gzserver-2] [INFO] [1743648186.785325792] [robot2.gazebo_ros2_control]: Loading joint: left_wheel_joint
      [gzserver-2] [INFO] [1743648186.785424816] [robot2.gazebo_ros2_control]:        State:
      [gzserver-2] [INFO] [1743648186.785438451] [robot2.gazebo_ros2_control]:                 position
      [gzserver-2] [INFO] [1743648186.785449251] [robot2.gazebo_ros2_control]:                 velocity
      [gzserver-2] [INFO] [1743648186.789883244] [robot2.gazebo_ros2_control]:                 effort
      [gzserver-2] [INFO] [1743648186.789891189] [robot2.gazebo_ros2_control]:        Command:
      [gzserver-2] [INFO] [1743648186.789919331] [robot2.gazebo_ros2_control]:                 velocity
      [gzserver-2] [INFO] [1743648186.790143749] [robot2.gazebo_ros2_control]:                 effort
      [gzserver-2] [INFO] [1743648186.790156363] [robot2.gazebo_ros2_control]: Loading joint: right_wheel_joint
      [gzserver-2] [INFO] [1743648186.790162734] [robot2.gazebo_ros2_control]:        State:
      [gzserver-2] [INFO] [1743648186.790168756] [robot2.gazebo_ros2_control]:                 position
      [gzserver-2] [INFO] [1743648186.790174326] [robot2.gazebo_ros2_control]:                 velocity
      [gzserver-2] [INFO] [1743648186.790179756] [robot2.gazebo_ros2_control]:                 effort
      [gzserver-2] [INFO] [1743648186.790184926] [robot2.gazebo_ros2_control]:        Command:
      [gzserver-2] [INFO] [1743648186.790191789] [robot2.gazebo_ros2_control]:                 velocity
      [gzserver-2] [INFO] [1743648186.790228076] [robot2.gazebo_ros2_control]:                 effort
      [gzserver-2] [INFO] [1743648186.790315619] [resource_manager]: Initialize hardware 'TrackCarGazeboSystem' 
      [gzserver-2] [INFO] [1743648186.790485555] [resource_manager]: Successful initialization of hardware 'TrackCarGazeboSystem'
      [gzserver-2] [INFO] [1743648186.790567368] [resource_manager]: 'configure' hardware 'TrackCarGazeboSystem' 
      [gzserver-2] [INFO] [1743648186.790576875] [resource_manager]: Successful 'configure' of hardware 'TrackCarGazeboSystem'
      [gzserver-2] [INFO] [1743648186.790582496] [resource_manager]: 'activate' hardware 'TrackCarGazeboSystem' 
      [gzserver-2] [INFO] [1743648186.790588126] [resource_manager]: Successful 'activate' of hardware 'TrackCarGazeboSystem'
      [gzserver-2] [INFO] [1743648186.790664048] [robot2.gazebo_ros2_control]: Loading controller_manager
      [gzserver-2] [WARN] [1743648186.821653458] [robot2.controller_manager]: 'update_rate' parameter not set, using default value.
      [gzserver-2] [ERROR] [1743648186.836982336] [robot2.gazebo_ros2_control]: controller manager doesn't have an update_rate parameter
      

      launch文件代码:

      import launch
      import launch_ros
      import os
      from ament_index_python.packages import get_package_share_directory
      from launch.launch_description_sources import PythonLaunchDescriptionSource
      from launch.substitutions import Command, LaunchConfiguration
      import launch_ros.parameter_descriptions
      from ament_index_python.packages import get_package_prefix
      from launch.actions import TimerAction
      
      def generate_launch_description():
          # pkg_robot1_path = get_package_share_directory('fishbot_description')
          pkg_robot2_path = get_package_share_directory('car_description')
          # urdf_robot1_path = os.path.join(pkg_robot1_path, 'urdf', 'fishbot', 'fishbot.urdf.xacro')
          urdf_robot2_path = os.path.join(pkg_robot2_path, 'urdf', 'car_urdf', 'trackcar.urdf.xacro')
      
          #获取模型文件目录
          package_name = 'car_description'
          pkg_share = os.pathsep + os.path.join(get_package_prefix(package_name), 'share')
          if 'GAZEBO_MODEL_PATH' in os.environ:  # 如果你修改了~/.bashrc, 就会执行这个
              os.environ['GAZEBO_MODEL_PATH'] += pkg_share
          else:  # 注意此处gazebo-11修改为你的gazebo版本
              os.environ['GAZEBO_MODEL_PATH'] = "/usr/share/gazebo-11/models" + pkg_share   
      
          default_world_path = os.path.join(pkg_robot2_path, 'world', 'custom_room.world')
      
          # action_declare_arg_mode1path = launch.actions.DeclareLaunchArgument(
          #     name='robot1',
          #     default_value=urdf_robot1_path
          # )
          action_declare_arg_mode2path = launch.actions.DeclareLaunchArgument(
              name='robot2',
              default_value=urdf_robot2_path
          )
      
          # robot1_description = launch_ros.parameter_descriptions.ParameterValue(
          #     Command(['xacro ', LaunchConfiguration("robot1")])
          # )
          robot2_description = launch_ros.parameter_descriptions.ParameterValue(
              Command(['xacro ', LaunchConfiguration("robot2")])
          )
      
          # robot1_state_publisher_node = launch_ros.actions.Node(
          #     package='robot_state_publisher',
          #     executable='robot_state_publisher',
          #     parameters=[{
          #         'robot_description': robot1_description
          #     }],
          #     namespace='robot1',
          #     output='screen'
          # )
          robot2_state_publisher_node = launch_ros.actions.Node(
              package='robot_state_publisher',
              executable='robot_state_publisher',
              parameters=[{
                  'robot_description': robot2_description
              }],
              namespace='robot2',
              output='screen'
          )
      
          action_launch_gazebo = launch.actions.IncludeLaunchDescription(
              PythonLaunchDescriptionSource(
                  os.path.join(
                      get_package_share_directory('gazebo_ros'),
                      'launch',
                      'gazebo.launch.py'
                  )
              ),
              launch_arguments=[
                  ('world', default_world_path),
                  ('verbose', 'true'),
                  ('use_sim_time', 'true')
              ]
          )
      
          # action_spawn1_entity = launch_ros.actions.Node(
          #     package='gazebo_ros',
          #     executable='spawn_entity.py',
          #     arguments=[
          #         '-topic', 'robot1/robot_description',
          #         '-entity', 'myrobot1',
          #         '-robot_namespace', 'robot1'
          #     ],
          #     output='screen'
          # )
          action_spawn2_entity = launch_ros.actions.Node(
              package='gazebo_ros',
              executable='spawn_entity.py',
              arguments=[
                  '-topic', 'robot2/robot_description',
                  '-entity', 'myrobot2',
                  '-robot_namespace', 'robot2',
                  '-x','1.0',
                  '-y','0.5',
                  '-z','0.0'
              ],
              output='screen'
          )
      
          # 为每个机器人单独启动 joint_state_publisher
          # joint_state_publisher_robot1 = launch_ros.actions.Node(
          #     package='joint_state_publisher',
          #     executable='joint_state_publisher',
          #     namespace='robot1',
          #     parameters=[{'source_list': ['robot1/joint_states']}]
          # )
          joint_state_publisher_robot2 = launch_ros.actions.Node(
              package='joint_state_publisher',
              executable='joint_state_publisher',
              namespace='robot2',
              parameters=[{'source_list': ['/joint_states']}]
          )
          action_robot2node_joint_state = launch.actions.ExecuteProcess(
              cmd=['ros2', 'control', 'load_controller',
                   '--controller-manager', 'robot2/controller_manager', # <--- **指定目标服务**
                   'track_car_joint_state_broadcaster',
                   '--set-state', 'active'],
              output='screen'
              
      
          )
          action_robot2node_diff_drive_controller = launch.actions.ExecuteProcess(
                # cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', 'track_car_diff_drive_controller'], # 旧命令,缺少--controller-manager
               cmd=['ros2', 'control', 'load_controller',
                   '--controller-manager', 'robot2/controller_manager', # <--- **指定目标服务**
                   'track_car_diff_drive_controller',
                   '--set-state', 'active'],
              output='screen'
          )
          # 发
          return launch.LaunchDescription([
              # action_declare_arg_mode1path,
              action_declare_arg_mode2path,
              # robot1_state_publisher_node,
              robot2_state_publisher_node,
              action_launch_gazebo,
              # action_spawn1_entity,
              action_spawn2_entity,
              # joint_state_publisher_robot1,
              launch.actions.RegisterEventHandler(
                  event_handler=launch.event_handlers.OnProcessExit(
                      target_action=action_spawn2_entity,
                      on_exit=[
                          TimerAction(
                              period=5.0,
                              actions=[action_robot2node_joint_state] # Timer结束后执行加载 broadcaster
                          )
                      ],
                  )
              ),
              launch.actions.RegisterEventHandler(
                  event_handler=launch.event_handlers.OnProcessExit(
                      target_action=action_robot2node_joint_state,
                      on_exit=[action_robot2node_diff_drive_controller],
                  )
              ) ,
          ])
      

      控制器URDF文件:

      <?xml version="1.0"?>
      <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
          <xacro:macro name="track_car_ros2_control">
          <ros2_control name="TrackCarGazeboSystem" type="system">
                  <hardware>
                      <plugin>gazebo_ros2_control/GazeboSystem</plugin>
                  </hardware>
                  <joint name="left_wheel_joint">
                  <!-- 命令接口 -->
                      <command_interface name="velocity">
                          <param name="min">-1</param>
                          <param name="max">1</param>
                      </command_interface>
                      <command_interface name="effort">
                          <param name="min">-0.1</param>
                          <param name="max">0.1</param>
                      </command_interface>
                      <!-- 状态接口 -->
                      <state_interface name="position" />
                      <state_interface name="velocity" />
                      <state_interface name="effort" />
                  </joint>
                  <joint name="right_wheel_joint">
                      <command_interface name="velocity">
                          <param name="min">-1</param>
                          <param name="max">1</param>
                      </command_interface>
                      <command_interface name="effort">
                          <param name="min">-0.1</param>
                          <param name="max">0.1</param>
                      </command_interface>
                      <state_interface name="position" />
                      <state_interface name="velocity" />
                      <state_interface name="effort" />
                  </joint>
              </ros2_control>
              <gazebo>
                  <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
                      <robot_namespace>/robot2</robot_namespace>
                      <parameters>$(find car_description)/config/track_car_ros2_controller.yaml</parameters>
                       <ros>
                          <remapping>/track_car_diff_drive_controller/odom:=/odom</remapping>
                          <remapping>/track_car_diff_drive_controller/cmd_vel_unstamped:=/cmd_vel</remapping>
                       </ros>
                  </plugin>
              </gazebo>
          </xacro:macro>
      </robot>
      

      param参数文件:

      controller_manager:
        ros__parameters:
          update_rate: 1000 # Hz
          use_sim_time: true
          track_car_joint_state_broadcaster:
            type: joint_state_broadcaster/JointStateBroadcaster
          track_car_effort_controller:
            type: effort_controllers/JointGroupEffortController
          track_car_diff_drive_controller:
            type: diff_drive_controller/DiffDriveController
      
      track_car_effort_controller:
        ros__parameters:
          joints:
            - left_wheel_joint
            - right_wheel_joint
          command_interfaces:
            - effort
          state_interfaces:
            - position
            - velocity
            - effort
      
      track_car_diff_drive_controller:
        ros__parameters:
          left_wheel_names: ["left_wheel_joint"]
          right_wheel_names: ["right_wheel_joint"]
      
          wheel_separation: 0.20
          #wheels_per_side: 1  # actually 2, but both are controlled by 1 signal
          wheel_radius: 0.05
      
          wheel_separation_multiplier: 1.0
          left_wheel_radius_multiplier: 1.0
          right_wheel_radius_multiplier: 1.0
      
          publish_rate: 50.0
          odom_frame_id: odom
          base_frame_id: base_footprint
          pose_covariance_diagonal : [0.001, 0.001, 0.0, 0.0, 0.0, 0.01]
          twist_covariance_diagonal: [0.001, 0.0, 0.0, 0.0, 0.0, 0.01]
      
          open_loop: true
          enable_odom_tf: true
      
          cmd_vel_timeout: 0.5
          #publish_limited_velocity: true
          use_stamped_vel: false
          #velocity_rolling_window_size: 10
      
      
      1 条回复 最后回复 回复 引用 0
      • 2
        2118561423 @sdcdacqdiuhoiwgaciba
        最后由 编辑

        @sdcdacqdiuhoiwgaciba 目前看来解决了,在参数文件中加入对应的命名空间就行,例如

        /robot1/controller_manager:
          ros__parameters:
            update_rate: 1000 # Hz
            use_sim_time: true
            track_car_joint_state_broadcaster:
              type: joint_state_broadcaster/JointStateBroadcaster
            track_car_effort_controller:
              type: effort_controllers/JointGroupEffortController
            track_car_diff_drive_controller:
              type: diff_drive_controller/DiffDriveController
        
        /robot1/track_car_effort_controller:
          ros__parameters:
            joints:
              - left_wheel_joint
              - right_wheel_joint
            command_interfaces:
              - effort
            state_interfaces:
              - position
              - velocity
              - effort
        
        /robot1/track_car_diff_drive_controller:
          ros__parameters:
            left_wheel_names: ["left_wheel_joint"]
            right_wheel_names: ["right_wheel_joint"]
        
            wheel_separation: 0.20
            #wheels_per_side: 1  # actually 2, but both are controlled by 1 signal
            wheel_radius: 0.05
        
            wheel_separation_multiplier: 1.0
            left_wheel_radius_multiplier: 1.0
            right_wheel_radius_multiplier: 1.0
        
            publish_rate: 50.0
            odom_frame_id: odom
            base_frame_id: base_footprint
            pose_covariance_diagonal : [0.001, 0.001, 0.0, 0.0, 0.0, 0.01]
            twist_covariance_diagonal: [0.001, 0.0, 0.0, 0.0, 0.0, 0.01]
        
            open_loop: true
            enable_odom_tf: true
            cmd_vel_timeout: 0.5
            #publish_limited_velocity: true
            use_stamped_vel: false
            #velocity_rolling_window_size: 10
        
        S 2 条回复 最后回复 回复 引用 1
        • S
          sdcdacqdiuhoiwgaciba
          最后由 编辑

          你好,请问解决了吗,我也遇到了一样的问题

          2 1 条回复 最后回复 回复 引用 0
          • 2
            2118561423 @sdcdacqdiuhoiwgaciba
            最后由 编辑

            @sdcdacqdiuhoiwgaciba 目前看来解决了,在参数文件中加入对应的命名空间就行,例如

            /robot1/controller_manager:
              ros__parameters:
                update_rate: 1000 # Hz
                use_sim_time: true
                track_car_joint_state_broadcaster:
                  type: joint_state_broadcaster/JointStateBroadcaster
                track_car_effort_controller:
                  type: effort_controllers/JointGroupEffortController
                track_car_diff_drive_controller:
                  type: diff_drive_controller/DiffDriveController
            
            /robot1/track_car_effort_controller:
              ros__parameters:
                joints:
                  - left_wheel_joint
                  - right_wheel_joint
                command_interfaces:
                  - effort
                state_interfaces:
                  - position
                  - velocity
                  - effort
            
            /robot1/track_car_diff_drive_controller:
              ros__parameters:
                left_wheel_names: ["left_wheel_joint"]
                right_wheel_names: ["right_wheel_joint"]
            
                wheel_separation: 0.20
                #wheels_per_side: 1  # actually 2, but both are controlled by 1 signal
                wheel_radius: 0.05
            
                wheel_separation_multiplier: 1.0
                left_wheel_radius_multiplier: 1.0
                right_wheel_radius_multiplier: 1.0
            
                publish_rate: 50.0
                odom_frame_id: odom
                base_frame_id: base_footprint
                pose_covariance_diagonal : [0.001, 0.001, 0.0, 0.0, 0.0, 0.01]
                twist_covariance_diagonal: [0.001, 0.0, 0.0, 0.0, 0.0, 0.01]
            
                open_loop: true
                enable_odom_tf: true
                cmd_vel_timeout: 0.5
                #publish_limited_velocity: true
                use_stamped_vel: false
                #velocity_rolling_window_size: 10
            
            S 2 条回复 最后回复 回复 引用 1
            • S
              sdcdacqdiuhoiwgaciba @2118561423
              最后由 编辑

              @2118561423 谢谢谢谢,我也解决了

              1 条回复 最后回复 回复 引用 0
              • ,2 2118561423 将这个主题标记为已解决
              • S
                sdcdacqdiuhoiwgaciba @2118561423
                最后由 编辑

                @2118561423 但是我出现了一个问题,每当编译的时候我的命名空间会自动被截断,如从

                /fishbot/controller_manager:
                  ros__parameters:
                    update_rate: 100  # Hz
                    use_sim_time: true
                    fishbot_joint_state_broadcaster:
                      type: joint_state_broadcaster/JointStateBroadcaster
                      use_sim_time: true
                    fishbot_effort_controller:
                      type: effort_controllers/JointGroupEffortController
                    fishbot_diff_drive_controller:
                      type: diff_drive_controller/DiffDriveController
                

                变成

                controller_manager:
                  ros__parameters:
                    update_rate: 100  # Hz
                    use_sim_time: true
                    fishbot_joint_state_broadcaster:
                      type: joint_state_broadcaster/JointStateBroadcaster
                      use_sim_time: true
                    fishbot_effort_controller:
                      type: effort_controllers/JointGroupEffortController
                    fishbot_diff_drive_controller:
                      type: diff_drive_controller/DiffDriveController
                

                请问这个问题您遇到过吗

                2 1 条回复 最后回复 回复 引用 0
                • 2
                  2118561423 @sdcdacqdiuhoiwgaciba
                  最后由 编辑

                  @sdcdacqdiuhoiwgaciba 你这个是不是在share目录下修改的文件,应该要在src目录下修改,或者是修改后没有保存就进行了编译?

                  S 1 条回复 最后回复 回复 引用 0
                  • S
                    sdcdacqdiuhoiwgaciba @2118561423
                    最后由 编辑

                    @2118561423 感谢感谢 已经解决了

                    1 条回复 最后回复 回复 引用 0
                    • 第一个帖子
                      最后一个帖子
                    皖ICP备16016415号-7
                    Powered by NodeBB | 鱼香ROS