Simulation Setup

Setting up a simulation requires a lot of different nodes that interact with each other. The following is a graph showing nodes (and associated relationships) used in a simulation.

digraph G {
   rankdir=LR;
   "/controller_manager";
   "/motion_control_handle"     -> "/cartesian_motion_controller"   [label="/target_frame"];
   "/joint_state_broadcaster"   -> "/robot_state_publisher"         [label="/joint_states"];
   "/robot_state_publisher"     -> "/transform_listener_impl_<#1>"  [label="/tf_static"];
   "/robot_state_publisher"     -> "/transform_listener_impl_<#1>"  [label="/tf"];
   "/sim_ros2_interface"        -> "/transform_listener_impl_<#1>"  [label="/tf"];
   "/sim_ros2_interface"        -> "/robot_controller"              [label="/coppelia_joint_joints"];
   "/robot_controller"          -> "/sim_ros2_interface"            [label="/coppelia_set_joints"];
}

Node description

The /joint_state_broadcaster node is part of the ROS2 control package. More details can be found here, but essentially the broadcaster reads all state interfaces and reports them on the /joint_states topic.

Such data is collected by the /robot_state_publisher node (package Robot State Publisher) that combines the knowledge of the robot’s kinematics to publish the full tree of transformations for the different links on the topics /tf and /tf_static.

The /motion_control_handle node is implemented as a ROS2 control that spawns an handle that can be moved in RViz that specifies the target position of the robot; the information is published on the /target_frame topic.

The target pose defined by the /motion_control_handle is actuated by the /cartesian_motion_controller, which is a kinematic ROS2 controller that connects to the hardware interface (/robot_controller) which loaded by the URDF.

The sim_ros2_interface node is instead provided by CoppeliaSim and is the bridge between the ROS2 world (in which the control is computed) and the Coppelia world (in which the system is simulated).

As mentioned here, the /transform_listener_impl_<> nodes are automatically spawned in order to ensure a reliable transformation processing.

The /robot_controller is the hardware interface that connects Coppeliasim to the ROS2 control framework. It is implemented reading the state from the robot and writing the command from the controller using ROS2 topics.

Finally, the standalone /controller_manager node, from ROS2 control, is the key node that needs to be enabled to manage the ROS2 control framework. It is responsible for spawning, starting and stopping the controllers.

Launch file

Coppelia simulator does not provide a ROS interface to start the simulation itself. Therefore, the simulator must be started manually (e.g. $COPPELIASIM_ROOT/coppeliaSim.sh), the proper .ttt scene must be selected and the simulation enabled.

After that, the ROS2 launch file can be used to start the ROS2 nodes. In the following, the different section of the launch file are explained in detail; the complete version of the script can be found here.

import xacro, os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare

As usual, first all required packages are imported.

def generate_launch_description():

Then its defined the function used by ROS2 that configures and starts all different required nodes.

share_pkg_dir = get_package_share_directory("ur_coppeliasim")
xacro_path = os.path.join(share_pkg_dir, "urdf", "ur.urdf.xacro")
available_joint_controllers = os.path.join(
    share_pkg_dir, "config", "ur_controllers_coppelia.yaml"
    )
declared_arguments = []
use_sim_time = True
ur_type = "ur3e"
robot_description_content = xacro.process_file(
    xacro_path,
    mappings={
        "safety_limits": "true",
        "safety_pos_margin": "0.15",
        "safety_k_position": "20",
        "name": "ur",
        "ur_type": ur_type,
        "prefix": '',
        "sim_ignition": "false",
        "sim_gazebo": "false",
        "simulation_controllers": available_joint_controllers
        }
    ).toprettyxml(indent=' ')
robot_description = {"robot_description": robot_description_content}
robot_controllers = available_joint_controllers

In this section some relevant resources are loaded. Given the share directory of the package (that in this case is assumed to be called ur_coppeliasim), the list of availabe controllers for the controller manager are loaded. Then, the URDF model is compiled starting from the xacro file of Universal Robots models; such file contains generic description of all UR models, and in this case the ur3e model is selected. Important is that both gazebo classic and gazebo ignition are disabled, since the simulator used is CoppeliaSim.

control_node = Node(
    package="controller_manager",
    executable="ros2_control_node",
    parameters=[
        robot_description, robot_controllers, {
            "use_sim_time": use_sim_time
            }
        ],
    output="both",
    remappings=[
        ('motion_control_handle/target_frame', 'target_frame'),
        ('cartesian_motion_controller/target_frame', 'target_frame'),
        ]
    )

This defines the configuration of the controller manager. Relevant is the configuration of the use_sim_time parameter: in this case it is set to true, to have a synchronization with the simulator. For instance, simulation might be slower than real time when it becomes more complex, or in case the simulation is trivial, it can be accelerated. Furthermore, some topics are remapped for ease of use and sake of demonstration, e.g. /motion_control_handle/target_frame is remapped to /target_frame.

joint_state_broadcaster_spawner = Node(
    package="controller_manager",
    executable="spawner",
    arguments=["joint_state_broadcaster", "-c", "/controller_manager"],
    parameters=[{
        "use_sim_time": use_sim_time
        }]
    )

This configures the joint state broadcaster node, bounding it to the controller manager defined above. More details of the arguments to use for the controller manager spawner can be found here.

cartesian_motion_controller_spawner = Node(
    package="controller_manager",
    executable="spawner",
    arguments=["cartesian_motion_controller", "-c", "/controller_manager"],
    parameters=[{
        "use_sim_time": use_sim_time
        }]
    )
# Motion handle
motion_control_handle_spawner = Node(
    package="controller_manager",
    executable="spawner",
    arguments=["motion_control_handle", "-c", "/controller_manager"],
    parameters=[{
        "use_sim_time": use_sim_time
        }]
    )

Similarly, here the controller manager spawner is used to start the cartesian motion controller, whose parameters have been loaded in the available_joint_controllers variable above. In the same way, the handle that can be moved from RViz is configured.

robot_state_publisher = Node(
    package="robot_state_publisher",
    executable="robot_state_publisher",
    output="both",
    parameters=[robot_description, {
        "use_sim_time": use_sim_time
        }],
    )

Here the robot state publisher is loaded.

rviz_config = PathJoinSubstitution([
    FindPackageShare("cartesian_controller_simulation"), "etc", "robot.rviz"
    ])
rviz = Node(
    package="rviz2",
    executable="rviz2",
    name="rviz2",
    output="log",
    arguments=["-d", rviz_config],
    parameters=[{
        "use_sim_time": use_sim_time
        }]
    )

Here RViz is started with a configuration that has been defined in another package, in particular from cartesian_controller_simulation.

nodes = [
    control_node,
    joint_state_broadcaster_spawner,
    cartesian_motion_controller_spawner,
    motion_control_handle_spawner,
    robot_state_publisher,
    rviz,
    ]
return LaunchDescription(declared_arguments + nodes)

Finally, all defined nodes are grouped in a list that will consistitute the final launch description.