hpp-model Documentation

Introduction

This package implements forward kinematics for a kinematic chain. The kinematic chain is a tree of joints (hpp::model::Joint) that belongs to a robot (hpp::model::Device).

The position of each joint depends on the current configuration of the robot.

A body (hpp::model::Body) can be attached to each joint. Bodies carry

A hpp::model::HumanoidRobot is a device with accessors to specific joints like

  • left and right ankles,
  • left and right wrists,
  • gaze joint (that moves the cameras),
  • chest,
  • waist.

Main classes

Joints

In the following, we denote by $M = (R, \mathbf{T})$ a rigid-body motion with

  • $R\in SO(3)$ a rotation matrix, and
  • $\mathbf{T}\in\mathbf{R}^3$ a translation vector. The space of rigid-body motion is denoted by $SE(3)$. A point $\mathbf{x}\in\mathbf{R}^3$ is mapped by $(R, \mathbf{T})$ to

    \begin{equation*} \mathbf{y} = R \mathbf{x} + \mathbf{T} \end{equation*}

Joints are represented by abstract class hpp::model::Joint. A joint is a mapping from an input space (a Lie group or a vector space) to SE(3) the space of rigid-body motion. The mapping is called the joint internal motion.

The types of joints implemented in the package are the following:

The position of a joint is defined by the following relation

\begin{equation} P_{joint} = P_{parent} P_{joint/parent} M (\mathbf{x}_{joint}) \end{equation}

where

  • $ P_{joint} \in SE(3)$ is the position of the joint,
  • $ P_{parent} \in SE(3)$ is the position of the parent joint,
  • $ P_{joint/parent}$ is the position of the joint in the frame of its parent when the joint internal motion is identity,
  • $ \mathbf{x}_{joint}$ is the joint configuration, and
  • $ M $ is the joint internal motion as defined previously.

Joint configuration

Abstract class hpp::model::JointConfiguration aims at handling joint configuration and velocities. The main methods are the following:

Device

The class device represents either a robot as a kinematic chain, or a free-floating object (hence the name of the class).

The kinematic chain can be accessed via method hpp::model::Device::rootJoint.

Configuration

The joints are stored in a vector (hpp::model::device::getJointVector). The configuration of the robot (commonly denoted by $\mathbf{q}$ is a vector built by concatenation of joint configuration vectors in the order to the joint vector.

Velocity

The velocity of the robot (commonly denoted by $\mathbf{q}$ is represented by a vector built by concatenating joint velocities in the order of the joint vector.

`

Note:
Unlike the dimension of the joint configuration, the dimension of the joint velocity is equal to the number of degrees of freedom. For instance configuration of hpp::model::JointSO3 is of dimension 4 for 3 degrees of freedom. Therefore, the dimension of the robot velocity vector can be different from the dimension of the robot configuration vector.

Operations between configurations and velocities

The following operations are defined between configurations and velocities.

  • hpp::model::integrate Integrates a constant velocity during unit time,
  • hpp::model::difference returns the constant velocity that moves from one configuration to the other in unit time.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends