Qontrol
Qontrol::Model::GenericModel Class Referenceabstract
Inheritance diagram for Qontrol::Model::GenericModel:

Public Member Functions

void setRobotState (const RobotState &robot_state)
 Load the robot model given a urdf path. More...
 
auto getRobotState () -> RobotState
 Get the robot state (position, velocity, acceleration, and external torque) More...
 
virtual auto getTipFrameName () -> std::string=0
 Get the name of the tip frame in the model. More...
 
virtual auto getRootFrameName () -> std::string=0
 Get the name of the root frame in the model. More...
 
virtual auto getNrOfDegreesOfFreedom () -> int=0
 Get the robot number of degrees of freedom. More...
 
virtual void setJointPosition (Eigen::VectorXd joint_position)
 Set the robot current joint position. More...
 
virtual auto getJointPosition () -> Eigen::VectorXd
 get the robot current joint position More...
 
void setLowerJointPositionLimits (Eigen::VectorXd lim)
 Set the robot lower joint position limits. More...
 
void setUpperJointPositionLimits (Eigen::VectorXd lim)
 Set the robot upper joint position limits. More...
 
virtual auto getLowerJointPositionLimits () -> Eigen::VectorXd
 Get the robot lower joint position limits. More...
 
virtual auto getUpperJointPositionLimits () -> Eigen::VectorXd
 Get the robot upper joint position limits. More...
 
virtual void setJointVelocity (Eigen::VectorXd joint_velocity)
 Set the robot current joint velocity. More...
 
virtual auto getJointVelocity () -> Eigen::VectorXd
 Get the robot current joint velocity. More...
 
void setJointVelocityLimits (Eigen::VectorXd lim)
 Set the robot joint velocity limts. More...
 
auto getJointVelocityLimits () -> Eigen::VectorXd
 Get the robot joint velocity limts. More...
 
virtual void setJointAcceleration (Eigen::VectorXd joint_acceleration)
 Set the robot current joint acceleration. More...
 
virtual auto getJointAcceleration () -> Eigen::VectorXd
 Get the robot current joint acceleration. More...
 
virtual void setJointTorque (Eigen::VectorXd joint_torque)
 Set the robot current joint torque. More...
 
virtual auto getJointTorque () -> Eigen::VectorXd
 Get the robot current joint torque. More...
 
void setJointTorqueLimits (Eigen::VectorXd lim)
 Set the robot joint torque limits. More...
 
auto getJointTorqueLimits () -> Eigen::VectorXd
 Get the robot joint torque limits. More...
 
virtual void setExternalJointTorque (Eigen::VectorXd external_joint_torque)
 Set the robot current external joint torque. More...
 
virtual auto getExternalJointTorque () -> Eigen::VectorXd
 Get the robot current external joint torque. More...
 
virtual auto getJointCoriolisTorques () -> Eigen::VectorXd=0
 Get the vector representing the gravity effect associated to the \(g\) term in the equation of motion: \( M(q)\ddot{q} + c(q, \dot{q}) + g(q) = \tau \). Taken at the current robot state. More...
 
virtual auto getJointInertiaMatrix () -> Eigen::MatrixXd=0
 Get the matrix representing the joint space inertia matrix associated to the \(M(q)\) term in the equation of motion: \( M(q)\ddot{q} + c(q, \dot{q}) + g(q) = \tau \). Taken at the current robot state. More...
 
virtual auto getInverseJointInertiaMatrix () -> Eigen::MatrixXd=0
 Get the matrix representing the inverse of the joint space inertia matrix associated to the \(M(q)\) term in the equation of motion: \( M(q)\ddot{q} + c(q, \dot{q}) + g(q) = \tau \). Taken at the current robot state. More...
 
virtual auto getFramePose (const std::string &body_name) -> Eigen::Isometry3d=0
 Get the pose of the frame called \(\text_it{body_name}\) in the URDF wrt. the root frame. More...
 
virtual auto getTipFramePose () -> Eigen::Isometry3d=0
 Get the pose of the tip frame wrt. the root frame. More...
 
virtual auto getJacobian (const std::string &body_name) -> Eigen::MatrixXd=0
 Get the Jacobian matrix expressed at the frame name \(\textit{body_name}\) in the URDF wrt. the root frame. More...
 
