Robot Model and Robot State

In this section, we will walk you through the C++ API for using kinematics in MoveIt!

The RobotModel and RobotState classes are the core classes that give you access to a robot’s kinematics.

The RobotModel class contains the relationships between all links and joints including their joint limit properties as loaded from the URDF. The RobotModel also separates the robot’s links and joints into planning groups defined in the SRDF. A separate tutorial on the URDF and SRDF can be found here: URDF and SRDF Tutorial

The RobotState contains information about the robot at a snapshot in time, storing vectors of joint positions and optionally velocities and accelerations that can be used to obtain kinematic information about the robot that depends on it’s current state such as the Jacobian of an end effector.

RobotState also contains helper functions for setting the arm location based on the end effector location (Cartesian pose) and for computing Cartesian trajectories.

In this example, we will walk through the process of using these classes with MARA.

If you haven’t already done so, make sure you’ve completed the steps in Getting Started.

All the code in this tutorial can be compiled and run from the moveit_tutorials package that you have as part of your MoveIt! setup.

Roslaunch the launch file to run the code directly from moveit_tutorials:

roslaunch mara_moveit_tutorials robot_model_and_robot_state_tutorial.launch

The expected output will be in the following form. The numbers will not match since we are using random joint values:

[ INFO] [1547721944.758962069]: Model frame: /world
[ INFO] [1547721944.758995899]: Joint motor1: 0.000000
[ INFO] [1547721944.759020386]: Joint motor2: 0.000000
[ INFO] [1547721944.759030961]: Joint motor3: 0.000000
[ INFO] [1547721944.759036819]: Joint motor4: 0.000000
[ INFO] [1547721944.759042679]: Joint motor5: 0.000000
[ INFO] [1547721944.759049818]: Joint motor6: 0.000000
[ INFO] [1547721944.759092130]: Current state is not valid
[ INFO] [1547721944.759133709]: Current state is valid
[ INFO] [1547721944.759201137]: Translation:
0.0632851
-0.275812
  1.41976

[ INFO] [1547721944.759235322]: Rotation:
 0.101829 -0.416261 -0.903525
-0.839096  0.451934 -0.302777
 0.534368  0.788976 -0.303262

[ INFO] [1547721944.759393213]: Joint motor1: -1.096107
[ INFO] [1547721944.759404281]: Joint motor2: 1.358151
[ INFO] [1547721944.759414220]: Joint motor3: 1.828464
[ INFO] [1547721944.759425549]: Joint motor4: -0.890700
[ INFO] [1547721944.759437474]: Joint motor5: 0.653983
[ INFO] [1547721944.759450043]: Joint motor6: 0.062458
[ INFO] [1547721944.759535568]: Jacobian:
   0.0630655    -0.466813      0.42927    0.0767336     0.167299 -6.93889e-18
   -0.275862     0.239885    -0.220593    -0.206486     0.182358  1.11022e-16
           0     0.216537    -0.412032   -0.0826728    -0.297215 -6.93889e-18
           0    -0.457062     0.457062    -0.403061    -0.329031    -0.839417
           0    -0.889435     0.889435     0.207125     0.876124    -0.100441
          -1            0            0    -0.891426     0.352342    -0.534126

Note: Don’t worry if your output has different ROS console format. You can customize your ROS console logger by following this blog post.

The entire code can be seen here in the MoveIt! GitHub project.

Setting up to start using the RobotModel class is very easy. In general, you will find that most higher-level components will return a shared pointer to the RobotModel. You should always use that when possible. In this example, we will start with such a shared pointer and discuss only the basic API. You can have a look at the actual code API for these classes to get more information about how to use more features provided by these classes.

We will start by instantiating a RobotModelLoader object, which will look up the robot description on the ROS parameter server and construct a RobotModel for us to use.

robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
robot_model::RobotModelPtr kinematic_model = robot_model_loader.getModel();
ROS_INFO("Model frame: %s", kinematic_model->getModelFrame().c_str());

Using the RobotModel, we can construct a RobotState that maintains the configuration of the robot. We will set all joints in the state to their default values. We can then get a JointModelGroup, which represents the robot model for a particular group, e.g. the “manipulator” of MARA's arm.

robot_state::RobotStatePtr kinematic_state(new robot_state::RobotState(kinematic_model));
kinematic_state->setToDefaultValues();
const robot_state::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup("manipulator");

const std::vector<std::string>& joint_names = joint_model_group->getVariableNames();

We can retreive the current set of joint values stored in the state for MARA.

std::vector<double> joint_values;
kinematic_state->copyJointGroupPositions(joint_model_group, joint_values);
for (std::size_t i = 0; i < joint_names.size(); ++i)
{
  ROS_INFO("Joint %s: %f", joint_names[i].c_str(), joint_values[i]);
}

Now, we can compute forward kinematics for a set of random joint values. Note that we would like to find the pose of the “ee_link” which is the most distal link in the “manipulator” group of the robot.

kinematic_state->setToRandomPositions(joint_model_group);
const Eigen::Affine3d& end_effector_state = kinematic_state->getGlobalLinkTransform("ee_link");

/* Print end-effector pose. Remember that this is in the model frame */
ROS_INFO_STREAM("Translation: \n" << end_effector_state.translation() << "\n");
ROS_INFO_STREAM("Rotation: \n" << end_effector_state.rotation() << "\n");

We can now solve inverse kinematics (IK) for MARA. To solve IK, we will need the following:

  • The desired pose of the end-effector (by default, this is the last link in the “manipulator” chain): end_effector_state that we computed in the step above.
  • The number of attempts to be made at solving IK: 10
  • The timeout for each attempt: 0.1 s
std::size_t attempts = 10;
double timeout = 0.1;
bool found_ik = kinematic_state->setFromIK(joint_model_group, end_effector_state, attempts, timeout);

Now, we can print out the IK solution (if found):

if (found_ik)
{
  kinematic_state->copyJointGroupPositions(joint_model_group, joint_values);
  for (std::size_t i = 0; i < joint_names.size(); ++i)
  {
    ROS_INFO("Joint %s: %f", joint_names[i].c_str(), joint_values[i]);
  }
}
else
{
  ROS_INFO("Did not find IK solution");
}

We can also get the Jacobian from the RobotState.

Eigen::Vector3d reference_point_position(0.0, 0.0, 0.0);
Eigen::MatrixXd jacobian;
kinematic_state->getJacobian(joint_model_group,
                             kinematic_state->getLinkModel(joint_model_group->getLinkModelNames().back()),
                             reference_point_position, jacobian);
ROS_INFO_STREAM("Jacobian: \n" << jacobian << "\n");

To run the code, you will need a launch file that does two things:

  • Loads Mara's URDF and SRDF onto the parameter server, and
  • Puts the kinematics_solver configuration generated by the MoveIt! Setup Assistant onto the ROS parameter server in the namespace of the node that instantiates the classes in this tutorial.
<launch>
  <include file="$(find mara_moveit_config)/launch/planning_context.launch">
    <arg name="load_robot_description" value="true"/>
  </include>

  <node name="robot_model_and_robot_state_tutorial"
        pkg="mara_moveit_tutorials"
        type="robot_model_and_robot_state_tutorial"
        respawn="false" output="screen">
    <rosparam command="load"
              file="$(find mara_moveit_config)/config/kinematics.yaml"/>
  </node>
</launch>