ros-controls / gazebo_ros2_control

Wrappers, tools and additional API's for using ros2_control with Gazebo Classic
Apache License 2.0
194 stars 125 forks source link

Loading Controller Crashes Gazebo Server #67

Open 808brick opened 3 years ago

808brick commented 3 years ago

I am trying to utilize the gazebo_ros2_control package for controlling the position of a revolute joint from a URDF file. However following along with the package README (which thankfully is better than most ROS2 pkg README's, so thank you for that), it seems something in the ros2_control tag is causing gazebo to crash, as the adding the libgazebo_ros2_control.so file with the gazebo tags alone without the ros2_control tags does not crash gazebo.

My URDF file spawned in fine prior to adding the following to the bottom within the <robot> tags. I configured it as follows:

<ros2_control name="GazeboSystem" type="system">
    <hardware>
      <plugin>gazebo_ros2_control/GazeboSystem</plugin>
    </hardware>
    <joint name="camera_pole_joint">
      <command_interface name="position">
        <param name="min">-3.14159</param>
        <param name="max">3.14159</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_param>robot_description</robot_param>
      <robot_param_node>robot_state_publisher</robot_param_node>
      <parameters>$(find ros2_sim_pkg)/config/cam_bot.yaml</parameters>
    </plugin>
  </gazebo>

With my config file having:

controller_manager:
  ros__parameters:
    update_rate: 50  # Hz

    joint_trajectory_controller:
      type: joint_trajectory_controller/JointTrajectoryController

    joint_state_controller:
      type: joint_state_controller/JointStateController

joint_trajectory_controller:
  ros__parameters:
    joints:
      - camera_pole_joint
    interface_name: position

Basically I am trying to create a position controller to interact with my joint called camera_pole_joint

OS: Ubuntu 20.04 ROS Distro: Foxy (apt install)

Output of terminal running gazebo:

ray@ubuntu:~/Workspaces/udemy_ros2_ws$ ros2 launch gazebo_ros gazebo.launch.py 
[INFO] [launch]: All log files can be found below /home/ray/.ros/log/2021-03-31-00-28-41-487954-ubuntu-21664
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [gzserver-1]: process started with pid [21666]
[INFO] [gzclient   -2]: process started with pid [21669]
[gzserver-1] [INFO] [1617186529.478072601] [camera_controller]: Publishing camera info to [/camera1/camera_info]
[gzserver-1] [INFO] [1617186529.587212547] [gazebo_ros2_control]: Loading gazebo_ros2_control plugin
[gzserver-1] [INFO] [1617186529.600678750] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in namespace: /
[gzserver-1] [INFO] [1617186529.603022856] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in ros 2 node: gazebo_ros2_control
[gzserver-1] [INFO] [1617186529.622931749] [gazebo_ros2_control]: connected to service!! robot_state_publisher
[gzserver-1] [INFO] [1617186529.624571891] [gazebo_ros2_control]: Recieved urdf from param server, parsing...
[gzserver-1] [INFO] [1617186529.641574313] [gazebo_ros2_control]: Loading joint: camera_pole_joint
[gzserver-1] [INFO] [1617186529.642266984] [gazebo_ros2_control]:   Command:
[gzserver-1] [INFO] [1617186529.642590928] [gazebo_ros2_control]:        position
[gzserver-1] [INFO] [1617186529.642890565] [gazebo_ros2_control]:   State:
[gzserver-1] [INFO] [1617186529.643170214] [gazebo_ros2_control]:        position
[gzserver-1] [INFO] [1617186529.643638167] [gazebo_ros2_control]:        velocity
[gzserver-1] [INFO] [1617186529.644139749] [gazebo_ros2_control]:        effort
[gzserver-1] [INFO] [1617186529.646519580] [gazebo_ros2_control]: Loading controller_manager
[gzserver-1] terminate called without an active exception
[gzserver-1] Aborted (core dumped)
[ERROR] [gzserver-1]: process has died [pid 21666, exit code 134, cmd 'gzserver                                                                    -s libgazebo_ros_init.so   -s libgazebo_ros_factory.so       '].

Terminal output of spawning in the URDF does not seem to throw any errors:

ay@ubuntu:~/Workspaces/udemy_ros2_ws$ ros2 launch ros2_sim_pkg cam_bot_world.launch.py 
[INFO] [launch]: All log files can be found below /home/ray/.ros/log/2021-03-31-00-28-47-357037-ubuntu-21761
[INFO] [launch]: Default logging verbosity is set to INFO
urdf_file_name : urdf/camera_bot.xacro
[INFO] [robot_state_publisher-1]: process started with pid [21766]
[INFO] [spawn_entity.py-2]: process started with pid [21768]
[robot_state_publisher-1] [WARN] [1617186527.537782915] [robot_state_publisher]: No robot_description parameter, but command-line argument available.  Assuming argument is name of URDF file.  This backwards compatibility fallback will be removed in the future.
[robot_state_publisher-1] Parsing robot urdf xml string.
[robot_state_publisher-1] Link base had 5 children
[robot_state_publisher-1] Link camera_pole had 1 children
[robot_state_publisher-1] Link camera_link had 0 children
[robot_state_publisher-1] Link wheel_BL had 0 children
[robot_state_publisher-1] Link wheel_BR had 0 children
[robot_state_publisher-1] Link wheel_FL had 0 children
[robot_state_publisher-1] Link wheel_FR had 0 children
[robot_state_publisher-1] [INFO] [1617186527.550467733] [robot_state_publisher]: got segment base
[robot_state_publisher-1] [INFO] [1617186527.550830406] [robot_state_publisher]: got segment camera_link
[robot_state_publisher-1] [INFO] [1617186527.551082150] [robot_state_publisher]: got segment camera_pole
[robot_state_publisher-1] [INFO] [1617186527.551316623] [robot_state_publisher]: got segment robot_footprint
[robot_state_publisher-1] [INFO] [1617186527.552871455] [robot_state_publisher]: got segment wheel_BL
[robot_state_publisher-1] [INFO] [1617186527.553206308] [robot_state_publisher]: got segment wheel_BR
[robot_state_publisher-1] [INFO] [1617186527.553421784] [robot_state_publisher]: got segment wheel_FL
[robot_state_publisher-1] [INFO] [1617186527.553628807] [robot_state_publisher]: got segment wheel_FR
[spawn_entity.py-2] [INFO] [1617186528.166923053] [urdf_spawner]: Spawn Entity started
[spawn_entity.py-2] [INFO] [1617186528.167815622] [urdf_spawner]: Loading entity published on topic /robot_description
[spawn_entity.py-2] [INFO] [1617186528.170817956] [urdf_spawner]: Waiting for entity xml on /robot_description
[spawn_entity.py-2] [INFO] [1617186528.263362879] [urdf_spawner]: Waiting for service /spawn_entity, timeout = 5
[spawn_entity.py-2] [INFO] [1617186528.264286665] [urdf_spawner]: Waiting for service /spawn_entity
[spawn_entity.py-2] [INFO] [1617186528.273687918] [urdf_spawner]: Calling service /spawn_entity
[spawn_entity.py-2] [INFO] [1617186528.582535103] [urdf_spawner]: Spawn status: SpawnEntity: Successfully spawned entity [cam_bot]
[INFO] [spawn_entity.py-2]: process has finished cleanly [pid 21768]

Here is my launch file in case it is of use:

import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, ExecuteProcess
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch.launch_description_sources import PythonLaunchDescriptionSource

def generate_launch_description():

  use_sim_time = LaunchConfiguration('use_sim_time', default='false')
  urdf_file_name = 'urdf/camera_bot.xacro'

  print("urdf_file_name : {}".format(urdf_file_name))

  urdf = os.path.join(
      get_package_share_directory('ros2_sim_pkg'),
      urdf_file_name)

  return LaunchDescription([

        DeclareLaunchArgument(
            'use_sim_time',
            default_value='false',
            description='Use simulation (Gazebo) clock if true'),

        # ExecuteProcess(
        #     cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_factory.so'],
        #     output='screen'),

        Node(
            package='robot_state_publisher',
            executable='robot_state_publisher',
            name='robot_state_publisher',
            output='screen',
            parameters=[{'use_sim_time': use_sim_time}],
            arguments=[urdf]),

        # Node(
        #     package='joint_state_publisher',
        #     executable='joint_state_publisher',
        #     name='joint_state_publisher',
        #     output='screen',
        #     parameters=[{'use_sim_time': use_sim_time}]
        #     ),

        Node(
            package='gazebo_ros',
            executable='spawn_entity.py',
            name='urdf_spawner',
            output='screen',
            arguments=["-topic", "/robot_description", "-entity", "cam_bot"])
  ])

I currently have the joint state publisher and auto launching gazebo commented out, as I was trying to make sure those were not interfering with the libgazebo_ros2_control.so.

808brick commented 3 years ago

As an update, I have tried to recreate my launch file to better represent that in the examples, however I am running into issues launching it, as I get the following error: ImportError: cannot import name 'GazeboRosPaths' from 'scripts' (/home/ray/Workspaces/udemy_ros2_ws/install/udemy_ros2_pkg/lib/python3.8/site-packages/scripts/__init__.py)

The launch file is as follows:

# Copyright 2020 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
#     http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler
from launch.event_handlers import OnProcessExit
from launch.launch_description_sources import PythonLaunchDescriptionSource

from launch_ros.actions import Node

import xacro

def generate_launch_description():
    gazebo = IncludeLaunchDescription(
                PythonLaunchDescriptionSource([os.path.join(
                    get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']),
             )

    # gazebo_ros2_control_demos_path = os.path.join(
    #     get_package_share_directory('gazebo_ros2_control_demos'))
    #
    # xacro_file = os.path.join(gazebo_ros2_control_demos_path,
    #                           'urdf',
    #                           'test_cart_position.xacro.urdf')
    #
    # doc = xacro.parse(open(xacro_file))
    # xacro.process_doc(doc)

    urdf_file_name = 'urdf/camera_bot.xacro'

    urdf = os.path.join(
        get_package_share_directory('ros2_sim_pkg'),
        urdf_file_name)

    params = {'robot_description': urdf}

    node_robot_state_publisher = Node(
        package='robot_state_publisher',
        executable='robot_state_publisher',
        output='screen',
        parameters=[params]
    )

    spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',
                        arguments=['-topic', 'robot_description',
                                   '-entity', 'cartpole'],
                        output='screen')

    load_joint_state_controller = ExecuteProcess(
        cmd=['ros2', 'control', 'load_start_controller', 'joint_state_controller'],
        output='screen'
    )

    load_joint_trajectory_controller = ExecuteProcess(
        cmd=['ros2', 'control', 'load_start_controller', 'joint_trajectory_controller'],
        output='screen'
    )

    return LaunchDescription([
        RegisterEventHandler(
            event_handler=OnProcessExit(
                target_action=spawn_entity,
                on_exit=[load_joint_state_controller],
            )
        ),
        RegisterEventHandler(
            event_handler=OnProcessExit(
                target_action=load_joint_state_controller,
                on_exit=[load_joint_trajectory_controller],
            )
        ),
        gazebo,
        node_robot_state_publisher,
        spawn_entity,
    ])

and the terminal output:

ay@ubuntu:~/Workspaces/udemy_ros2_ws$ ros2 launch ros2_sim_pkg gazebo_ros2_control_test.launch.py 
[INFO] [launch]: All log files can be found below /home/ray/.ros/log/2021-03-31-01-20-49-067692-ubuntu-26382
[INFO] [launch]: Default logging verbosity is set to INFO
Task exception was never retrieved
future: <Task finished name='Task-2' coro=<LaunchService._process_one_event() done, defined at /opt/ros/foxy/lib/python3.8/site-packages/launch/launch_service.py:271> exception=ImportError("cannot import name 'GazeboRosPaths' from 'scripts' (/home/ray/Workspaces/udemy_ros2_ws/install/udemy_ros2_pkg/lib/python3.8/site-packages/scripts/__init__.py)")>
Traceback (most recent call last):
  File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_service.py", line 273, in _process_one_event
    await self.__process_event(next_event)
  File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_service.py", line 293, in __process_event
    visit_all_entities_and_collect_futures(entity, self.__context))
  File "/opt/ros/foxy/lib/python3.8/site-packages/launch/utilities/visit_all_entities_and_collect_futures_impl.py", line 45, in visit_all_entities_and_collect_futures
    futures_to_return += visit_all_entities_and_collect_futures(sub_entity, context)
  File "/opt/ros/foxy/lib/python3.8/site-packages/launch/utilities/visit_all_entities_and_collect_futures_impl.py", line 45, in visit_all_entities_and_collect_futures
    futures_to_return += visit_all_entities_and_collect_futures(sub_entity, context)
  File "/opt/ros/foxy/lib/python3.8/site-packages/launch/utilities/visit_all_entities_and_collect_futures_impl.py", line 45, in visit_all_entities_and_collect_futures
    futures_to_return += visit_all_entities_and_collect_futures(sub_entity, context)
  [Previous line repeated 3 more times]
  File "/opt/ros/foxy/lib/python3.8/site-packages/launch/utilities/visit_all_entities_and_collect_futures_impl.py", line 38, in visit_all_entities_and_collect_futures
    sub_entities = entity.visit(context)
  File "/opt/ros/foxy/lib/python3.8/site-packages/launch/action.py", line 108, in visit
    return self.execute(context)
  File "/opt/ros/foxy/lib/python3.8/site-packages/launch/actions/include_launch_description.py", line 125, in execute
    launch_description = self.__launch_description_source.get_launch_description(context)
  File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_description_source.py", line 84, in get_launch_description
    self._get_launch_description(self.__expanded_location)
  File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_description_sources/python_launch_description_source.py", line 51, in _get_launch_description
    return get_launch_description_from_python_launch_file(location)
  File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_description_sources/python_launch_file_utilities.py", line 62, in get_launch_description_from_python_launch_file
    launch_file_module = load_python_launch_file_as_module(python_launch_file_path)
  File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_description_sources/python_launch_file_utilities.py", line 37, in load_python_launch_file_as_module
    loader.exec_module(mod)
  File "<frozen importlib._bootstrap_external>", line 783, in exec_module
  File "<frozen importlib._bootstrap>", line 219, in _call_with_frames_removed
  File "/opt/ros/foxy/share/gazebo_ros/launch/gzserver.launch.py", line 28, in <module>
    from scripts import GazeboRosPaths
ImportError: cannot import name 'GazeboRosPaths' from 'scripts' (/home/ray/Workspaces/udemy_ros2_ws/install/udemy_ros2_pkg/lib/python3.8/site-packages/scripts/__init__.py)
Schulze18 commented 3 years ago

Hello, it seems a problem in your gzserver launch file. Is the "gzserver" launch file working fine in your system? Just try: ros2 launch gazebo_ros gzserver.launch.py

If not, try to reinstall gazebo11 and gazebo_ros_pkgs for ROS2.

Thieso commented 3 years ago

Hi I have the same error (at least the initial one) where loading the controller manager crashes gazebo. There are also no error messages for me except the final one that the gzserver has died. Running ros2 launch gazebo_ros gzserver.launch.py works without any problems.

Schulze18 commented 3 years ago

Hi @Thieso, I am not sure, but I think the initial problem was that the URDF has been passed as an argument to robot_state_publisher:

Node(
     package='robot_state_publisher',
     executable='robot_state_publisher',
     name='robot_state_publisher',
     output='screen',
     parameters=[{'use_sim_time': use_sim_time}],
     arguments=[urdf]), 

but it should be given as a parameter (what @808brick already did in the second post):

params = {'robot_description': urdf}
Node(
     package='robot_state_publisher',
     executable='robot_state_publisher',
     name='robot_state_publisher',
     output='screen',
      parameters=[params]
Schulze18 commented 3 years ago

@808brick It seems that your ros2 launch file is looking only for your workspace scripts folder, did you source the ros2 distro? source /opt/ros/foxy/setup.bash

Thieso commented 3 years ago

Hi @Schulze18

I am already passing it as an argument so that does sadly not solve the problem.

Thieso commented 3 years ago

So further information on this,

I ran gazebo with gazebo --verbose -s libgazebo_ros_init.so -s libgazebo_ros_factory.so which gives me the error [Err] [Model.cc:1137] Exception occured in the Load function of plugin with name[gazebo_ros2_control] and filename[libgazebo_ros2_control.so]. This plugin will not run.

Sadly this is also not helpful for me but maybe you can see some problem there. Any hints are appreciated

My launch file is

#!/usr/bin/env python3

import os
import sys

from ament_index_python.packages import get_package_share_directory

import launch
from launch import LaunchDescription, LaunchService
from launch.actions import IncludeLaunchDescription, RegisterEventHandler, ExecuteProcess
from launch_ros.actions import Node
from launch.event_handlers import OnProcessExit
from launch.launch_description_sources import PythonLaunchDescriptionSource
import xacro

def generate_launch_description():
    # Load the URDF into a parameter
    bringup_dir = get_package_share_directory('scanbot_description')
    urdf_path = os.path.join(bringup_dir, 'scanbot_system.urdf.xacro')
    urdf = xacro.process_file(urdf_path).toxml()

    rviz_config_file = os.path.join(
        get_package_share_directory('scanbot_description'),
        'scanbot.rviz'
        )

    gazebo_node = launch.actions.ExecuteProcess(
        cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'],
        output='screen'
    )
    # gazebo_node = IncludeLaunchDescription(
        # PythonLaunchDescriptionSource([os.path.join(
            # get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']),
    # )

    spawn_entity_node = Node(package='gazebo_ros', executable='spawn_entity.py',
            arguments=['-entity', 'scanbot', '-topic', 'robot_description'],
            output='screen')

    joint_state_publisher_node = Node(
            name='joint_state_publisher',
            package='joint_state_publisher',
            executable='joint_state_publisher',
            output='screen'
    )
    robot_state_publisher_node = Node(
            name='robot_state_publisher',
            package='robot_state_publisher',
            executable='robot_state_publisher',
            parameters=[{'robot_description': urdf}],
            output='screen'
    )
    rviz_node = Node(
            package='rviz2',
            name='rviz2',
            executable='rviz2',
            output='screen',
            arguments=['-d', rviz_config_file],
    )

    return LaunchDescription([
        joint_state_publisher_node,
        rviz_node,
        gazebo_node,
        robot_state_publisher_node,
        spawn_entity_node,
    ])

def main(argv=sys.argv[1:]):
    """Run lifecycle nodes via launch."""
    ld = generate_launch_description()
    ls = LaunchService(argv=argv)
    ls.include_launch_description(ld)
    return ls.run()

if __name__ == '__main__':
    main()
808brick commented 3 years ago

I apologize for being inactive on this thread, was a busy week.

@Schulze18 my terminals are automatically sourced to ROS Foxy via .bashrc (so the line source /opt/ros/foxy/setup.bash is at the end of the .bashrc file, which is how my ROS commands are able to run) then I go into the workspace, source it and try to launch.

I am not on the system in question right now, but I will try to do more experimenting this weekend with the comments you have given and report back. Thanks for all the feedback and help.

newcanopies commented 3 years ago

hi @Schulze18

is it even possible to launch Gazebo with both plugins as suggested above https://github.com/ros-simulation/gazebo_ros2_control/issues/67#issuecomment-816849356 gazebo --verbose -s libgazebo_ros_init.so -s libgazebo_ros_factory.so

MXS13 commented 2 years ago

Hi @Schulze18, hi @808brick Was this issue resolved? I still have the issue on Foxy Branch with Gazebo-11 and would like to know if there's a workaround.

image

image

Somehow it seems to function out of the box when looking at eg. https://www.youtube.com/watch?v=xBhYHOSxMOk.

My controller config:

` controller_manager: ros__parameters: update_rate: 100 # Hz

joint_trajectory_controller_spj:
  type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster_spj:
  type: joint_state_broadcaster/JointStateBroadcaster

joint_trajectory_controller_slj:
  type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster_slj:
  type: joint_state_broadcaster/JointStateBroadcaster

joint_trajectory_controller_ej:
  type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster_ej:
  type: joint_state_broadcaster/JointStateBroadcaster

joint_trajectory_controller_w1j:
  type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster_w1j:
  type: joint_state_broadcaster/JointStateBroadcaster

joint_trajectory_controller_w2j:
  type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster_w2j:
  type: joint_state_broadcaster/JointStateBroadcaster

joint_trajectory_controller_w3j:
  type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster_w3j:
  type: joint_state_broadcaster/JointStateBroadcaster

joint_trajectory_controller_spj: ros__parameters: joints:

joint_trajectory_controller_slj: ros__parameters: joints:

joint_trajectory_controller_ej: ros__parameters: joints:

joint_trajectory_controller_w1j: ros__parameters: joints:

joint_trajectory_controller_w2j: ros__parameters: joints:

joint_trajectory_controller_w3j: ros__parameters: joints:

And my xacro:

`<?xml version="1.0"?>

gazebo_ros2_control/GazeboSystem ${shoulder_pan_lower_limit} ${shoulder_pan_upper_limit} ${shoulder_lift_lower_limit} ${shoulder_lift_upper_limit} ${elbow_joint_lower_limit} ${elbow_joint_upper_limit} ${wrist_1_lower_limit} ${wrist_1_upper_limit} ${wrist_2_lower_limit} ${wrist_2_upper_limit} ${wrist_3_lower_limit} ${wrist_3_upper_limit} $(find modprof_bringup)/config/ur_joint_controller_angle.yaml --> `
MXS13 commented 2 years ago

Okay, it was my bad. The robot I wanted to control had already ros2_control tags. I added xacro conditionals to determine real HW, fake HW or Gazebo. Problem solved.

bmagyar commented 2 years ago

Please don't expect many things to be fixed in Foxy. We'd appreciate if you could give us feedback about what's on rolling ATM as it will be the baseline for the Humble release, thanks!

On Wed, 11 May 2022, 10:58 MXS13, @.***> wrote:

Okay, it was my bad. The robot I wanted to control had already ros2_control tags. I added xacro conditionals to determine real HW, fake HW or Gazebo. Problem solved.

— Reply to this email directly, view it on GitHub https://github.com/ros-simulation/gazebo_ros2_control/issues/67#issuecomment-1123477987, or unsubscribe https://github.com/notifications/unsubscribe-auth/AA24PYPICHK2KKLNPKR3SZ3VJOADFANCNFSM42ELBKMQ . You are receiving this because you are subscribed to this thread.Message ID: @.***>

Flamethr0wer commented 1 month ago

Okay, it was my bad. The robot I wanted to control had already ros2_control tags. I added xacro conditionals to determine real HW, fake HW or Gazebo. Problem solved.

@MXS13 could you please expand on this? I'm having the same issue.

christophfroehlich commented 1 month ago

probably something like we did in our demos.

Flamethr0wer commented 1 month ago

How does that prevent Gazebo from crashing?