virtual auto getJacobian (const std::string &body_name, const Eigen::Isometry3d &frame) -> Eigen::MatrixXd=0
 
virtual auto getJacobianTimeDerivativeQdot (const std::string &body_name) -> Eigen::VectorXd=0
 Get the vector representing the \(\dot{J}\dot{q}\) terme in the equation \(\dot{twist} = \dot{J}\dot{q} + J\ddot{q}\). More...
 
virtual auto getJacobianTimeDerivativeQdot (const std::string &body_name, const Eigen::Isometry3d &frame) -> Eigen::VectorXd=0
 Get the vector representing the \(\dot{J}\dot{q}\) terme in the equation \(\dot{twist} = \dot{J}\dot{q} + J\ddot{q}\). More...
 
virtual auto getFrameVelocity (const std::string &body_name) -> Eigen::Matrix< double, 6, 1 >=0
 Get the twist representing the velocity of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame. More...
 
virtual auto getFrameVelocity (const std::string &body_name, const Eigen::Isometry3d &frame) -> Eigen::Matrix< double, 6, 1 >=0
 Get the twist representing the \(\textit{frame}\) velocity wrt. the root frame. More...
 
virtual auto getTipFrameVelocity () -> Eigen::Matrix< double, 6, 1 >=0
 The twist representing the velocity of the tip frame wrt. the root frame. More...
 
virtual auto getJointAccelerationFromTorques (Eigen::VectorXd torque) -> Eigen::VectorXd=0
 
virtual auto getFrameAccelerationFromJointAcceleration (const std::string &body_name) -> Eigen::Matrix< double, 6, 1 >=0
 Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/acceleration. More...
 
virtual auto getFrameAccelerationFromJointAcceleration (const std::string &body_name, const Eigen::Isometry3d &frame) -> Eigen::Matrix< double, 6, 1 >=0
 Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/acceleration. More...
 
virtual auto getFrameAccelerationFromTorques (const std::string &body_name) -> Eigen::Matrix< double, 6, 1 >=0
 Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/torque/external torque. More...
 
virtual auto getFrameAccelerationFromTorques (const std::string &body_name, const Eigen::Isometry3d &frame) -> Eigen::Matrix< double, 6, 1 >=0
 Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/torque/external torque. More...
 
virtual auto getExternalWrench (const std::string &body_name) -> Eigen::Matrix< double, 6, 1 >=0
 Get the external wrench applied on the named \(\textit{body_name}\) in the URDF wrt. the root frame given the external joint torques applied on the robot. More...
 
virtual auto getExternalWrench (const std::string &body_name, const Eigen::Isometry3d &frame) -> Eigen::Matrix< double, 6, 1 >=0
 
auto integrate (Eigen::VectorXd q, Eigen::VectorXd v, double dt) -> Eigen::VectorXd
 

Static Public Member Functions

static auto skew (Eigen::Vector3d vector) -> Eigen::Matrix3d
 compute the skew symetry matrix of a vector. Usefull to perform cross products More...
 

Protected Attributes

Eigen::VectorXd lower_joint_position_limits
 
Eigen::VectorXd upper_joint_position_limits
 
Eigen::VectorXd joint_velocity_limits
 
Eigen::VectorXd joint_torque_limits
 

Member Function Documentation

◆ getExternalJointTorque()

auto Qontrol::Model::GenericModel::getExternalJointTorque ( ) -> Eigen::VectorXd
virtual

Get the robot current external joint torque.

Returns
A \(ndof\) vector representing the external torque measured on each joint (in Nm for a revolute joint and N for a prismatic joint )

◆ getExternalWrench()

virtual auto Qontrol::Model::GenericModel::getExternalWrench ( const std::string &  body_name) -> Eigen::Matrix< double, 6, 1 >
pure virtual

Get the external wrench applied on the named \(\textit{body_name}\) in the URDF wrt. the root frame given the external joint torques applied on the robot.

Parameters
body_nameThe name of the frame in the urdf.
Returns
Eigen::Vector6d

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getFrameAccelerationFromJointAcceleration() [1/2]

