Skip to content

Latest commit

 

History

History
91 lines (69 loc) · 4.97 KB

robot_model_and_robot_state_tutorial.rst

File metadata and controls

91 lines (69 loc) · 4.97 KB

Robot Model and Robot State

"That is a sweet robot" you might say.

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

The RobotModel and RobotState Classes

The :moveit_codedir:`RobotModel<moveit_core/robot_model/include/moveit/robot_model/robot_model.h>` and :moveit_codedir:`RobotState<moveit_core/robot_state/include/moveit/robot_state/robot_state.h>` classes are the core classes that give you access to a robot's kinematics.

The :moveit_codedir:`RobotModel<moveit_core/robot_model/include/moveit/robot_model/robot_model.h>` 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: :doc:`URDF and SRDF Tutorial </doc/examples/urdf_srdf/urdf_srdf_tutorial>`

The :moveit_codedir:`RobotState<moveit_core/robot_state/include/moveit/robot_state/robot_state.h>` contains information about the robot at a certain point in time, storing vectors of joint positions and optionally velocities and accelerations. This information can be used to obtain kinematic information about the robot that depends on its 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 the Panda.

Getting Started

If you haven't already done so, make sure you've completed the steps in :doc:`Getting Started </doc/tutorials/getting_started/getting_started>`.

Running the Code

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

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

ros2 launch moveit2_tutorials robot_model_and_robot_state_tutorial.launch.py

Expected Output

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

... [robot_model_and_state_tutorial]: Model frame: world
... [robot_model_and_state_tutorial]: Joint panda_joint1: 0.000000
... [robot_model_and_state_tutorial]: Joint panda_joint2: 0.000000
... [robot_model_and_state_tutorial]: Joint panda_joint3: 0.000000
... [robot_model_and_state_tutorial]: Joint panda_joint4: 0.000000
... [robot_model_and_state_tutorial]: Joint panda_joint5: 0.000000
... [robot_model_and_state_tutorial]: Joint panda_joint6: 0.000000
... [robot_model_and_state_tutorial]: Joint panda_joint7: 0.000000
... [robot_model_and_state_tutorial]: Current state is not valid
... [robot_model_and_state_tutorial]: Current state is valid
... [robot_model_and_state_tutorial]: Translation:
-0.368232
0.645742
0.752193

... [robot_model_and_state_tutorial]: Rotation:
 0.362374 -0.925408  -0.11093
 0.911735  0.327259  0.248275
 -0.193453 -0.191108  0.962317

... [robot_model_and_state_tutorial]: Joint panda_joint1: 2.263889
... [robot_model_and_state_tutorial]: Joint panda_joint2: 1.004608
... [robot_model_and_state_tutorial]: Joint panda_joint3: -1.125652
... [robot_model_and_state_tutorial]: Joint panda_joint4: -0.278822
... [robot_model_and_state_tutorial]: Joint panda_joint5: -2.150242
... [robot_model_and_state_tutorial]: Joint panda_joint6: 2.274891
... [robot_model_and_state_tutorial]: Joint panda_joint7: -0.774846
... [robot_model_and_state_tutorial]: Jacobian:
  -0.645742     -0.26783   -0.0742358    -0.315413    0.0224927    -0.031807 -2.77556e-17
  -0.368232     0.322474    0.0285092    -0.364197   0.00993438     0.072356  2.77556e-17
          0    -0.732023    -0.109128     0.218716   2.9777e-05     -0.11378 -1.04083e-17
          0    -0.769274    -0.539217     0.640569     -0.36792     -0.91475     -0.11093
          0    -0.638919      0.64923   -0.0973283     0.831769     -0.40402     0.248275
          1  4.89664e-12     0.536419     0.761708     0.415688  -0.00121099     0.962317

Note: Don't worry if your output has different ROS console format.

The Entire Code

The entire code can be seen :codedir:`here in the MoveIt GitHub project<examples/robot_model_and_robot_state/src/robot_model_and_robot_state_tutorial.cpp>`.

.. tutorial-formatter:: ./src/robot_model_and_robot_state_tutorial.cpp

The Launch File

To run the code, you will need a launch file that does two things:
  • Loads the Panda 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.
.. literalinclude:: ./launch/robot_model_and_robot_state_tutorial.launch.py