Skip to main content
Version: ROS 2 Humble

Manipulators

Manipulators include all robotic arms and grippers. Unlike sensors, manipulators are not controlled by external drivers. Instead, a hardware controller must be loaded into the controller manager to handle the joint interface to move the specific manipulator joints.

Additionally, MoveIt! must be launched to plan paths and move manipulators to a given pose.

Every arm can have at most one gripper, and grippers can only be added to an existing arm. This way, depending on the arm and the gripper, the configuration system can determine whether the arm handles communication with the gripper or whether it must be done through an external connection directly to the robot computer.

Kinova Arms

manipulators:
arms:
- model: kinova_gen3_lite
parent: default_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ip: 192.168.131.40
port: 10000
gripper:
model: kinova_2f_lite

Package and Setup

The Kinova Gen3 Lite uses the kortex_description and kortex_driver ROS 2 Packages. The driver is open source, maintaned by Kinova Robotics, and hosted on GitHub.

For more specifics on the way Clearpath's configuration system adds the manipulator to the robot description, see the Kinova Gen3 Lite description file in clearpath_manipulators_description.

Device IP and Port

The ip and port parameters must be set to the corresponding values set on the manipulators configuration page.


manipulators:
arms:
- model: kinova_gen3_6dof
parent: default_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ip: 192.168.131.40
port: 10000
gripper:
model: robotiq_2f_85

Package and Setup

The Kinova Gen3 6Dof uses the kortex_description and kortex_driver ROS 2 Packages. The driver is open source, maintaned by Kinova Robotics, and hosted on GitHub.

For more specifics on the way Clearpath's configuration system adds the manipulator to the robot description, see the Kinova Gen3 6Dof description file in clearpath_manipulators_description.

Device IP and Port

The ip and port parameters must be set to the corresponding values set on the manipulators configuration page.


manipulators:
arms:
- model: kinova_gen3_7dof
parent: default_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ip: 192.168.131.40
port: 10000
gripper:
model: robotiq_2f_85

Package and Setup

The Kinova Gen3 7Dof uses the kortex_description and kortex_driver ROS 2 Packages. The driver is open source, maintaned by Kinova Robotics, and hosted on GitHub.

For more specifics on the way Clearpath's configuration system adds the manipulator to the robot description, see the Kinova Gen3 7Dof description file in clearpath_manipulators_description.

Device IP and Port

The ip and port parameters must be set to the corresponding values set on the manipulators configuration page.


Kinova Grippers

manipulators:
arms:
- model: kinova_gen3_lite
parent: default_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ip: 192.168.131.40
port: 10000
gripper:
model: kinova_2f_lite

Package and Setup

note

The Kinova 2F Lite gripper is the standard gripper on the Kinova Gen3 Lite. It is controlled via the arm's hardware interface and therefore, does not need it's own controller.

The Kinova 2F Lite gripper uses the kortex_description and kortex_driver ROS 2 Packages. The driver is open source, maintaned by Kinova Robotics, and hosted on GitHub.

For more specifics on the way Clearpath's configuration system adds the manipulator to the robot description, see the Kinova 2F Lite gripper description file in clearpath_manipulators_description.


Robotiq Grippers

manipulators:
arms:
- model: kinova_gen3_6dof
parent: default_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ip: 192.168.131.40
port: 10000
gripper:
model: robotiq_2f_85

Package and Setup

note

The Robotiq 2F 85 gripper is supported by the Kinova Gen3 arm's wrist connector and hardware interface. Therefore, when attached to Kinova arm's the Robotiq gripper does not need it's own controller.

The Robotiq 2F 85 uses the robotiq_description and robotiq_driver ROS 2 Packages. The driver is open source, maintaned by PickNik Robotics, and hosted on GitHub.

For more specifics on the way Clearpath's configuration system adds the manipulator to the robot description, see the Robotiq 2F 85 gripper description file in clearpath_manipulators_description.


manipulators:
arms:
- model: kinova_gen3_6dof
parent: default_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ip: 192.168.131.40
port: 10000
gripper:
model: robotiq_2f_140

Package and Setup

note

The Robotiq 2F 140 gripper is supported by the Kinova Gen3 arm's wrist connector and hardware interface. Therefore, when attached to Kinova arm's the Robotiq gripper does not need it's own controller.

The Robotiq 2F 140 uses the robotiq_description and robotiq_driver ROS 2 Packages. The driver is open source, maintaned by PickNik Robotics, and hosted on GitHub.

For more specifics on the way Clearpath's configuration system adds the manipulator to the robot description, see the Robotiq 2F 140 gripper description file in clearpath_manipulators_description.


Universal Robots

manipulators:
arms:
- model: universal_robots
parent: default_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ur_type: ur5e
robot_ip: 192.168.131.40
headless: false

Package and Setup

The Universal Robots arms use the ur_description and ur_driver ROS 2 Packages. The description and driver are open source, maintained by Universal Robots, and are hosted on GitHub. Refer to the description repository and driver repository.

For more specifics on the way Clearpath's configuration system adds the arm to the robot description, see the description file. Note, all parameters to the xacro:macro universal_robots can be passed through the robot.yaml entry above. For examples, read the sections below.

Teach Pendant Setup

The following sub-sections will cover the standard UR teach pendant setup, but with the specific Clearpath parameters. For the UR instructions see: Setting up a UR robot for ur_robot_driver and Installing a URCap on a e-Series robot.

Networking Settings

At Clearpath, we use the 192.168.131.x subnet and assign manipulators to the range 192.168.131.40-49. Therefore, when setting up a UR arm, we encourage the use of the 192.168.131.40 address.

Navigate to the Settings/System/Networking page of the UR teach pendant and set the following:

URCap

In order to control the arm from an external device, the External Control URCap needs to be setup. You can find the latest externalcontrol-x.x.x.urcap in its repository. Install it by adding it to the programs folder in the /, root directory of the arm's control box. Use a USB stick or scp.

Navigate to the Settings/System/URCaps page to install the URCap. Note, you will be prompted and must restart before using the URCap.

Navigate to the Installation/URCaps page to configure the IP address and hostname of the external device. The standard Clearpath robot computer IP address is 192.168.131.40. Each robot has its own hostname, we will use cpr-a300-0000 as a placeholder:

External Control Program

Once the URCap has been installed and configured, a program that launches the ExternalControl task needs to be created and set as default.

Begin by navigating to the Programs/URCap section, make sure the program is empty except for the addition of the ExternalControl task. Save the program as external_control.urp:

Now, set the program as default so that it is automatically loaded and ready to run on start-up. Navigate to the Installation/General/Startup page and set the external_control.urp program as the default:

Initializing the Arm

At start up, the arm needs to be turned on and initialized. Press the button in the bottom left corner which will bring-up the arm start-up sequence window. Follow the instructions to initialize the arm:

Once the robot is in normal mode, you can proceed to initialize the external control program.

At start up, the robot computer will launch the arm's controller using the clearpath-manipulators.service. Once the arm is on and initialized through the teach pendant, start the external_control program, which will begin communication with the ROS driver.

Start the program by pressing the play button on the Run page.

Troubleshooting

If the following error pop-up window appears, then ensure that the arm's URCap configuration matches the robot's computer and that the robot's computer is able to ping the arm. The error also indicates that the ROS driver is not currently running or has been stopped. Restart the clearpath-manipulators.service and try again:

sudo systemctl stop clearpath-manipulators.service
sudo systemctl start clearpath-manipulators.service

Headless Initialization

If the arm has been setup to accept external control by surrendering manual control in the teach pendant, then it is possible to bypass the manual initialization of the UR program on the tablet. If this is the case, make sure the arm has been turned on and initialized through the teach pendant, then set, headless: true in the robot.yaml. This will restart the services and the arm should connect automatically.

Setup

The headless setup is not recommended as it is more complicated, however it exposes the entire teach pendant's functionality to the ROS interface, and thus, provides experienced ROS users with the ability to detect arm faults, clear faults, and restart the arm programmatically.

To begin the setup, make sure that remote control is enabled in the Settings/System/Remote Control page:

To enter Remote Control mode, first put the teach pendant in Automatic:

Then, you will be able to switch from Automatic to Remote Control:

In this mode, you will be unable to interface with the arm directly from the tablet. Instead, all commands must be sent by the external device. You can restore manual control by following the steps above in reverse.

Parameter: Device IP

The robot_ip must be set to match the networking settings of the arm's control box. By default, we use the 192.168.131.40 address.

Parameter: UR Type

The ur_type parameter can be modified to change the type of the arm. By default, it is set to ur5e. But, it is critical that it is changed to match the real arm type. The following types are supported: ur3, ur3e, ur5, ur5e, ur10, ur10e, ur16e, ur20, ur30.

Parameter: Calibration Parameters

By default, the default kinematics parameter file is passed to the arm's ROS controller. Because each arm has it's own measurable offsets, it is likely that without updating this calibration file the arm's movements will not be as accurate as could be. Therefore, use the ur_calibration package to obtain the calibration parameter file.

ros2 launch ur_calibration calibration_correction.launch.py robot_ip:=<robot_ip> target_filename:="${HOME}/my_robot_calibration.yaml"

Then, in the entry to the configuration file, pass in the path to the calibrated kinematics file.

manipulators:
arms:
- model: universal_robots
parent: default_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ur_type: ur5e # ur3, ur3e, ur5, ur5e, ur10, ur10e, ur16e, ur20, ur30
robot_ip: 192.168.131.40
headless: false
kinematics_parameters_file: "/path/to/my_robot_calibration.yaml"

Note, you can also pass in substitution arguments:

      kinematics_parameters_file: "$(find package_name)/path/to/my_robot_calibration.yaml"