virtual auto Qontrol::Model::GenericModel::getFrameAccelerationFromJointAcceleration ( const std::string &  body_name) -> Eigen::Matrix< double, 6, 1 >
pure virtual

Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/acceleration.

Parameters
body_nameThe name of the frame in the urdf.
Returns
Eigen::Vector6d

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getFrameAccelerationFromJointAcceleration() [2/2]

virtual auto Qontrol::Model::GenericModel::getFrameAccelerationFromJointAcceleration ( const std::string &  body_name,
const Eigen::Isometry3d &  frame 
) -> Eigen::Matrix< double, 6, 1 >
pure virtual

Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/acceleration.

Parameters
body_nameThe name of the frame in the urdf.
Returns
Eigen::Vector6d

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getFrameAccelerationFromTorques() [1/2]

virtual auto Qontrol::Model::GenericModel::getFrameAccelerationFromTorques ( const std::string &  body_name) -> Eigen::Matrix< double, 6, 1 >
pure virtual

Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/torque/external torque.

Parameters
body_nameThe name of the frame in the urdf.
Returns
Eigen::Vector6d

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getFrameAccelerationFromTorques() [2/2]

virtual auto Qontrol::Model::GenericModel::getFrameAccelerationFromTorques ( const std::string &  body_name,
const Eigen::Isometry3d &  frame 
) -> Eigen::Matrix< double, 6, 1 >
pure virtual

Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/torque/external torque.

Parameters
body_nameThe name of the frame in the urdf.
Returns
Eigen::Vector6d

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getFramePose()

virtual auto Qontrol::Model::GenericModel::getFramePose ( const std::string &  body_name) -> Eigen::Isometry3d
pure virtual

Get the pose of the frame called \(\text_it{body_name}\) in the URDF wrt. the root frame.

Parameters
body_nameThe name of the frame in the urdf.
Returns
an Isometry.

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getFrameVelocity() [1/2]

virtual auto Qontrol::Model::GenericModel::getFrameVelocity ( const std::string &  body_name) -> Eigen::Matrix< double, 6, 1 >
pure virtual

Get the twist representing the velocity of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame.

Parameters
body_nameThe name of the frame in the urdf.
Returns
a twist.

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getFrameVelocity() [2/2]

virtual auto Qontrol::Model::GenericModel::getFrameVelocity ( const std::string &  body_name,
const Eigen::Isometry3d &  frame 
) -> Eigen::Matrix< double, 6, 1 >
pure virtual

Get the twist representing the \(\textit{frame}\) velocity wrt. the root frame.

Parameters
frameA frame expressed wrt. the root frame.
Returns
A twist

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getInverseJointInertiaMatrix()

virtual auto Qontrol::Model::GenericModel::getInverseJointInertiaMatrix ( ) -> Eigen::MatrixXd
pure virtual

Get the matrix representing the inverse of the joint space inertia matrix associated to the \(M(q)\) term in the equation of motion: \( M(q)\ddot{q} + c(q, \dot{q}) + g(q) = \tau \). Taken at the current robot state.

Returns
A \(ndof \times ndof\) matrix

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getJacobian() [1/2]

virtual auto Qontrol::Model::GenericModel::getJacobian ( const std::string &  body_name) -> Eigen::MatrixXd
pure virtual

Get the Jacobian matrix expressed at the frame name \(\textit{body_name}\) in the URDF wrt. the root frame.

Parameters
body_nameThe name of the frame in the urdf
Returns
A \(6 \times ndof\) Jacobian matrix.

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getJacobian() [2/2]

virtual auto Qontrol::Model::GenericModel::getJacobian ( const std::string &  body_name,
const Eigen::Isometry3d &  frame 
) -> Eigen::MatrixXd
pure virtual
Parameters
frameA frame expressed wrt. the root frame.
Returns
A \(6 \times ndof\) Jacobian matrix expressed at the \(\textit{frame}\) pose wrt. the root frame.

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getJacobianTimeDerivativeQdot() [1/2]

virtual auto Qontrol::Model::GenericModel::getJacobianTimeDerivativeQdot ( const std::string &  body_name) -> Eigen::VectorXd
pure virtual

