Following along with the ros2_control demonstration from ROSCon 2022, I am attempting to run step 5, simulation in Gazebo. The system successfully responds to Joint Trajectory commands, both through publishing a goal to the action server, as well as using the rqt_joint_trajectory_controller package, but the system does not seem to be operational for Gazebo. However, I have gotten the ROSCon 2022 Controlko robot package to successfully load its model in Gazebo, so the issue appears to be with my URDF.
Launching Gazebo Classic is done with the following command:
ros2 launch linear_slider_bringup linear_slider_sim_gazebo.launch.py sim_gazebo_classic:=true
I receive the following feedback after launch:
[INFO] [robot_state_publisher-1]: process started with pid [84675]
[INFO] [gzserver-2]: process started with pid [84677]
[INFO] [gzclient-3]: process started with pid [84679]
[INFO] [spawn_entity.py-4]: process started with pid [84681]
[robot_state_publisher-1] [INFO] [1710962513.742943224] [robot_state_publisher]: got segment base
[robot_state_publisher-1] [INFO] [1710962513.743020949] [robot_state_publisher]: got segment base_link
[robot_state_publisher-1] [INFO] [1710962513.743025336] [robot_state_publisher]: got segment flange
[robot_state_publisher-1] [INFO] [1710962513.743027819] [robot_state_publisher]: got segment moving_base
[robot_state_publisher-1] [INFO] [1710962513.743030104] [robot_state_publisher]: got segment tool0
[robot_state_publisher-1] [INFO] [1710962513.743032301] [robot_state_publisher]: got segment world
[spawn_entity.py-4] [INFO] [1710962513.982791564] [spawn_linear_slider]: Spawn Entity started
[spawn_entity.py-4] [INFO] [1710962513.982982280] [spawn_linear_slider]: Loading entity published on topic robot_description
[spawn_entity.py-4] /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/qos.py:307: UserWarning: DurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL is deprecated. Use DurabilityPolicy.TRANSIENT_LOCAL instead.
[spawn_entity.py-4] warnings.warn(
[spawn_entity.py-4] [INFO] [1710962513.984899469] [spawn_linear_slider]: Waiting for entity xml on robot_description
[spawn_entity.py-4] [INFO] [1710962514.111381248] [spawn_linear_slider]: Waiting for service /spawn_entity, timeout = 30
[spawn_entity.py-4] [INFO] [1710962514.111706169] [spawn_linear_slider]: Waiting for service /spawn_entity
[spawn_entity.py-4] [INFO] [1710962514.618182119] [spawn_linear_slider]: Calling service /spawn_entity
[spawn_entity.py-4] [INFO] [1710962514.801764666] [spawn_linear_slider]: Spawn status: SpawnEntity: Successfully spawned entity [linear_slider]
[gzserver-2] [INFO] [1710962514.816576069] [gazebo_ros2_control]: Loading gazebo_ros2_control plugin
[gzserver-2] [INFO] [1710962514.817868509] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in namespace: /
[gzserver-2] [INFO] [1710962514.817971930] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in ros 2 node: gazebo_ros2_control
[gzserver-2] [INFO] [1710962514.818000582] [gazebo_ros2_control]: Loading parameter files /home/user/ros2_ws/install/linear_slider_bringup/share/linear_slider_bringup/config/linear_slider_controllers.yaml
[gzserver-2] [INFO] [1710962514.819166614] [gazebo_ros2_control]: connected to service!! robot_state_publisher
[gzserver-2] [INFO] [1710962514.819530996] [gazebo_ros2_control]: Received urdf from param server, parsing...
[gzserver-2] [WARN] [1710962514.824922049] [gazebo_ros2_control]: Skipping joint in the URDF named 'joint1' which is not in the gazebo model.
[gzserver-2] [WARN] [1710962514.824944559] [gazebo_ros2_control]: Skipping sensor in the URDF named 'lim_switch_neg' which is not in the gazebo model.
[gzserver-2] [WARN] [1710962514.824972376] [gazebo_ros2_control]: Skipping sensor in the URDF named 'lim_switch_pos' which is not in the gazebo model.
[gzserver-2] [INFO] [1710962514.824985514] [resource_manager]: Initialize hardware 'linear_slider_ros2_control'
[gzserver-2] [INFO] [1710962514.825043669] [resource_manager]: Successful initialization of hardware 'linear_slider_ros2_control'
[gzserver-2] [INFO] [1710962514.825076663] [resource_manager]: 'configure' hardware 'linear_slider_ros2_control'
[gzserver-2] [INFO] [1710962514.825081268] [resource_manager]: Successful 'configure' of hardware 'linear_slider_ros2_control'
[gzserver-2] [INFO] [1710962514.825083439] [resource_manager]: 'activate' hardware 'linear_slider_ros2_control'
[gzserver-2] [INFO] [1710962514.825086273] [resource_manager]: Successful 'activate' of hardware 'linear_slider_ros2_control'
[gzserver-2] [INFO] [1710962514.825118472] [gazebo_ros2_control]: Loading controller_manager
[gzserver-2] [WARN] [1710962514.834426588] [gazebo_ros2_control]: Desired controller update period (0.01 s) is slower than the gazebo simulation period (0.001 s).
[gzserver-2] [INFO] [1710962514.834576721] [gazebo_ros2_control]: Loaded gazebo_ros2_control.
[INFO] [spawn_entity.py-4]: process has finished cleanly [pid 84681]
[INFO] [spawner-5]: process started with pid [84822]
[gzserver-2] [INFO] [1710962515.659723466] [controller_manager]: Loading controller 'joint_state_broadcaster'
[spawner-5] [INFO] [1710962515.676665510] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[gzserver-2] [INFO] [1710962515.677689805] [controller_manager]: Configuring controller 'joint_state_broadcaster'
[gzserver-2] [INFO] [1710962515.677986019] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[gzserver-2] [ERROR] [1710962515.705082392] [joint_state_broadcaster]: None of requested interfaces exist. Controller will not run.
[gzserver-2] [WARN] [1710962515.705154140] [joint_state_broadcaster]: Error occurred while doing error handling.
[gzserver-2] [ERROR] [1710962515.705205212] [controller_manager]: After activation, controller 'joint_state_broadcaster' is in state 'unconfigured' (1), expected 'active' (3).
[spawner-5] [INFO] [1710962515.715562559] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[INFO] [spawner-5]: process has finished cleanly [pid 84822]
[INFO] [rviz2-6]: process started with pid [84938]
[rviz2-6] Warning: Ignoring XDG_SESSION_TYPE=wayland on Gnome. Use QT_QPA_PLATFORM=wayland to run on Wayland anyway.
[rviz2-6] [INFO] [1710962516.049478468] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-6] [INFO] [1710962516.049587327] [rviz2]: OpenGl version: 4.6 (GLSL 4.6)
[rviz2-6] [INFO] [1710962516.065913352] [rviz2]: Stereo is NOT SUPPORTED
[gzserver-2] [INFO] [1710963128.379637264] [controller_manager]: Loading controller 'joint_trajectory_controller'
[spawner-6] [INFO] [1710963128.402799383] [spawner_joint_trajectory_controller]: Loaded joint_trajectory_controller
[gzserver-2] [INFO] [1710963128.484252881] [controller_manager]: Configuring controller 'joint_trajectory_controller'
[gzserver-2] [INFO] [1710963128.484424061] [joint_trajectory_controller]: No specific joint names are used for command interfaces. Using 'joints' parameter.
[gzserver-2] [INFO] [1710963128.484455242] [joint_trajectory_controller]: Command interfaces are [position] and state interfaces are [position].
[gzserver-2] [INFO] [1710963128.484473404] [joint_trajectory_controller]: Using 'splines' interpolation method.
[gzserver-2] [INFO] [1710963128.485896343] [joint_trajectory_controller]: Controller state will be published at 50.00 Hz.
[gzserver-2] [INFO] [1710963128.487285184] [joint_trajectory_controller]: Action status changes will be monitored at 21.00 Hz.
[gzserver-2] [ERROR] [1710963128.503798555] [resource_manager]: Not acceptable command interfaces combination:
[gzserver-2] Start interfaces:
[gzserver-2] [
[gzserver-2] joint1/position
[gzserver-2] ]
[gzserver-2] Stop interfaces:
[gzserver-2] [
[gzserver-2] ]
[gzserver-2] Not existing:
[gzserver-2] [
[gzserver-2] joint1/position
[gzserver-2] ]
[gzserver-2]
[gzserver-2] [ERROR] [1710963128.503825172] [controller_manager]: Could not switch controllers since prepare command mode switch was rejected.
[spawner-6] [ERROR] [1710963128.504372440] [spawner_joint_trajectory_controller]: Failed to activate controller
[ERROR] [spawner-6]: process has died [pid 91644, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner joint_trajectory_controller -c /controller_manager --ros-args']
Most notable is the following line: [gzserver-2] [WARN] [1710962514.824922049] [gazebo_ros2_control]: Skipping joint in the URDF named 'joint1' which is not in the gazebo model.
I am assuming this is the reason why the JointStateBroadcaster and the JointTrajectoryController are not able to load. However, I am confused as to why Gazebo does not like my URDF. The fully-formed URDF that is generated at launch time is as follows:
<robot name="linear_slider">
<!-- World link -->
<link name="world"/>
<!-- ================== -->
<!-- Properties -->
<!-- ================== -->
<!-- ================== -->
<!-- Materials -->
<!-- ================== -->
<material name="alpha_black">
<color rgba="0.6 0.6 0.6 1"/>
</material>
<material name="red_v">
<color rgba="1 0 0 1"/>
</material>
<!-- ================== -->
<!-- Links -->
<!-- ================== -->
<!-- base_link -->
<link name="base_link">
<visual>
<material name="alpha_black"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="package://linear_slider_description/meshes/7thlink_fixed.STL" scale="0.001 0.001 0.001"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="1.0 0.3 0.10"/>
</geometry>
</collision>
</link>
<gazebo reference="base_link">
<material>Gazebo/Gray</material>
</gazebo>
<!-- moving_base link -->
<link name="moving_base">
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<material name="red_v"/>
<geometry>
<mesh filename="package://linear_slider_description/meshes/7thlink_move.STL" scale="0.001 0.001 0.001"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.22 0.202 0.118"/>
</geometry>
</collision>
<inertial>
<mass value="10.0"/>
<origin xyz="0.0 0.0 0.0"/>
<inertia ixx="0.0915" ixy="0.0" ixz="0.0" iyy="0.975" iyz="0.0" izz="0.9915"/>
</inertial>
</link>
<gazebo reference="moving_base">
<material>Gazebo/Red</material>
</gazebo>
<!-- tool link -->
<link name="tool0"/>
<link name="base"/>
<!-- Frame for mounting EEF models to a manipulator. x+ axis points forward (REP 103). -->
<link name="flange"/>
<!-- ================== -->
<!-- Joints -->
<!-- ================== -->
<!-- base_joint fixes base_link to the environment -->
<joint name="base_joint" type="fixed">
<parent link="world"/>
<child link="base_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<!-- joint1 -->
<joint name="joint1" type="prismatic">
<parent link="base_link"/>
<child link="moving_base"/>
<axis xyz="1 0 0"/>
<limit effort="10" lower="-0.4" upper="0.4" velocity="0.25"/>
<!-- effort is attribute for enforcing maximum joint effort, between 0 and 100% -->
<origin xyz="0.0 0.0 0.0"/>
<!-- Define where the joint will be located, defined in terms of parent's reference frame -->
</joint>
<!-- Extra joints for ros-industrial standard compatability -->
<!-- tool frame to fixed frame -->
<joint name="moving_base-tool0" type="fixed">
<parent link="moving_base"/>
<child link="tool0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<joint name="base_link-base_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="base"/>
</joint>
<joint name="tool0-flange_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="tool0"/>
<child link="flange"/>
</joint>
<!-- The caret ^ indicates to use the outer-scope property (with same name). The pipe | indicates to use the given fallback if the property is not defined in outer scope. -->
<!-- ================== -->
<!-- ros2_control -->
<!-- ================== -->
<ros2_control name="linear_slider_ros2_control" type="system">
<!-- Hardware -->
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<!-- Joints -->
<joint name="joint1">
<!-- Command interface -->
<command_interface name="position">
<param name="min">-0.40</param>
<param name="max">0.40</param>
</command_interface>
<!-- State interface -->
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<!-- Sensors -->
<sensor name="lim_switch_neg">
<state_interface name="switch_val">
<param name="initial_value">0</param>
</state_interface>
<param name="frame_id">base_link</param>
</sensor>
<sensor name="lim_switch_pos">
<state_interface name="switch_val">
<param name="initial_value">0</param>
</state_interface>
<param name="frame_id">base_link</param>
</sensor>
</ros2_control>
<!-- ================== -->
<!-- Gazebo Classic -->
<!-- ================== -->
<gazebo reference="world"/>
<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>/home/user/ros2_ws/install/linear_slider_bringup/share/linear_slider_bringup/config/linear_slider_controllers.yaml</parameters>
</plugin>
</gazebo>
</robot>
Several other users with similar errors to mine didn't appear to have mass and intertia tags present in their links, but I have defined them appropriately. For more context, I have included my launch file:
#!/usr/bin/env python3
from launch import LaunchDescription
from launch.actions import (
DeclareLaunchArgument,
IncludeLaunchDescription,
RegisterEventHandler,
TimerAction,
LogInfo,
)
from launch.conditions import IfCondition
from launch.event_handlers import OnProcessExit, OnProcessStart
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import (
LaunchConfiguration,
PathJoinSubstitution,
PythonExpression,
Command,
FindExecutable,
)
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
declared_args = []
declared_args.append(
DeclareLaunchArgument(
"runtime_config_package",
default_value = "linear_slider_bringup",
description = 'Package with the controller\'s configuration in the "config" folder. Usually, the argument is not set; it enables the use of a custom setup.'
)
)
declared_args.append(
DeclareLaunchArgument(
"controllers_file",
default_value = "linear_slider_controllers.yaml",
description = "YAML file with the controllers description."
)
)
declared_args.append(
DeclareLaunchArgument(
"description_package",
default_value = "linear_slider_description",
description = "Description package with the robot URDF/xacro files. Usually, the argument is not sset; it enables the use of a custom setup."
)
)
declared_args.append(
DeclareLaunchArgument(
"description_file",
default_value = "linear_slider.urdf.xacro",
description = "URDF/xacro description file of the robot."
)
)
declared_args.append(
DeclareLaunchArgument(
"prefix",
default_value = '""',
description = "Prefix of the joint names, useful for multi-robot setup. If changed, then you need to update the joint names in the controllers' description."
)
)
declared_args.append(
DeclareLaunchArgument(
"use_mock_hardware",
default_value = "false",
choices=['true', 'false'],
description = "Start robot with fake hardware mirroring command to its states."
)
)
declared_args.append(
DeclareLaunchArgument(
"mock_sensor_commands",
default_value = "false",
description = "Enable fake command interfaces for sensors for simple simulation. Use only if `use_mock_hardware` parameter is true."
)
)
declared_args.append(
DeclareLaunchArgument(
"robot_controller",
default_value = "joint_trajectory_controller",
choices = ["velocity_controller", "joint_trajectory_controller"], # add another here if we want to switch between different controllers
description = "Robot controller"
)
)
declared_args.append(
DeclareLaunchArgument(
"sim_gazebo",
default_value="false",
description="Simulate within the Gazebo Ignition environment"
)
)
declared_args.append(
DeclareLaunchArgument(
"sim_gazebo_classic",
default_value="false",
description="Simulate within the Gazebo Classic environment."
)
)
# Initialize args
runtime_config_package = LaunchConfiguration("runtime_config_package")
controllers_file = LaunchConfiguration("controllers_file")
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
prefix = LaunchConfiguration("prefix")
robot_controller = LaunchConfiguration("robot_controller")
use_mock_hardware = LaunchConfiguration("use_mock_hardware")
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
sim_gazebo = LaunchConfiguration("sim_gazebo")
sim_gazebo_classic = LaunchConfiguration("sim_gazebo_classic")
# Get URDF from xacro
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution(
[FindPackageShare(description_package), "urdf", description_file]
),
" ",
"prefix:=",
prefix,
" ",
"use_mock_hardware:=",
use_mock_hardware,
" ",
"mock_sensor_commands:=",
mock_sensor_commands,
" ",
"sim_gazebo:=",
sim_gazebo,
" ",
"sim_gazebo_classic:=",
sim_gazebo_classic,
" ",
]
)
robot_description = {"robot_description": robot_description_content}
_log0 = LogInfo(msg=robot_description_content)
_log1 = LogInfo(msg=sim_gazebo)
_log2 = LogInfo(msg=sim_gazebo_classic)
robot_state_pub_node = Node(
package = "robot_state_publisher",
executable = "robot_state_publisher",
output = "both",
parameters = [robot_description],
)
joint_state_broadcaster_spawner = Node(
package = "controller_manager",
executable = "spawner",
arguments = [
"joint_state_broadcaster",
"-c",
"/controller_manager",
],
)
robot_controllers = [robot_controller]
robot_controller_spawners = []
for controller in robot_controllers:
robot_controller_spawners.append(
Node(
package = "controller_manager",
executable = "spawner",
arguments = [controller, "-c", "/controller_manager"],
)
)
gazebo_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
FindPackageShare("ros_ign_gazebo"),
"/launch",
"/ign_gazebo.launch.py"
]),
launch_arguments={"ign_args": " -r -v 3 empty.sdf"}.items(),
condition=IfCondition(sim_gazebo)
)
gazebo_classic_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
FindPackageShare("gazebo_ros"),
"/launch",
"/gazebo.launch.py"
]),
condition=IfCondition(sim_gazebo_classic)
)
gazebo_node_spawner = Node(
package="ros_ign_gazebo", #"ros_gz_sim"
executable="create",
name="spawn_linear_slider",
arguments=["-name", "linear_slider", "-topic", "robot_description"],
condition=IfCondition(sim_gazebo),
output="screen"
)
gazebo_classic_node_spawner = Node(
package="gazebo_ros",
executable="spawn_entity.py",
name="spawn_linear_slider",
arguments=["-entity", "linear_slider", "-topic", "robot_description"],
condition=IfCondition(sim_gazebo_classic),
output="screen"
)
rviz_config_file = PathJoinSubstitution([
FindPackageShare(description_package),
"rviz",
"linear_slider.rviz"
])
rviz_node = Node(
package="rviz2",
executable="rviz2",
name="rviz2",
output="log",
arguments=["-d", rviz_config_file],
)
delay_joint_state_broadcaster_spawner_after_gazebo_spawner = RegisterEventHandler(
event_handler=OnProcessStart(
target_action=gazebo_node_spawner,
on_start=[joint_state_broadcaster_spawner],
),
condition=IfCondition(sim_gazebo)
)
delay_joint_state_broadcaster_spawner_after_gazebo_classic_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=gazebo_classic_node_spawner,
on_exit=[joint_state_broadcaster_spawner],
),
condition=IfCondition(sim_gazebo_classic)
)
delay_rviz_after_joint_state_broadcaster = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[rviz_node],
)
)
delay_robot_controller_spawners_after_joint_state_broadcaster_spawner = []
for controller in robot_controller_spawners:
delay_robot_controller_spawners_after_joint_state_broadcaster_spawner += [
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[controller]
)
)
]
return LaunchDescription(
declared_args
+ [
_log0,
_log1,
_log2,
robot_state_pub_node,
gazebo_launch,
gazebo_classic_launch,
gazebo_node_spawner,
gazebo_classic_node_spawner,
delay_joint_state_broadcaster_spawner_after_gazebo_classic_spawner,
delay_joint_state_broadcaster_spawner_after_gazebo_spawner,
delay_rviz_after_joint_state_broadcaster
]
+ delay_robot_controller_spawners_after_joint_state_broadcaster_spawner
)
Finally, here is my linear_slider_controllers.yaml
file:
controller_manager:
ros__parameters:
update_rate: 100 # hz
joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
joint_trajectory_controller:
ros__parameters:
joints:
- joint1
command_interfaces:
- position
state_interfaces:
- position
state_publish_rate: 50.0 # defaults to 50
action_monitor_rate: 21.0 # defaults to 20
allow_partial_joints_goal: false # defaults to false
constraints:
stopped_velocity_tolerance: 0.01 # Defaults to 0.01
goal_time: 0.0 # defaults to 0.0 (start immediately)
allow_nonzero_velocity_at_trajectory_end: false
I do not know how to make my URDF compatible with Gazebo Classic. I know there are more Gazebo tags, but they do not appear to be mandatory.