Skip to main content
Version: 7

Creating a Custom Robot Configuration

This guide explains how to setup any brand of robot arm and associated hardware, including custom in-house designed robotic hardware. It walks you through setup of the robot configuration package, grasp orientation, teleoperation, cameras, and real-time robot drivers.

tip

Many robots are already compatible with ROS 2 and MoveIt Pro, see our full list of robots on our ROS 2 Hardware Ecosystem page.

note

PickNik's onboarding, training, and configuration services typically assist companies in setting up their robot with MoveIt Pro. While we provide the documentation below, a certain level of existing expertise with ROS and robotics is assumed. We'd love to co-develop your application with your engineering team. We can also develop ROS 2 drivers for you, if needed.

Overview on Robot Configuration Packages

MoveIt Pro uses robot configuration packages to specify all configurations and parameters necessary for launching the application for example:

  • The robot(s) being operated and the environment - their URDFs and optionally MJCF robot models.
  • The simulated world or imported CAD file of your workcell.
  • Configuration files describing included sensors, actuators, controllers, and settings for motion planning.
  • The available set of objectives, behaviors, and waypoints for that specific configuration.

When the MoveIt Pro is launched, it loads robot description info and system settings from a specified configuration package. These configuration packages are implemented as ROS 2 packages.

MoveIt Pro includes a few configuration packages you can switch between. When you install MoveIt Pro, the configuration packages above are installed by default in a workspace cloned from the moveit_pro_example_ws repository. You can refer to this repository while reading this document, and later on when you decide to create your own configuration packages.

As an example, MoveIt Pro can be configured to use an example configuration named picknik_ur_base_config from the moveit_pro_example_ws repo. This package describes a Universal Robots UR5e manipulator with a Robotiq 2F-85 gripper. To do this, start MoveIt Pro as follows:

moveit_pro run -c picknik_ur_base_config

In this case, since the picknik_ur_base_config package is defined in an external workspace located in ~/moveit_pro/moveit_pro_example_ws, it must be mounted into MoveIt Pro by setting the user workspace to this path using moveit_pro configure.

note

The above steps assume MoveIt Pro was installed to the default directory, ~/moveit_pro. If you installed to a different directory, this path should change accordingly.

1. Create the ROS 2 Package

The structure of the package will be as follows. We will be using the picknik_ur_base_config package as reference.

picknik_ur_base_config/
config/
control/
moveit/
config.yaml
description/
launch/
objectives/
waypoints/
CMakeLists.txt
package.xml

Fill in package.xml

If your configuration requires resources from other packages or is inheriting from another config, tag them as dependencies here. Below is an example with dependencies for configuring a UR5e arm with an Intel Realsense camera and a Robotiq gripper:

<?xml version="1.0"?>
<package format="3">
<name>picknik_ur_base_config</name>
<version>3.0.0</version>

<description>Base configuration package for Picknik's UR robot arms</description>

<maintainer email="[email protected]">MoveIt Pro Maintainer</maintainer>

<license>BSD-3-Clause</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<exec_depend>admittance_controller</exec_depend>
<exec_depend>kinematics_interface_kdl</exec_depend>
<exec_depend>moveit_planners_stomp</exec_depend>
<exec_depend>moveit_ros_perception</exec_depend>
<exec_depend>moveit_studio_agent</exec_depend>
<exec_depend>moveit_studio_behavior</exec_depend>
<exec_depend>moveit_studio_ur_pstop_manager</exec_depend>
<exec_depend>picknik_accessories</exec_depend>
<exec_depend>pose_ik</exec_depend>
<exec_depend>realsense2_description</exec_depend>
<exec_depend>realsense2_camera</exec_depend>
<exec_depend>robotiq_description</exec_depend>
<exec_depend>robotiq_driver</exec_depend>
<exec_depend>robotiq_controllers</exec_depend>
<exec_depend>ur_description</exec_depend>
<exec_depend>ur_robot_driver</exec_depend>

<test_depend>ament_lint_auto</test_depend>

<test_depend>ament_clang_format</test_depend>
<test_depend>ament_clang_tidy</test_depend>p
<test_depend>ament_cmake_copyright</test_depend>
<test_depend>picknik_ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>

Fill in CMakeLists.txt

The CMakeLists.txt defines the install targets for all the shared package artifacts. If your configuration requires other packages or is inheriting from another config package, include them as find_package requirements here. The example below installs all the populated subdirectories to the package's share directory:

cmake_minimum_required(VERSION 3.16.3)
project(picknik_ur_base_config)

find_package(ament_cmake REQUIRED)

install(
DIRECTORY
config
description
launch
objectives
waypoints
DESTINATION
share/${PROJECT_NAME}
)

ament_package()

2. Create and populate a config.yaml file

Each configuration package requires a config/config.yaml file that defines various settings, including:

  • URDF and SRDF files defining the setup's robot description and semantics.
  • Configuration for robot drivers, controllers, and sensors
  • Configuration for the MoveIt instance
  • Definitions for MoveIt Pro Objectives and Behaviors