Get the vector representing the \(\dot{J}\dot{q}\) terme in the equation \(\dot{twist} = \dot{J}\dot{q} + J\ddot{q}\).

Parameters
body_nameThe name of the frame in the urdf
Returns
A \(6\) vector

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getJacobianTimeDerivativeQdot() [2/2]

virtual auto Qontrol::Model::GenericModel::getJacobianTimeDerivativeQdot ( const std::string &  body_name,
const Eigen::Isometry3d &  frame 
) -> Eigen::VectorXd
pure virtual

Get the vector representing the \(\dot{J}\dot{q}\) terme in the equation \(\dot{twist} = \dot{J}\dot{q} + J\ddot{q}\).

Parameters
body_nameThe name of the frame in the urdf
Returns
A \(6\) vector

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getJointAcceleration()

auto Qontrol::Model::GenericModel::getJointAcceleration ( ) -> Eigen::VectorXd
virtual

Get the robot current joint acceleration.

Returns
A \(ndof\) vector representing the current robot joint acceleration

◆ getJointCoriolisTorques()

virtual auto Qontrol::Model::GenericModel::getJointCoriolisTorques ( ) -> Eigen::VectorXd
pure virtual

Get the vector representing the gravity effect associated to the \(g\) term in the equation of motion: \( M(q)\ddot{q} + c(q, \dot{q}) + g(q) = \tau \). Taken at the current robot state.

