Robot Description Tutorial#

Objectives#

Through this tutorial, you will learn:

  1. How to load a robot description from file

  2. How to query useful data from the robot description

What is a Robot Description?#

A “robot description” is essentially everything needed to describe the robot, which includes (but is not limited to):

  • The kinematics (links, joints, frames, etc.)

  • The definition of configuration space (c-space) and auxiliary c-space

  • C-space position, velocity, acceleration, and jerk limits

  • Default c-space position

  • A list of tool frames

  • Collision spheres for both self- and world-collision

Importantly, the robot description does NOT include a description of the environment (e.g. obstacles).

Loading a Robot Description From File#

Currently, the cuMotion library does not support building robots programmatically. All robot descriptions are expected to be defined by two files:

  1. URDF

  2. XRDF

Assuming these two files are correctly formatted and contain all the required information, the robot description can be loaded using:

std::ifstream xrdf_fstream(xrdf_file);
std::stringstream xrdf_ss;
xrdf_ss << xrdf_fstream.rdbuf();
robot_description = cumotion.load_robot_from_file(xrdf_path, urdf_path)

Alternatively, the robot description can be loaded from a string containing the contents of those files:

std::ifstream xrdf_fstream(xrdf_file);
std::stringstream xrdf_ss;
xrdf_ss << xrdf_fstream.rdbuf();
const std::string xrdf_contents = xrdf_ss.str();

std::ifstream urdf_fstream(urdf_file);
std::stringstream urdf_ss;
urdf_ss << urdf_fstream.rdbuf();
const std::string urdf_contents = urdf_ss.str();

std::unique_ptr<cumotion::RobotDescription> robot_description_from_memory =
    cumotion::LoadRobotFromMemory(xrdf_contents, urdf_contents);
with open(xrdf_path) as file:
    xrdf_contents = file.read()
with open(urdf_path) as file:
    urdf_contents = file.read()
robot_description_from_memory = cumotion.load_robot_from_memory(xrdf_contents, urdf_contents)

Querying Robot Metadata#

The robot description allows us to retrieve some useful metadata about the robot. We can get the number of c-space coordinates:

const int num_coords = robot_description->numCSpaceCoords();
num_coords = robot_description.num_cspace_coords()

The name of each c-space coordinate:

std::vector<std::string> coord_names(num_coords);
for (int coord_index = 0; coord_index < num_coords; ++coord_index) {
coord_names[coord_index] = robot_description->cSpaceCoordName(coord_index);
}
for (int coord_index = 0; coord_index < num_coords; ++coord_index) {
std::cout << "Coordinate " << coord_index << " name: " << coord_names[coord_index] << "\n";
}
coord_names = [robot_description.cspace_coord_name(coord_index) for coord_index in
               range(num_coords)]
for (index, name) in enumerate(coord_names):
    print("Coordinate {} name: {}".format(index, name))

Output:

Coordinate 0 name: panda_joint1
Coordinate 1 name: panda_joint2
Coordinate 2 name: panda_joint3
Coordinate 3 name: panda_joint4
Coordinate 4 name: panda_joint5
Coordinate 5 name: panda_joint6
Coordinate 6 name: panda_joint7

The default c-space position:

Eigen::VectorXd default_cspace_position = robot_description->defaultCSpaceConfiguration();
std::cout << "Default position: [" << default_cspace_position.transpose() << "]\n";
default_cspace_position = robot_description.default_cspace_configuration()
print("Default position: ", default_cspace_position)

Output:

Default position: [    0  -1.3     0 -2.87     0     2  0.75]

And the tool frame names:

std::vector<std::string> tool_frame_names = robot_description->toolFrameNames();
std::cout << "Tool frame names: [ ";
for (const auto &tool_name : tool_frame_names) {
std::cout << tool_name << " ";
}
std::cout << "]\n";
tool_frame_names = robot_description.tool_frame_names()
print("Tool frame names: ", tool_frame_names)

Output:

Tool frame names: [ panda_leftfingertip ]

Create the Robot Kinematics#

The kinematics of the robot describe the physical structure of the robot, and provide the interface for querying the position and orientation of frames at each link, as a function of the c-space coordinates (i.e. forward kinematics).

Creating the kinematics for the robot is done through the robot description:

std::unique_ptr<cumotion::Kinematics> kinematics = robot_description->kinematics();
kinematics: cumotion.Kinematics = robot_description.kinematics()

For more details on the kinematics, see the Kinematics Tutorial.

This function creates a new instance of the robot kinematics each time it is called. It is highly recommended that the user call this function once and save the result.

Note

When using C++, the kinematics.h header must be included prior to calling cumotion::RobotDescription::kinematics().