The config/config.yaml tells the MoveIt Pro precisely what resources to load and how to configure them at runtime. The following sections describe how to prepare the resources and configure the config for MoveIt Pro to launch successfully.

Configuring Robot Description and Semantics

The MoveIt Pro config requires the robot_description property to point to the robot description and semantics files using the urdf and srdf keys. For the urdf key, either a XACRO or URDF file can be used. If a XACRO file is used, the corresponding URDF file is generated with each launch. Optional XACRO arguments can be defined using the urdf_params key. URDF or XACRO files are typically placed in the description folder of a configuration package, the SRDF file is commonly placed inside config/moveit/. However, it is also possible to point to an existing MoveIt configuration or other ROS 2 packages.

Below is a simplified example from the picknik_ur_base_config.

# Parameters used to configure the robot description through XACRO.
# A URDF and SRDF are both required.
# [Required]
robot_description:
urdf:
package: "picknik_ur_base_config"
path: "description/picknik_ur.xacro"
srdf:
package: "picknik_ur_base_config"
path: "config/moveit/picknik_ur.srdf"

# Specify any additional parameters required for the URDF and SRDF.
# Many of these are specific to the UR descriptions packages, and can be customized as needed.
# [Optional]
urdf_params:
- name: "picknik_ur5e"
- prefix: ""

Configuring Grasp Preview

MoveIt Pro uses the following convention for grasping frames:

MoveIt Pro Grasp Link

  • Positive X points to the robots left and is parallel to the direction the fingers move
  • Positive Y points up towards the top of the gripper (from the wrist camera's perspective, if present)
  • Positive Z points out of the gripper

It is required to add a frame to your robot's end effector like this to your URDF (e.g. labsim URDF). By default, we use the frame name grasp_link, but you can rename it as needed, so long as your Behaviors specify the correct frame name.

Configuring UI Grasp Previews

MoveIt Pro uses the group defined as the end_effector element in the config's SRDF file for previewing grasp poses. When creating a custom config, make sure you define an end_effector element in your SRDF like this:

<end_effector name="moveit_ee" parent_link="tool0" group="gripper"/>

The group attribute specifies the move group containing the joints, links and/or chains that pertain to your end effector. We recommend using chains when creating this group as opposed to links in order to avoid discrepancies when specifying these fields. You can see an example of this in the lab_sim example configuration.

Configuring Robot Drivers and Controllers

The MoveIt Pro config supports specifying the robot's runtime configuration, including hardware drivers, simulation backends and controllers.

Add robot and driver launch files

You can specify different launch files for simulation vs. hardware environments, which are controlled by the hardware.simulated option in config/config.yaml. Take a look at the picknik_ur_base_config's config file, the robot driver configurations of lab_sim are inherited from this config.

The robot_driver_persist_launch_file and simulated_robot_driver_persist_launch_file are intended to launch robot drivers (and other processes) that are expected to stay active the entire time MoveIt Pro is running.

For example, if you are using MoveIt Pro with a mobile manipulator, the robot_driver_persist_launch_file and simulated_robot_driver_persist_launch_file can be used to launch Nav2 via the launch file.

The simulated_hardware_launch_file can be used to launch a process which simulates your hardware, such as MuJoCo.

objectives

In this section you configure which behaviors from MoveIt Pro core you can use in your configuration and where this configs objectives and waypoints are stored. Use lab_sim's config.yaml as reference how the objectives section is configured.

The objectives directory contains XML Objective definition files that define the Objectives which the robot can run. It also contains an autogenerated tree_nodes_model.xml file, which provides the necessary metadata needed to display Objectives and Behaviors in the MoveIt Studio Developer Tool.

Required Version
This feature requires MoveIt Pro version 7.6.0 or newer.

MoveIt Pro makes available a selection of commonly used objectives through the moveit_pro_objectives package. You can use them by adding the following to your config.yaml:

objective_library_paths:
core_objectives:
package_name: "moveit_pro_objectives"
relative_path: "objectives/core"
motion_objectives:
package_name: "moveit_pro_objectives"
relative_path: "objectives/motion"
perception_objectives:
package_name: "moveit_pro_objectives"
relative_path: "objectives/perception"
note

The last entry in this list will be the location newly created objectives are saved to.

These default objectives give you immediate and universal functionality to your robot config, namely:

You can override any of the default objectives by adding a new objective with the same name to your custom config. To include objectives from your robot configuration package, add a modified version of the following code to your list of objective_library_paths:

  custom_objectives:
package_name: "my_robot_config_package"
relative_path: "objectives"
note

The below does not require 7.6.0.

There are a bunch of objectives from here that enable different functionalities in MoveIt Pro. The following sections cover them and explain what they are needed for.

Configuring Teleoperation

MoveIt Pro provides access to different control modes to move your robot. The different control modes are described in the Teleoperate Robot tutorial

A Teleoperate Objective is included in MoveIt Pro's core_objectives path from above.

The teleoperate Objective uses the Request Teleoperation Objective as a subtree and hence this Objective should also be added to the custom config.

note

The core_objectives path contains a Request Teleoperation Objective, but we recommend you write your own for the drivers and controllers you need.

The Request Teleoperation SubTree can be added to other objectives that require hybrid autonomous/manual modes, remote recovery fallbacks, etc.

note

Note that the teleoperation Objectives below use Behaviors requiring parameters such as, but not limited to:

  • controller_names
  • planning_group_name
  • planner_interface

When making these Objectives, make sure to check the values you specify correspond to the definitions in your ros2_control.yaml, SRDF, XACRO/URDF, etc files.

Waypoints

The Waypoint control mode requires the following objectives and updated parameters:

IMarker

The IMarker control mode requires the following objectives and updated parameters:

IMarker also requires the proper setup of your servo yaml config file, as it will reference the active planning group of the servo server (e.g. move_group_name: manipulator) to use the tip frame of the gripper planning group.

In the Move To Pose Objective in the SetupMTCMoveToPose Behavior, the ik_frame link you specify must be:

  • Part of the group you specify via the SetupMTCMoveToPose Behavior's planning_group_name parameter.
  • Part of the group you specify in your SRDF's end_effector tag's group field.
  • Part of the servo server's active planning group (e.g. move_group_name: manipulator)
Pose Jog

The Pose Jog control mode requires the following objectives and updated parameters:

Joints Jogs

The Joints Jog control mode requires the following objectives and updated parameters:

Joint jog also requires the proper setup of your servo yaml config file, as it will reference the active planning group of the servo server (e.g. move_group_name: manipulator) to populate the list of joints to create sliders for.

In order for Joint Jog Teloperation to function properly, parameters for MoveIt Servo (listed in your project's servo config yaml ie. ur5e_servo.yaml) will require specification of the following topics:

  • cartesian_command_in_topic: defined as ~/delta_twist_cmds
  • joint_command_in_topic: defined as ~/delta_joint_cmds

The waypoints/waypoints.yaml file defines a set of named robot joint states that the runtime can retrieve and plan to during an Objective. This file replaces the named group states commonly included in the robot's SRDF file. Waypoints can be saved and edited during runtime, as explained further in Configuring MoveIt Pro.

moveit_params

The config package allows configuring any of the MoveIt runtime properties using the same yaml files obtained from the MoveIt Setup Assistant. However, instead of depending on a MoveIt config package, the yaml files need to be added to the configuration package's config/moveit/ subdirectory.

The config files supported by MoveIt Pro include:

  • joint_limits.yaml: Sets joint position, velocity, acceleration, and effort limits to use when planning and parameterizing robot motion.
  • kinematics.yaml: Configures MoveIt's kinematics solvers. Note you can specify multiple kinematics files for different applications, for example for motion planning vs. servoing.
  • ompl_planning.yaml: Defines settings for MoveIt's OMPL planners.
  • stomp_planning: Defines settings for MoveIt's STOMP planner plugin.
  • pilz_planning: Defines settings for MoveIt's PILZ planner plugin.
  • pilz_cartesian_limits.yaml: Defines Cartesian velocity and acceleration limits for the Pilz Industrial Motion Planner.
  • sensors_3d.yaml: Defines how the MoveIt MoveGroup node should handle point clouds from the robot's RGB-D cameras.
  • servo.yaml: Configures settings for the MoveIt Servo server node.
  • servo_joint_limits: Configures joint limits for MoveIt Servo.
  • sensors_3d: Configures the MoveIt perception pipeline to handle sensor inputs e.g. from depth camera.

You find examples for each file in the moveit_pro_example_ws/src/lab_sim/config/moveit directory take a look at lab_sim's config.yaml file to see which configuration file is used for which setting.

Additionally it is possible to change different parameters of the move_group that is launched when MoveIt Pro is brought up.

# Extend the basic Universal Robots configuration
based_on_package: picknik_ur_base_config

hardware:
robot_description:
urdf:
package: "picknik_ur_site_config"
path: "description/my_customized_robot.xacro"

objectives:
behavior_loader_plugins:
# You must use a unique key for each Behavior plugin.
# The picknik_ur_base_config uses "core"
custom_behaviors:
package_name: "my_custom_behaviors::MyCustomBehaviorsLoader"
objective_library_paths:
# You must use a unique key for each package.
# The picknik_ur_base_config uses "core"
custom_objectives:
package_name: "picknik_ur_site_config"
relative_path: "objectives"
# Configures the move_group's trajectory execution manager.
trajectory_execution:
manage_controllers: True
allowed_execution_duration_scaling: 2.0
allowed_goal_duration_margin: 5.0
allowed_start_tolerance: 0.01