Returns
A f$ndof \( vector . */ virtual auto getJointGravityTorques() -> Eigen::VectorXd = 0; /** @brief Get the vector representing the Coriolis effect associated to the \)@_fakenlc(q,
{q} )\f$ term in the equation of motion: \f$ M(q)\ddot{q} +

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getJointInertiaMatrix()

virtual auto Qontrol::Model::GenericModel::getJointInertiaMatrix ( ) -> Eigen::MatrixXd
pure virtual

Get the matrix representing the joint space inertia matrix associated to the \(M(q)\) term in the equation of motion: \( M(q)\ddot{q} + c(q, \dot{q}) + g(q) = \tau \). Taken at the current robot state.

Returns
A \(ndof \times ndof\) matrix

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getJointPosition()

auto Qontrol::Model::GenericModel::getJointPosition ( ) -> Eigen::VectorXd
virtual

get the robot current joint position

Returns
A \(ndof\) vector representing the current robot joint position

◆ getJointTorque()

auto Qontrol::Model::GenericModel::getJointTorque ( ) -> Eigen::VectorXd
virtual

Get the robot current joint torque.

Returns
A \(ndof\) vector representing the current robot joint torque

◆ getJointTorqueLimits()

auto Qontrol::Model::GenericModel::getJointTorqueLimits ( ) -> Eigen::VectorXd

Get the robot joint torque limits.

Returns
The robot torque limits

◆ getJointVelocity()

auto Qontrol::Model::GenericModel::getJointVelocity ( ) -> Eigen::VectorXd
virtual

Get the robot current joint velocity.

Returns
A \(ndof\) vector representing the current robot joint velocity

◆ getJointVelocityLimits()

auto Qontrol::Model::GenericModel::getJointVelocityLimits ( ) -> Eigen::VectorXd

Get the robot joint velocity limts.

Returns
The robot velocity limits

◆ getLowerJointPositionLimits()

auto Qontrol::Model::GenericModel::getLowerJointPositionLimits ( ) -> Eigen::VectorXd
virtual

Get the robot lower joint position limits.

Returns
The robot lower position limits

◆ getNrOfDegreesOfFreedom()

virtual auto Qontrol::Model::GenericModel::getNrOfDegreesOfFreedom ( ) -> int
pure virtual

Get the robot number of degrees of freedom.

Returns
The robot number of degrees of freedom

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getRobotState()

auto Qontrol::Model::GenericModel::getRobotState ( ) -> RobotState

Get the robot state (position, velocity, acceleration, and external torque)

Returns
The robot state

◆ getRootFrameName()

virtual auto Qontrol::Model::GenericModel::getRootFrameName ( ) -> std::string
pure virtual

Get the name of the root frame in the model.

Returns
The name of the root frame

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getTipFrameName()

virtual auto Qontrol::Model::GenericModel::getTipFrameName ( ) -> std::string
pure virtual

Get the name of the tip frame in the model.

Returns
The name of the tip frame

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getTipFramePose()

virtual auto Qontrol::Model::GenericModel::getTipFramePose ( ) -> Eigen::Isometry3d
pure virtual

Get the pose of the tip frame wrt. the root frame.

Returns
an Isometry.

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getTipFrameVelocity()

virtual auto Qontrol::Model::GenericModel::getTipFrameVelocity ( ) -> Eigen::Matrix< double, 6, 1 >
pure virtual

The twist representing the velocity of the tip frame wrt. the root frame.

Returns
A twist

Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.

◆ getUpperJointPositionLimits()

auto Qontrol::Model::GenericModel::getUpperJointPositionLimits ( ) -> Eigen::VectorXd
virtual

Get the robot upper joint position limits.

Returns
The robot upper position limits

◆ setExternalJointTorque()

void Qontrol::Model::GenericModel::setExternalJointTorque ( Eigen::VectorXd  external_joint_torque)
virtual

Set the robot current external joint torque.

Parameters
external_joint_torquethe robot external joint torque

◆ setJointAcceleration()

void Qontrol::Model::GenericModel::setJointAcceleration ( Eigen::VectorXd  joint_acceleration)
virtual

Set the robot current joint acceleration.

Parameters
joint_accelerationthe robot current joint acceleration

◆ setJointPosition()

void Qontrol::Model::GenericModel::setJointPosition ( Eigen::VectorXd  joint_position)
virtual

Set the robot current joint position.

Parameters
joint_positionthe robot current joint position

◆ setJointTorque()

void Qontrol::Model::GenericModel::setJointTorque ( Eigen::VectorXd  joint_torque)
virtual

Set the robot current joint torque.

Parameters
joint_torquethe robot current joint torque

◆ setJointTorqueLimits()

void Qontrol::Model::GenericModel::setJointTorqueLimits ( Eigen::VectorXd  lim)

Set the robot joint torque limits.

Parameters
limThe robot upper velocity limits
Remarks
This functions is automatically called by loadModelFromString to set the joint torque limits according to the urdf model

◆ setJointVelocity()

void Qontrol::Model::GenericModel::setJointVelocity ( Eigen::VectorXd  joint_velocity)
virtual

Set the robot current joint velocity.

Parameters
joint_velocitythe robot current joint velocity

◆ setJointVelocityLimits()

void Qontrol::Model::GenericModel::setJointVelocityLimits ( Eigen::VectorXd  lim)

Set the robot joint velocity limts.

Parameters
limThe robot velocity limits
Remarks
This functions is automatically called by loadModelFromString to set the joint velocity limits according to the urdf model

◆ setLowerJointPositionLimits()

void Qontrol::Model::GenericModel::setLowerJointPositionLimits ( Eigen::VectorXd  lim)

Set the robot lower joint position limits.

Parameters
limThe robot lower position limits
Remarks
This functions is automatically called by loadModelFromString to set the lower joint position limits according to the urdf model

◆ setRobotState()

void Qontrol::Model::GenericModel::setRobotState ( const RobotState robot_state)

Load the robot model given a urdf path.

Parameters
urdf_patha urdf string representing the robot description
root_linkThe name of the root link in the urdf file. By default the first link in the urdf is taken.
tip_linkThe name of the tip link in the urdf file. By default the last link in the urdf is taken.

Sets the robot state (position, velocity, acceleration, and external torque)

Parameters
robot_statethe robot state

◆ setUpperJointPositionLimits()

void Qontrol::Model::GenericModel::setUpperJointPositionLimits ( Eigen::VectorXd  lim)

Set the robot upper joint position limits.

Parameters
limThe robot upper position limits
Remarks
This functions is automatically called by loadModelFromString to set the upper joint position limits according to the urdf model

◆ skew()

auto Qontrol::Model::GenericModel::skew ( Eigen::Vector3d  vector) -> Eigen::Matrix3d
static

compute the skew symetry matrix of a vector. Usefull to perform cross products

Parameters
vectora vector
Returns
The skew matrix associated to \(vecotr\)

The documentation for this class was generated from the following files: