Background

XBotInterface

_images/XBotInterface_Img_0.png

XBot::Joint

The most atomic component is XBot::Joint, which collects all joint states and commands, and provides the corresponding getters and setters. Joints are organized into kinematic chains, which are implemented by the XBot::KinematicChain class.

XBot::KinematicChain

Each kinematic chain of the robot (as described by the SRDF file) is parsed into an object of this class. It stores internally the vector of joints belonging to the chain, and provides chain-wise getters and setters for the robot state, so that is easy for the user to command or read a single chain of the robot. Moreover, the KinematicChain provides the ability of getting sensors attached to it. The set of all kinematic chains is organized into the main object of the library, the XBot::XBotInterface.

XBot::XBotInterface

XBotInterface provides a view of the robot as a set of kinematic chains. Internally, it stores the vector of all chains that make up the robot. It provides robot-wise getters and setters for the robot state, and for all sensors attached to it.

XBot::RobotInterface

The XBot::XBotInterface library acts as a simple, organized container for the robot state. The XBot::RobotInterface inherits from such a class, and adds a few method that allow for communication from/to a robot:

  • sense() acquires data from the robot sensors.

  • move() sends commands to the robot actuators.

Depending on the actual implementation of the RobotInterface being used, these methods will perform different operations, e.g.

  • reading/publishing to suitable ROS topics

  • reading/writing to suitable YARP ports.

  • reading/writing to suitable OROCOS ports.

  • reading/writing directly from the robot hardware abstraction layer as in the case of the XBotRT implementation.

XBot::ModelInterface

XBot::ModelInterface adds to XBot::XBotInterface methods for computing kinematics/dynamics quantities corresponding to the robot state described by the underlying XBotInterface object. These include:

  • forward kinematics (link pose, orientation, twists, jacobians, jdotqdot terms, centre-of-mass, centroidal momentum and centroidal momentum matrix, …).

  • inverse dynamics (gravity compensation torques, inertia matrix, …).

  • forward dynamics.

Before computing any of these quantities, an update() method must be called. T his has the effect of updating the underlying back-end with the joint states stored inside the XBot::ModelInterface.

Moreover, since robot and model objects derive from a common base class, it is very simple to exchange information between them. More specifically:

  • a model can be synchronized to the actual state of the robot by calling a syncFrom() method on the model, and providing the robot as argument.

  • a model state can be used as desired state for the robot, by calling a setReferenceFrom() method on the robot and providing a model as argument. Both these methods work also in the case that the model only represents a subset of the robot kinematic tree (e.g. just the upperbody of a humanoid robot).

The ModelInterface uses external library to compute kinematics/dynamics quantities such as RBDL.

Floating Base Robot

Some of the most interesting dynamical systems come from the borderline science fiction robots that walk around on two or four legs. These robots are what we call floating-based robots. The base isn’t bolted to the floor. It instead floats above the ground and moves from place to place with the robot. At any moment in time, the robot must choose carefully torques to apply that will induce the perfect reaction forces from the environment at its points of contact so that those reaction forces correctly manipulate its free floating base.

_images/XBotInterface_Img_1.png

We also now have an underactuated system. Since the base of the robot is free to move around, we can no longer fully control all degrees of freedom. We often choose the floating-base of the robot to be situated somewhere around the robot’s torso near the robot’s center of mass. These floating base dimensions consist of three positional coordinates and three rotational components totaling a full six degrees of freedom that we can’t directly control. The robot doesn’t have a collection of jet engines attached to its torso that can directly induce forces and torques on the floating base. All forces and torques on that base must be generated by some contact with the environment. Physically this means that in order to fully control these unactuated degrees of freedom, the robot needs to reason about how it can generate the requisite reaction forces from the environment around it:

_images/XBotInterface_Img_2.png

XBotInterface API’s Translated

XBotInterface

Methods and Class description

Method

Input

Output

getEnabledJointId

NONE

int Vector of joints enabled

getJointPosition

NONE

double Vector of joints position

getMotorPosition

NONE

double Vector of motors position

getJointVelocity

NONE

double Vector of joints velocity

getMotorVelocity

NONE

double Vector of motors velocity

getJointAcceleration

NONE

double Vector of joints acceleration

getJointEffort

NONE

double Vector of joints torque

getTemperature

NONE

double Vector of joints temperature

getStiffness

NONE

double Vector of joints stiffnes

getDamping

NONE

double Vector of joints damping

getPositionReference

NONE

double Vector of joints position reference

getVelocityReference

NONE

double Vector of joints velocity reference

getEffortReference

NONE

double Vector of joints torque reference

setPositionReference

double Vector of joints position reference

NONE

setJointPosition

double Vector of joints position reference

NONE

setMotorPosition

double Vector of motors position reference

NONE

setVelocityReference

double Vector of joints velocity reference

NONE

setJointVelocity

double Vector of joints velocity reference

NONE

setMotorVelocity

double Vector of motors velocity reference

NONE

setJointAcceleration

double Vector of joints acceleration reference

NONE

setEffortReference

double Vector of joints torque reference

NONE

setJointEffort

double Vector of joints torque reference

NONE

setTemperature

double Vector of joints temperature reference

NONE

setStiffness

double Vector of joints stiffness reference

NONE

setDamping

double Vector of joints damping reference

NONE

enforceJointLimits

double Vector of joints position reference

NONE

enforceVelocityLimit

double Vector of joints velocity reference

NONE

enforceEffortLimit

double Vector of joints torque reference

NONE

getJointLimits

NONE

double Vectors of mechanical position limits

getVelocityLimits

NONE

double Vector of mechanical velocity limits

getEffortLimits

NONE

double Vector of mechanical torque limits

checkJointLimits

BOOL value if position limits are satisfied

double Vector of joints position reference

checkVelocityLimits

BOOL value if velocity limits are satisfied

double Vector of joints velocity reference

checkEffortLimits

BOOL value if torque limits are satisfied

double Vector of joints torque reference

getForceTorque

NONE

ForceTorqueSensor::ConstPtr MAP

getForceTorque

Force Torque Sensor ID

ForceTorqueSensor::ConstPtr

getImu

NONE

ImuSensor::ConstPtr MAP

getImu

IMU Sensor ID

ImuSensor::ConstPtr

RobotInterface

Methods and Class description

Method

Input

Output

sense

NONE

BOOL if the sense is successful

move

NONE

BOOL if the move is successful

setReferenceFrom

ModelInterface

BOOL if the synchronization is allowed

ModelInterface

Methods and Class description

Method

Input

Output

update

NONE

BOOL if the update is successful

syncFrom

XBotInterface

BOOL if the synchronization is allowed

getFloatingBasePose

NONE

BOOL if the the model is floating base

getFloatingBaseTwist

NONE

BOOl if the the model is floating base

setFloatingBasePose

Homogeneous transformation

BOOL if the floating_base_pose frame is valid

setFloatingBaseState

Homogeneous transformation and Twist vector

BOOL if the the model is floating base

setFloatingBaseOrientation

Rotation matrix

BOOL if the the model is floating base

setFloatingBaseTwist

Twist vector

BOOL if the the model is floating base

setFloatingBaseAngularVelocity

Angulator velocity

BOOL if the the model is floating base

getGravity

NONE

Gravity vector

getGravity

Reference frame

Gravity vector, BOOL if the reference frame is valid

setGravity

Gravity vector

NONE

setGravity

Reference frame, Gravity vector

BOOL if the reference frame is a valid link name

getPose

Source and Target frame

Homogeneous transformation, BOOL if the source/target frame are valid

getPose

Source frame

Homogeneous transformation, BOOL if the source frame is valid

getOrientation

Source and Target frame

Rotation matrix, BOOL if the source/target frame are valid

getOrientation

Source frame

Rotation matrix, BOOL if the source frame is valid

getPointPosition

Source, Target frame and source point vector

Point vector, BOOL if the source/target frame are valid

getPointPosition

Source frame and source point vector

Point vector, BOOL if the source frame is valid

getPointAcceleration

Link Name and point vector

Acceleration vector, BOOL if the link name is valid

getCOM

NONE

COM Point vector

getCOM

Reference frame

COM Point vector, BOOL if the reference frame is valid

getCOMVelocity

NONE

COM Velocity vector

getCOMAcceleration

NONE

COM Acceleration vector

getCentroidalMomentum

NONE

Centroidal Momentum

getCentroidalMomentumMatrix

NONE

Centroidal Momentum Matrix

getCentroidalMomentumMatrix

NONE

Centroidal Momentum Matrix, The d(CMM)/dt * qdot term

getVelocityTwist

Link Name

Twist velocity vector, BOOL if the link name is valid

getAccelerationTwist

Link Name

Twist acceleration vector, BOOL if the link name is valid

getRelativeVelocityTwist

Link and Base Link Name

Twist velocity vector, BOOL if the link and base link names are valid

getRelativeAccelerationTwist

Link and Base Link Name

Twist acceleration vector, BOOL if the link and base link names are valid

getJacobian

Link Name

Jacobina Matrix, BOOL if the link name is valid

getJacobian

Link Name and reference point

Jacobina Matrix, BOOL if the link name is valid

getJacobian

Link Name and Target Frame

Jacobina Matrix, BOOL if the link name and target frame are valid

getRelativeJacobian

Target and Base Link Name

Jacobina Matrix, BOOL if the target and base link name are valid

getCOMJacobian

NONE

COM Jacobian Matrix

getCOMJacobian

NONE

COM Jacobian Matrix The d(Jcom)/dt * qdot term

getPosturalJacobian

NONE

Postural Jacobian Matrix

computeJdotQdot

Link Name and point vector

Jacobian time derivative by the joint velocity BOOL if link name is valid

computeRelativeJdotQdot

Target and Base Link Name

Jacobian time derivative by the joint velocity BOOL if target and base link name are valid

getMass

NONE

Mass of the robot

getInertiaMatrix

NONE

Inertia matrix

getInertiaInverse

NONE

Inverse Inertia matrix

computeNonlinearTerm

NONE

The non-linear torques vector

computeGravityCompensation

NONE

The gravity compensation torque vector

computeInverseDynamics

NONE

The inverse dynamics torque vector

computeConstrainedInverseDynamics

Jacobian and weight vector

The inverse dynamics torque vector

ForceTorqueSensor

Methods and Class description

Method

Input

Output

getForce

NONE

Force vector

getToque

NONE

Torque vector

getWrench

NONE

Wrench vector

IMUSensor

Methods and Class description

Method

Input

Output

getOrientation

NONE

Orientation matrix

getOrientation

NONE

Quaternion

getLinearAcceleration

NONE

Linear Acceleration vector

getAngularVelocity

NONE

Angular Velocity vector