robotoc
robotoc - efficient ROBOT Optimal Control solvers
Loading...
Searching...
No Matches
robotoc::Robot Class Reference

Dynamics and kinematics model of robots. Wraps pinocchio::Model and pinocchio::Data. Includes contacts. More...

#include <robot.hpp>

Public Types

using Vector6d = Eigen::Matrix< double, 6, 1 >
 

Public Member Functions

 Robot (const RobotModelInfo &robot_model_info)
 Constructs a robot model according to the input model info. More...
 
 Robot ()
 Default constructor. More...
 
 ~Robot ()=default
 Default destructor. More...
 
 Robot (const Robot &)=default
 Default copy constructor. More...
 
Robotoperator= (const Robot &)=default
 Default copy assign operator. More...
 
 Robot (Robot &&) noexcept=default
 Default move constructor. More...
 
Robotoperator= (Robot &&) noexcept=default
 Default move assign operator. More...
 
template<typename TangentVectorType , typename ConfigVectorType >
void integrateConfiguration (const Eigen::MatrixBase< TangentVectorType > &v, const double integration_length, const Eigen::MatrixBase< ConfigVectorType > &q) const
 Integrates the generalized velocity, that is, performs q <- q + integration_length * v like computation on the configuration manifolds. More...
 
template<typename ConfigVectorType1 , typename TangentVectorType , typename ConfigVectorType2 >
void integrateConfiguration (const Eigen::MatrixBase< ConfigVectorType1 > &q, const Eigen::MatrixBase< TangentVectorType > &v, const double integration_length, const Eigen::MatrixBase< ConfigVectorType2 > &q_integrated) const
 Integrates the generalized velocity, that is, performs q_integrated = q + integration_length * v like computation on the configuration manifolds. More...
 
template<typename ConfigVectorType , typename TangentVectorType , typename MatrixType1 , typename MatrixType2 >
void dIntegrateTransport_dq (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< MatrixType1 > &Jin, const Eigen::MatrixBase< MatrixType2 > &Jout) const
 Transport the Jacobian w.r.t. the configuration evaluated at the integrated configuration q + v to q. More...
 
template<typename ConfigVectorType , typename TangentVectorType , typename MatrixType1 , typename MatrixType2 >
void dIntegrateTransport_dv (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< MatrixType1 > &Jin, const Eigen::MatrixBase< MatrixType2 > &Jout) const
 Transport the Jacobian w.r.t. the generalized velocity evaluated at the integrated configuration q + v to q. More...
 
template<typename ConfigVectorType1 , typename ConfigVectorType2 , typename TangentVectorType >
void subtractConfiguration (const Eigen::MatrixBase< ConfigVectorType1 > &qf, const Eigen::MatrixBase< ConfigVectorType2 > &q0, const Eigen::MatrixBase< TangentVectorType > &qdiff) const
 Computes qf - q0 at the tangent space. The result means that the unit velocity from initial configuration q0 to terminal configuration qf. More...
 
template<typename ConfigVectorType1 , typename ConfigVectorType2 , typename MatrixType >
void dSubtractConfiguration_dqf (const Eigen::MatrixBase< ConfigVectorType1 > &qf, const Eigen::MatrixBase< ConfigVectorType2 > &q0, const Eigen::MatrixBase< MatrixType > &dqdiff_dqf) const
 Computes the partial derivative of the function of subtraction qf - q0 w.r.t. the terminal configuration qf. More...
 
template<typename ConfigVectorType1 , typename ConfigVectorType2 , typename MatrixType >
void dSubtractConfiguration_dq0 (const Eigen::MatrixBase< ConfigVectorType1 > &qf, const Eigen::MatrixBase< ConfigVectorType2 > &q0, const Eigen::MatrixBase< MatrixType > &dqdiff_dq0) const
 Computes the partial derivative of the function of subtraction qf - q0 w.r.t. the initial configuration qf. More...
 
template<typename ConfigVectorType1 , typename ConfigVectorType2 , typename ConfigVectorType3 >
void interpolateConfiguration (const Eigen::MatrixBase< ConfigVectorType1 > &q1, const Eigen::MatrixBase< ConfigVectorType2 > &q2, const double t, const Eigen::MatrixBase< ConfigVectorType3 > &qout) const
 Computes an interpolation of two configurations by (1.0 - t) * s1 + t * s2. More...
 
template<typename ConfigVectorType , typename MatrixType >
void integrateCoeffWiseJacobian (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< MatrixType > &J) const
 Transforms the Jacobian w.r.t. configuration to tangentspace. More...
 
template<typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 >
void updateKinematics (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
 Updates the kinematics of the robot. The frame placements, frame velocity, frame acceleration, and the relevant Jacobians are calculated. More...
 
template<typename ConfigVectorType , typename TangentVectorType >
void updateKinematics (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
 Updates the kinematics of the robot. The frame placements, frame velocity, and the relevant Jacobians are calculated. More...
 
template<typename ConfigVectorType >
void updateKinematics (const Eigen::MatrixBase< ConfigVectorType > &q)
 Updates the kinematics of the robot. The frame placements and and the relevant Jacobians are calculated. More...
 
template<typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 >
void updateFrameKinematics (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
 Updates the frame kinematics of the robot. The frame placements, velocities, and accelerations are calculated. More...
 
template<typename ConfigVectorType , typename TangentVectorType >
void updateFrameKinematics (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
 Updates the frame kinematics of the robot. The frame placements and velocities are calculated. More...
 
template<typename ConfigVectorType >
void updateFrameKinematics (const Eigen::MatrixBase< ConfigVectorType > &q)
 Updates the frame kinematics of the robot. The frame placements are calculated. More...
 
const Eigen::Vector3d & framePosition (const int frame_id) const
 Returns the position of the frame. Before calling this function, updateKinematics() or updateFrameKinematics() must be called. More...
 
const Eigen::Vector3d & framePosition (const std::string &frame_name) const
 Returns the position of the frame. Before calling this function, updateKinematics() or updateFrameKinematics() must be called. More...
 
const Eigen::Matrix3d & frameRotation (const int frame_id) const
 Returns the rotation matrix of the frame. Before calling this
function, updateKinematics() or updateFrameKinematics() must be called. More...
 
const Eigen::Matrix3d & frameRotation (const std::string &frame_name) const
 Returns the rotation matrix of the frame. Before calling this
function, updateKinematics() or updateFrameKinematics() must be called. More...
 
const SE3framePlacement (const int frame_id) const
 Returns the SE(3) of the frame. Before calling this function, updateKinematics() or updateFrameKinematics() must be called. More...
 
const SE3framePlacement (const std::string &frame_name) const
 Returns the SE(3) of the frame. Before calling this function, updateKinematics() or updateFrameKinematics() must be called. More...
 
const Eigen::Vector3d & CoM () const
 Returns the position of the center of mass. Before calling this function, updateKinematics() or updateFrameKinematics() must be called. More...
 
Eigen::Vector3d frameLinearVelocity (const int frame_id, const pinocchio::ReferenceFrame reference_frame=pinocchio::LOCAL_WORLD_ALIGNED) const
 Returns the linear (translational) velocity of the frame. Before calling
this function, updateKinematics() or updateFrameKinematics() must be called. More...
 
Eigen::Vector3d frameLinearVelocity (const std::string &frame_name, const pinocchio::ReferenceFrame reference_frame=pinocchio::LOCAL_WORLD_ALIGNED) const
 Returns the linear (translational) velocity of the frame. Before calling
this function, updateKinematics() or updateFrameKinematics() must be called. More...
 
Eigen::Vector3d frameAngularVelocity (const int frame_id, const pinocchio::ReferenceFrame reference_frame=pinocchio::LOCAL_WORLD_ALIGNED) const
 Returns the angular velocity of the frame. Before calling
this function, updateKinematics() or updateFrameKinematics() must be called. More...
 
Eigen::Vector3d frameAngularVelocity (const std::string &frame_name, const pinocchio::ReferenceFrame reference_frame=pinocchio::LOCAL_WORLD_ALIGNED) const
 Returns the angular velocity of the frame. Before calling
this function, updateKinematics() or updateFrameKinematics() must be called. More...
 
Vector6d frameSpatialVelocity (const int frame_id, const pinocchio::ReferenceFrame reference_frame=pinocchio::LOCAL_WORLD_ALIGNED) const
 Returns the spatial velocity of the frame. Before calling
this function, updateKinematics() or updateFrameKinematics() must be called. More...
 
Vector6d frameSpatialVelocity (const std::string &frame_name, const pinocchio::ReferenceFrame reference_frame=pinocchio::LOCAL_WORLD_ALIGNED) const
 Returns the spatial velocity of the frame. Before calling
this function, updateKinematics() or updateFrameKinematics() must be called. More...
 
const Eigen::Vector3d & CoMVelocity () const
 Returns the linear velocity of the center of mass expressed in the world frame. Before calling this function, updateKinematics() or updateFrameKinematics() must be called. More...
 
template<typename MatrixType >
void getFrameJacobian (const int frame_id, const Eigen::MatrixBase< MatrixType > &J)
 Computes the Jacobian of the frame position expressed in the local coordinate. Before calling this function, updateKinematics() must be called. More...
 
template<typename MatrixType >
void getCoMJacobian (const Eigen::MatrixBase< MatrixType > &J) const
 Gets the Jacobian of the position of the center of mass. Before calling this function, updateKinematics() must be called. More...
 
template<typename Vector3dType >
void transformFromLocalToWorld (const int frame_id, const Eigen::Vector3d &vec_local, const Eigen::MatrixBase< Vector3dType > &vec_world) const
 Transforms 3D quantity from local frame to the world frame. More...
 
template<typename Vector3dType , typename MatrixType >
void getJacobianTransformFromLocalToWorld (const int frame_id, const Eigen::MatrixBase< Vector3dType > &vec_world, const Eigen::MatrixBase< MatrixType > &J)
 Jacobian of the transformation mapping of a 3D quantity from local frame to the world frame. More...
 
template<typename VectorType >
void computeBaumgarteResidual (const ContactStatus &contact_status, const Eigen::MatrixBase< VectorType > &baumgarte_residual)
 Computes the residual of the contact constriants represented by Baumgarte's stabilization method. Before calling this function, updateKinematics() must be called. More...
 
template<typename MatrixType1 , typename MatrixType2 , typename MatrixType3 >
void computeBaumgarteDerivatives (const ContactStatus &contact_status, const Eigen::MatrixBase< MatrixType1 > &baumgarte_partial_dq, const Eigen::MatrixBase< MatrixType2 > &baumgarte_partial_dv, const Eigen::MatrixBase< MatrixType3 > &baumgarte_partial_da)
 Computes the partial derivatives of the contact constriants represented by the Baumgarte's stabilization method. Before calling this function, updateKinematics() must be called. More...
 
template<typename VectorType >
void computeImpactVelocityResidual (const ImpactStatus &impact_status, const Eigen::MatrixBase< VectorType > &velocity_residual) const
 Computes the residual of the impact velocity constraint. Before calling this function, updateKinematics() must be called. More...
 
template<typename MatrixType1 , typename MatrixType2 >
void computeImpactVelocityDerivatives (const ImpactStatus &impact_status, const Eigen::MatrixBase< MatrixType1 > &velocity_partial_dq, const Eigen::MatrixBase< MatrixType2 > &velocity_partial_dv)
 Computes the partial derivatives of the impact velocity constraint. Before calling this function, updateKinematics() must be called. More...
 
template<typename VectorType >
void computeContactPositionResidual (const ImpactStatus &impact_status, const Eigen::MatrixBase< VectorType > &position_residual)
 Computes the residual of the contact position constraint at the impact. Before calling this function, updateKinematics() must be called. More...
 
template<typename MatrixType >
void computeContactPositionDerivative (const ImpactStatus &impact_status, const Eigen::MatrixBase< MatrixType > &position_partial_dq)
 Computes the partial derivative of the contact position at the impact. Before calling this function, updateKinematics() must be called. More...
 
void setContactForces (const ContactStatus &contact_status, const std::vector< Vector6d > &f)
 Set contact forces in this robot model for each active contacts.
More...
 
void setImpactForces (const ImpactStatus &impact_status, const std::vector< Vector6d > &f)
 Set impact forces in this robot model for each active impacts. More...
 
template<typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename TangentVectorType3 >
void RNEA (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const Eigen::MatrixBase< TangentVectorType3 > &tau)
 Computes inverse dynamics, i.e., generalized torques corresponding for given configuration, velocity, acceleration, and contact forces. If the robot has contacts, update contact forces via setContactForces() before calling this function. More...
 
template<typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename MatrixType1 , typename MatrixType2 , typename MatrixType3 >
void RNEADerivatives (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const Eigen::MatrixBase< MatrixType1 > &dRNEA_partial_dq, const Eigen::MatrixBase< MatrixType2 > &dRNEA_partial_dv, const Eigen::MatrixBase< MatrixType3 > &dRNEA_partial_da)
 Computes the partial dervatives of the function of inverse dynamics with respect to the configuration, velocity, and acceleration. If the robot has contacts, update contact forces via setContactForces() before calling this function. More...
 
template<typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 >
void RNEAImpact (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &dv, const Eigen::MatrixBase< TangentVectorType2 > &res)
 Computes the residual of the impact dynamics for given configuration and impact change in the generalized velocity, and impact forces by using RNEA. Before call this function, update contact forces via setImpactForces(). More...
 
template<typename ConfigVectorType , typename TangentVectorType , typename MatrixType1 , typename MatrixType2 >
void RNEAImpactDerivatives (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &dv, const Eigen::MatrixBase< MatrixType1 > &dRNEA_partial_dq, const Eigen::MatrixBase< MatrixType2 > &dRNEA_partial_ddv)
 Computes the partial dervatives of the function of impuse dynamics with respect to configuration and impact changes in the velocity. Before calling this function, update contact forces via setImpactForces(). More...
 
template<typename MatrixType1 , typename MatrixType2 >
void computeMinv (const Eigen::MatrixBase< MatrixType1 > &M, const Eigen::MatrixBase< MatrixType2 > &Minv)
 Computes the inverse of the joint inertia matrix M. More...
 
template<typename MatrixType1 , typename MatrixType2 , typename MatrixType3 >
void computeMJtJinv (const Eigen::MatrixBase< MatrixType1 > &M, const Eigen::MatrixBase< MatrixType2 > &J, const Eigen::MatrixBase< MatrixType3 > &MJtJinv)
 Computes the inverse of the contact dynamics matrix [[M J^T], [J O]]. More...
 
Eigen::VectorXd generateFeasibleConfiguration () const
 Generates feasible configuration randomly. More...
 
template<typename ConfigVectorType >
void normalizeConfiguration (const Eigen::MatrixBase< ConfigVectorType > &q) const
 Normalizes a configuration vector. More...
 
int frameId (const std::string &frame_name) const
 Gets the id of the specified frame. More...
 
std::string frameName (const int frame_id) const
 Gets the name of the specified frame. More...
 
double totalMass () const
 Returns the total mass of this robot model. More...
 
double totalWeight () const
 Returns the total weight of this robot model. More...
 
int dimq () const
 Returns the dimensiton of the configuration. More...
 
int dimv () const
 Returns the dimensiton of the velocity, i.e, tangent space. More...
 
int dimu () const
 Returns the dimensiton of the velocity, i.e, tangent space. More...
 
int max_dimf () const
 Returns the maximum dimension of the contacts. More...
 
int dim_passive () const
 Returns the dimensiton of the generalized torques corresponding to the passive joints. More...
 
bool hasFloatingBase () const
 Returns true if the robot has a floating base and false if not. More...
 
int maxNumContacts () const
 Returns the maximum number of the contacts. More...
 
int maxNumPointContacts () const
 Returns the maximum number of the point contacts. More...
 
int maxNumSurfaceContacts () const
 Returns the maximum number of the surface contacts. More...
 
ContactType contactType (const int contact_index) const
 Returns the type of the contact. More...
 
std::vector< ContactTypecontactTypes () const
 Returns the types of the contacts. More...
 
std::vector< int > contactFrames () const
 Retruns the indices of the frames involving the point or surface contacts. More...
 
std::vector< std::string > contactFrameNames () const
 Retruns the names of the contact frames involving the point or. More...
 
std::vector< int > pointContactFrames () const
 Retruns the indices of the frames involving the contacts. More...
 
std::vector< std::string > pointContactFrameNames () const
 Retruns the names of the frames involving the contacts. More...
 
std::vector< int > surfaceContactFrames () const
 Retruns the indices of the frames involving the surface contacts. More...
 
std::vector< std::string > surfaceContactFrameNames () const
 Retruns the names of the frames involving the surface contacts. More...
 
ContactStatus createContactStatus () const
 Creates a ContactStatus for this robot model. More...
 
ImpactStatus createImpactStatus () const
 Creates a ImpactStatus for this robot model. More...
 
void initializeJointLimits ()
 Initializes the results of jointEffortLimit(), jointVelocityLimit(), lowerJointPositionLimit(), and upperJointPositionLimit() by the URDF. More...
 
Eigen::VectorXd jointEffortLimit () const
 Returns the effort limit of each joints. More...
 
Eigen::VectorXd jointVelocityLimit () const
 Returns the joint velocity limit of each joints. More...
 
Eigen::VectorXd lowerJointPositionLimit () const
 Returns the lower limit of the position of each joints. More...
 
Eigen::VectorXd upperJointPositionLimit () const
 Returns the upper limit of the position of each joints. More...
 
void setJointEffortLimit (const Eigen::VectorXd &joint_effort_limit)
 Sets the effort limit of each joints. More...
 
void setJointVelocityLimit (const Eigen::VectorXd &joint_velocity_limit)
 Sets the joint velocity limit of each joints. More...
 
void setLowerJointPositionLimit (const Eigen::VectorXd &lower_joint_position_limit)
 Sets the lower limit of the position of each joints. More...
 
void setUpperJointPositionLimit (const Eigen::VectorXd &upper_joint_position_limit)
 Sets the upper limit of the position of each joints. More...
 
const RobotModelInforobotModelInfo () const
 Gets the robot model info. More...
 
const RobotPropertiesrobotProperties () const
 Gets a collectio of the properties of this robot model. More...
 
void setRobotProperties (const RobotProperties &properties)
 Sets a collection of the properties for this robot model. More...
 
void disp (std::ostream &os) const
 Displays the robot model onto a ostream. More...
 

Friends

std::ostream & operator<< (std::ostream &os, const Robot &robot)
 

Detailed Description

Dynamics and kinematics model of robots. Wraps pinocchio::Model and pinocchio::Data. Includes contacts.

Member Typedef Documentation

◆ Vector6d

using robotoc::Robot::Vector6d = Eigen::Matrix<double, 6, 1>

Constructor & Destructor Documentation

◆ Robot() [1/4]

robotoc::Robot::Robot ( const RobotModelInfo robot_model_info)

Constructs a robot model according to the input model info.

Parameters
[in]robot_model_infoInfo of a robot model.

◆ Robot() [2/4]

robotoc::Robot::Robot ( )

Default constructor.

◆ ~Robot()

robotoc::Robot::~Robot ( )
default

Default destructor.

◆ Robot() [3/4]

robotoc::Robot::Robot ( const Robot )
default

Default copy constructor.

◆ Robot() [4/4]

robotoc::Robot::Robot ( Robot &&  )
defaultnoexcept

Default move constructor.

Member Function Documentation

◆ CoM()

const Eigen::Vector3d & robotoc::Robot::CoM ( ) const

Returns the position of the center of mass. Before calling this function, updateKinematics() or updateFrameKinematics() must be called.

◆ computeBaumgarteDerivatives()

template<typename MatrixType1 , typename MatrixType2 , typename MatrixType3 >
void robotoc::Robot::computeBaumgarteDerivatives ( const ContactStatus contact_status,
const Eigen::MatrixBase< MatrixType1 > &  baumgarte_partial_dq,
const Eigen::MatrixBase< MatrixType2 > &  baumgarte_partial_dv,
const Eigen::MatrixBase< MatrixType3 > &  baumgarte_partial_da 
)
inline

Computes the partial derivatives of the contact constriants represented by the Baumgarte's stabilization method. Before calling this function, updateKinematics() must be called.

Parameters
[in]contact_statusContact status.
[out]baumgarte_partial_dqThe partial derivative with respect to the configuaration. Size must be ContactStatus::dimf() x Robot::dimv().
[out]baumgarte_partial_dvThe partial derivative with respect to the velocity. Size must be ContactStatus::dimf() x Robot::dimv().
[out]baumgarte_partial_daThe partial derivative with respect to the acceleration. Size must be ContactStatus::dimf() x be Robot::dimv().

◆ computeBaumgarteResidual()

template<typename VectorType >
void robotoc::Robot::computeBaumgarteResidual ( const ContactStatus contact_status,
const Eigen::MatrixBase< VectorType > &  baumgarte_residual 
)
inline

Computes the residual of the contact constriants represented by Baumgarte's stabilization method. Before calling this function, updateKinematics() must be called.

Parameters
[in]contact_statusContact status.
[out]baumgarte_residualResiduals in the contact constraints. Size must be ContactStatus::dimf().

◆ computeContactPositionDerivative()

template<typename MatrixType >
void robotoc::Robot::computeContactPositionDerivative ( const ImpactStatus impact_status,
const Eigen::MatrixBase< MatrixType > &  position_partial_dq 
)
inline

Computes the partial derivative of the contact position at the impact. Before calling this function, updateKinematics() must be called.

Parameters
[in]impact_statusImpact status.
[out]position_partial_dqThe result of the partial derivative
with respect to the configuaration. Rows must be at least 3. Cols must be Robot::dimv().

◆ computeContactPositionResidual()

template<typename VectorType >
void robotoc::Robot::computeContactPositionResidual ( const ImpactStatus impact_status,
const Eigen::MatrixBase< VectorType > &  position_residual 
)
inline

Computes the residual of the contact position constraint at the impact. Before calling this function, updateKinematics() must be called.

Parameters
[in]impact_statusImpact status.
[out]position_residualResiduals in the contact position constraint. Size must be ImpactStatus::dimf().

◆ computeImpactVelocityDerivatives()

template<typename MatrixType1 , typename MatrixType2 >
void robotoc::Robot::computeImpactVelocityDerivatives ( const ImpactStatus impact_status,
const Eigen::MatrixBase< MatrixType1 > &  velocity_partial_dq,
const Eigen::MatrixBase< MatrixType2 > &  velocity_partial_dv 
)
inline

Computes the partial derivatives of the impact velocity constraint. Before calling this function, updateKinematics() must be called.

Parameters
[in]impact_statusImpact status.
[out]velocity_partial_dqThe partial derivative with respect to the configuaration. Size must be ImpactStatus::dimf() x Robot::dimv().
[out]velocity_partial_dvThe partial derivative with respect to the velocity. Size must be ImpactStatus::dimf() x Robot::dimv().

◆ computeImpactVelocityResidual()

template<typename VectorType >
void robotoc::Robot::computeImpactVelocityResidual ( const ImpactStatus impact_status,
const Eigen::MatrixBase< VectorType > &  velocity_residual 
) const
inline

Computes the residual of the impact velocity constraint. Before calling this function, updateKinematics() must be called.

Parameters
[in]impact_statusImpact status.
[out]velocity_residualResiduals in the contact velocity constraint. Size must be ImpactStatus::dimf().

◆ computeMinv()

template<typename MatrixType1 , typename MatrixType2 >
void robotoc::Robot::computeMinv ( const Eigen::MatrixBase< MatrixType1 > &  M,
const Eigen::MatrixBase< MatrixType2 > &  Minv 
)
inline

Computes the inverse of the joint inertia matrix M.

Parameters
[in]MJoint inertia matrix. Size must be Robot::dimv() x Robot::dimv().
[out]MinvInverse of the joint inertia matrix M. Size must be Robot::dimv() x Robot::dimv().

◆ computeMJtJinv()

template<typename MatrixType1 , typename MatrixType2 , typename MatrixType3 >
void robotoc::Robot::computeMJtJinv ( const Eigen::MatrixBase< MatrixType1 > &  M,
const Eigen::MatrixBase< MatrixType2 > &  J,
const Eigen::MatrixBase< MatrixType3 > &  MJtJinv 
)
inline

Computes the inverse of the contact dynamics matrix [[M J^T], [J O]].

Parameters
[in]MJoint inertia matrix. Size must be Robot::dimv() x Robot::dimv().
[in]JContact Jacobian. Size must be ContactStatus::dimf() x Robot::dimv().
[out]MJtJinvInverse of the matrix [[M J^T], [J O]]. Size must be (Robot::dimv() + ContactStatus::dimf()) x (Robot::dimv() + ContactStatus::dimf()).

◆ CoMVelocity()

const Eigen::Vector3d & robotoc::Robot::CoMVelocity ( ) const

Returns the linear velocity of the center of mass expressed in the world frame. Before calling this function, updateKinematics() or updateFrameKinematics() must be called.

◆ contactFrameNames()

std::vector< std::string > robotoc::Robot::contactFrameNames ( ) const

Retruns the names of the contact frames involving the point or.

surface contacts.

Returns
Names of the contact frames.

◆ contactFrames()

std::vector< int > robotoc::Robot::contactFrames ( ) const

Retruns the indices of the frames involving the point or surface contacts.

Returns
Indices of the contact frames.

◆ contactType()

ContactType robotoc::Robot::contactType ( const int  contact_index) const

Returns the type of the contact.

Parameters
[in]contact_indexIndex of a contact of interedted.
Returns
Contact type.

◆ contactTypes()

std::vector< ContactType > robotoc::Robot::contactTypes ( ) const

Returns the types of the contacts.

Returns
Contact types.

◆ createContactStatus()

ContactStatus robotoc::Robot::createContactStatus ( ) const

Creates a ContactStatus for this robot model.

Returns
ContactStatus for this robot model.

◆ createImpactStatus()

ImpactStatus robotoc::Robot::createImpactStatus ( ) const

Creates a ImpactStatus for this robot model.

Returns
ImpactStatus for this robot model.

◆ dim_passive()

int robotoc::Robot::dim_passive ( ) const

Returns the dimensiton of the generalized torques corresponding to the passive joints.

Returns
The dimensiton of the generalized torques corresponding to the
passive joints.

◆ dimq()

int robotoc::Robot::dimq ( ) const

Returns the dimensiton of the configuration.

Returns
The dimensiton of the configuration.

◆ dimu()

int robotoc::Robot::dimu ( ) const

Returns the dimensiton of the velocity, i.e, tangent space.

Returns
The dimensiton of the velocity, i.e, the dimension of the tangent space of the configuration space.

◆ dimv()

int robotoc::Robot::dimv ( ) const

Returns the dimensiton of the velocity, i.e, tangent space.

Returns
The dimensiton of the velocity, i.e, the dimension of the tangent space of the configuration space.

◆ dIntegrateTransport_dq()

template<typename ConfigVectorType , typename TangentVectorType , typename MatrixType1 , typename MatrixType2 >
void robotoc::Robot::dIntegrateTransport_dq ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< TangentVectorType > &  v,
const Eigen::MatrixBase< MatrixType1 > &  Jin,
const Eigen::MatrixBase< MatrixType2 > &  Jout 
) const
inline

Transport the Jacobian w.r.t. the configuration evaluated at the integrated configuration q + v to q.

Parameters
[in]qConfiguration. Size must be Robot::dimq().
[in]vGeneralized velocity. Size must be Robot::dimv().
[in]JinThe Jacobian w.r.t. the configuration evaluated at q + v. Cols must be Robot::dimv().
[out]JoutThe resultant Jacobian w.r.t. the configuration evaluated at q. The number of columns must be Robot::dimv().

◆ dIntegrateTransport_dv()

template<typename ConfigVectorType , typename TangentVectorType , typename MatrixType1 , typename MatrixType2 >
void robotoc::Robot::dIntegrateTransport_dv ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< TangentVectorType > &  v,
const Eigen::MatrixBase< MatrixType1 > &  Jin,
const Eigen::MatrixBase< MatrixType2 > &  Jout 
) const
inline

Transport the Jacobian w.r.t. the generalized velocity evaluated at the integrated configuration q + v to q.

Parameters
[in]qConfiguration. Size must be Robot::dimq().
[in]vGeneralized velocity. Size must be Robot::dimv().
[in]JinThe Jacobian w.r.t. the generalized velocity evaluated at q + v. Cols must be Robot::dimv().
[out]JoutThe resultant Jacobian w.r.t. the generalized velocity evaluated at q. The number of columns must be Robot::dimv().

◆ disp()

void robotoc::Robot::disp ( std::ostream &  os) const

Displays the robot model onto a ostream.

◆ dSubtractConfiguration_dq0()

template<typename ConfigVectorType1 , typename ConfigVectorType2 , typename MatrixType >
void robotoc::Robot::dSubtractConfiguration_dq0 ( const Eigen::MatrixBase< ConfigVectorType1 > &  qf,
const Eigen::MatrixBase< ConfigVectorType2 > &  q0,
const Eigen::MatrixBase< MatrixType > &  dqdiff_dq0 
) const
inline

Computes the partial derivative of the function of subtraction qf - q0 w.r.t. the initial configuration qf.

Parameters
[in]qfTerminal configuration. Size must be Robot::dimq().
[in]q0Initial configuration. Size must be Robot::dimq().
[out]dqdiff_dq0The partial derivative of the subtraction. Size must be Robot::dimv() x Robot::dimv().

◆ dSubtractConfiguration_dqf()

template<typename ConfigVectorType1 , typename ConfigVectorType2 , typename MatrixType >
void robotoc::Robot::dSubtractConfiguration_dqf ( const Eigen::MatrixBase< ConfigVectorType1 > &  qf,
const Eigen::MatrixBase< ConfigVectorType2 > &  q0,
const Eigen::MatrixBase< MatrixType > &  dqdiff_dqf 
) const
inline

Computes the partial derivative of the function of subtraction qf - q0 w.r.t. the terminal configuration qf.

Parameters
[in]qfTerminal configuration. Size must be Robot::dimq().
[in]q0Initial configuration. Size must be Robot::dimq().
[out]dqdiff_dqfThe partial derivative of the subtraction. Size must be Robot::dimv() x Robot::dimv().

◆ frameAngularVelocity() [1/2]

Eigen::Vector3d robotoc::Robot::frameAngularVelocity ( const int  frame_id,
const pinocchio::ReferenceFrame  reference_frame = pinocchio::LOCAL_WORLD_ALIGNED 
) const

Returns the angular velocity of the frame. Before calling
this function, updateKinematics() or updateFrameKinematics() must be called.

Parameters
[in]frame_idIndex of the frame.
[in]reference_frameReference frame. Default is pinocchio::LOCAL_WORLD_ALIGNED (world velocity).
Returns
Angular velocity of the frame.

◆ frameAngularVelocity() [2/2]

Eigen::Vector3d robotoc::Robot::frameAngularVelocity ( const std::string &  frame_name,
const pinocchio::ReferenceFrame  reference_frame = pinocchio::LOCAL_WORLD_ALIGNED 
) const

Returns the angular velocity of the frame. Before calling
this function, updateKinematics() or updateFrameKinematics() must be called.

Parameters
[in]frame_nameName of the frame.
[in]reference_frameReference frame. Default is pinocchio::LOCAL_WORLD_ALIGNED (world velocity).
Returns
Angular velocity of the frame.

◆ frameId()

int robotoc::Robot::frameId ( const std::string &  frame_name) const

Gets the id of the specified frame.

Parameters
[in]frame_nameFrame name of interest.
Returns
id of the specified frame. Returns maximum number of the frames if the frame whose name is frame_name does not exist.

◆ frameLinearVelocity() [1/2]

Eigen::Vector3d robotoc::Robot::frameLinearVelocity ( const int  frame_id,
const pinocchio::ReferenceFrame  reference_frame = pinocchio::LOCAL_WORLD_ALIGNED 
) const

Returns the linear (translational) velocity of the frame. Before calling
this function, updateKinematics() or updateFrameKinematics() must be called.

Parameters
[in]frame_idIndex of the frame.
[in]reference_frameReference frame. Default is pinocchio::LOCAL_WORLD_ALIGNED (world velocity).
Returns
Translational velocity of the frame.

◆ frameLinearVelocity() [2/2]

Eigen::Vector3d robotoc::Robot::frameLinearVelocity ( const std::string &  frame_name,
const pinocchio::ReferenceFrame  reference_frame = pinocchio::LOCAL_WORLD_ALIGNED 
) const

Returns the linear (translational) velocity of the frame. Before calling
this function, updateKinematics() or updateFrameKinematics() must be called.

Parameters
[in]frame_nameName of the frame.
[in]reference_frameReference frame. Default is pinocchio::LOCAL_WORLD_ALIGNED (world velocity).
Returns
Translational velocity of the frame.

◆ frameName()

std::string robotoc::Robot::frameName ( const int  frame_id) const

Gets the name of the specified frame.

Parameters
[in]frame_idFrame id of interest.
Returns
Name of the specified frame.

◆ framePlacement() [1/2]

const SE3 & robotoc::Robot::framePlacement ( const int  frame_id) const

Returns the SE(3) of the frame. Before calling this function, updateKinematics() or updateFrameKinematics() must be called.

Parameters
[in]frame_idIndex of the frame.
Returns
Const reference to the SE(3) of the frame.

◆ framePlacement() [2/2]

const SE3 & robotoc::Robot::framePlacement ( const std::string &  frame_name) const

Returns the SE(3) of the frame. Before calling this function, updateKinematics() or updateFrameKinematics() must be called.

Parameters
[in]frame_nameName of the frame.
Returns
Const reference to the SE(3) of the frame.

◆ framePosition() [1/2]

const Eigen::Vector3d & robotoc::Robot::framePosition ( const int  frame_id) const

Returns the position of the frame. Before calling this function, updateKinematics() or updateFrameKinematics() must be called.

Parameters
[in]frame_idIndex of the frame.
Returns
Const reference to the position of the frame.

◆ framePosition() [2/2]

const Eigen::Vector3d & robotoc::Robot::framePosition ( const std::string &  frame_name) const

Returns the position of the frame. Before calling this function, updateKinematics() or updateFrameKinematics() must be called.

Parameters
[in]frame_nameName of the frame.
Returns
Const reference to the position of the frame.

◆ frameRotation() [1/2]

const Eigen::Matrix3d & robotoc::Robot::frameRotation ( const int  frame_id) const

Returns the rotation matrix of the frame. Before calling this
function, updateKinematics() or updateFrameKinematics() must be called.

Parameters
[in]frame_idIndex of the frame.
Returns
Const reference to the rotation matrix of the frame.

◆ frameRotation() [2/2]

const Eigen::Matrix3d & robotoc::Robot::frameRotation ( const std::string &  frame_name) const

Returns the rotation matrix of the frame. Before calling this
function, updateKinematics() or updateFrameKinematics() must be called.

Parameters
[in]frame_nameName of the frame.
Returns
Const reference to the rotation matrix of the frame.

◆ frameSpatialVelocity() [1/2]

Vector6d robotoc::Robot::frameSpatialVelocity ( const int  frame_id,
const pinocchio::ReferenceFrame  reference_frame = pinocchio::LOCAL_WORLD_ALIGNED 
) const

Returns the spatial velocity of the frame. Before calling
this function, updateKinematics() or updateFrameKinematics() must be called.

Parameters
[in]frame_idIndex of the frame.
[in]reference_frameReference frame. Default is pinocchio::LOCAL_WORLD_ALIGNED (world velocity).
Returns
Spatial velocity of the frame.

◆ frameSpatialVelocity() [2/2]

Vector6d robotoc::Robot::frameSpatialVelocity ( const std::string &  frame_name,
const pinocchio::ReferenceFrame  reference_frame = pinocchio::LOCAL_WORLD_ALIGNED 
) const

Returns the spatial velocity of the frame. Before calling
this function, updateKinematics() or updateFrameKinematics() must be called.

Parameters
[in]frame_nameName of the frame.
[in]reference_frameReference frame. Default is pinocchio::LOCAL_WORLD_ALIGNED (world velocity).
Returns
Spatial velocity of the frame.

◆ generateFeasibleConfiguration()

Eigen::VectorXd robotoc::Robot::generateFeasibleConfiguration ( ) const

Generates feasible configuration randomly.

Returns
The random and feasible configuration. Size is Robot::dimq().

◆ getCoMJacobian()

template<typename MatrixType >
void robotoc::Robot::getCoMJacobian ( const Eigen::MatrixBase< MatrixType > &  J) const
inline

Gets the Jacobian of the position of the center of mass. Before calling this function, updateKinematics() must be called.

Parameters
[out]JJacobian. Size must be 3 x Robot::dimv().

◆ getFrameJacobian()

template<typename MatrixType >
void robotoc::Robot::getFrameJacobian ( const int  frame_id,
const Eigen::MatrixBase< MatrixType > &  J 
)
inline

Computes the Jacobian of the frame position expressed in the local coordinate. Before calling this function, updateKinematics() must be called.

Parameters
[in]frame_idIndex of the frame.
[out]JJacobian. Size must be 6 x Robot::dimv().

◆ getJacobianTransformFromLocalToWorld()

template<typename Vector3dType , typename MatrixType >
void robotoc::Robot::getJacobianTransformFromLocalToWorld ( const int  frame_id,
const Eigen::MatrixBase< Vector3dType > &  vec_world,
const Eigen::MatrixBase< MatrixType > &  J 
)
inline

Jacobian of the transformation mapping of a 3D quantity from local frame to the world frame.

Parameters
[in]frame_idIndex of the frame whose local coordinate is of interest.
[in]vec_world3-dimensional vector-valued quantity expressed at the world frame.
[out]JThe Jacobian. Size must be 6 x Robot::dimv(). The result is stored at the top 3 rows.

◆ hasFloatingBase()

bool robotoc::Robot::hasFloatingBase ( ) const

Returns true if the robot has a floating base and false if not.

Returns
true if the robot has a floating base and false if not.

◆ initializeJointLimits()

void robotoc::Robot::initializeJointLimits ( )

◆ integrateCoeffWiseJacobian()

template<typename ConfigVectorType , typename MatrixType >
void robotoc::Robot::integrateCoeffWiseJacobian ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< MatrixType > &  J 
) const
inline

Transforms the Jacobian w.r.t. configuration to tangentspace.

Parameters
[in]qConfiguration. Size must be Robot::dimq().
[in,out]JJacobian. Size must be Robot::dimq() x Robot::dimv().

◆ integrateConfiguration() [1/2]

template<typename ConfigVectorType1 , typename TangentVectorType , typename ConfigVectorType2 >
void robotoc::Robot::integrateConfiguration ( const Eigen::MatrixBase< ConfigVectorType1 > &  q,
const Eigen::MatrixBase< TangentVectorType > &  v,
const double  integration_length,
const Eigen::MatrixBase< ConfigVectorType2 > &  q_integrated 
) const
inline

Integrates the generalized velocity, that is, performs q_integrated = q + integration_length * v like computation on the configuration manifolds.

Parameters
[in]qConfiguration. Size must be Robot::dimq().
[in]vGeneralized velocity. Size must be Robot::dimv().
[in]integration_lengthThe length of the integration.
[out]q_integratedConfiguration. Size must be Robot::dimq().

◆ integrateConfiguration() [2/2]

template<typename TangentVectorType , typename ConfigVectorType >
void robotoc::Robot::integrateConfiguration ( const Eigen::MatrixBase< TangentVectorType > &  v,
const double  integration_length,
const Eigen::MatrixBase< ConfigVectorType > &  q 
) const
inline

Integrates the generalized velocity, that is, performs q <- q + integration_length * v like computation on the configuration manifolds.

Parameters
[in]vGeneralized velocity. Size must be Robot::dimv().
[in]integration_lengthThe length of the integration.
[in,out]qConfiguration. Size must be Robot::dimq().

◆ interpolateConfiguration()

template<typename ConfigVectorType1 , typename ConfigVectorType2 , typename ConfigVectorType3 >
void robotoc::Robot::interpolateConfiguration ( const Eigen::MatrixBase< ConfigVectorType1 > &  q1,
const Eigen::MatrixBase< ConfigVectorType2 > &  q2,
const double  t,
const Eigen::MatrixBase< ConfigVectorType3 > &  qout 
) const
inline

Computes an interpolation of two configurations by (1.0 - t) * s1 + t * s2.

Parameters
[in]q1Configuration. Size must be Robot::dimq().
[in]q2Configuration. Size must be Robot::dimq().
[in]tInterpolation parameter. Must be between 0 to 1.
[out]qoutConfiguration. Size must be Robot::dimq().

◆ jointEffortLimit()

Eigen::VectorXd robotoc::Robot::jointEffortLimit ( ) const

Returns the effort limit of each joints.

Returns
The effort limit of each joints.

◆ jointVelocityLimit()

Eigen::VectorXd robotoc::Robot::jointVelocityLimit ( ) const

Returns the joint velocity limit of each joints.

Returns
The joint velocity limit of each joints.

◆ lowerJointPositionLimit()

Eigen::VectorXd robotoc::Robot::lowerJointPositionLimit ( ) const

Returns the lower limit of the position of each joints.

Returns
The lower limit of the position of each joints.

◆ max_dimf()

int robotoc::Robot::max_dimf ( ) const

Returns the maximum dimension of the contacts.

Returns
The maximum dimension of the contacts.

◆ maxNumContacts()

int robotoc::Robot::maxNumContacts ( ) const

Returns the maximum number of the contacts.

Returns
The maximum number of the contacts.

◆ maxNumPointContacts()

int robotoc::Robot::maxNumPointContacts ( ) const

Returns the maximum number of the point contacts.

Returns
The maximum number of the point contacts.

◆ maxNumSurfaceContacts()

int robotoc::Robot::maxNumSurfaceContacts ( ) const

Returns the maximum number of the surface contacts.

Returns
The maximum number of the surface contacts.

◆ normalizeConfiguration()

template<typename ConfigVectorType >
void robotoc::Robot::normalizeConfiguration ( const Eigen::MatrixBase< ConfigVectorType > &  q) const
inline

Normalizes a configuration vector.

Parameters
[in,out]qThe normalized configuration. Size must be Robot::dimq().

◆ operator=() [1/2]

Robot & robotoc::Robot::operator= ( const Robot )
default

Default copy assign operator.

◆ operator=() [2/2]

Robot & robotoc::Robot::operator= ( Robot &&  )
defaultnoexcept

Default move assign operator.

◆ pointContactFrameNames()

std::vector< std::string > robotoc::Robot::pointContactFrameNames ( ) const

Retruns the names of the frames involving the contacts.

Returns
Names of the contact frames.

◆ pointContactFrames()

std::vector< int > robotoc::Robot::pointContactFrames ( ) const

Retruns the indices of the frames involving the contacts.

Returns
Indices of the contact frames.

◆ RNEA()

template<typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename TangentVectorType3 >
void robotoc::Robot::RNEA ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< TangentVectorType1 > &  v,
const Eigen::MatrixBase< TangentVectorType2 > &  a,
const Eigen::MatrixBase< TangentVectorType3 > &  tau 
)
inline

Computes inverse dynamics, i.e., generalized torques corresponding for given configuration, velocity, acceleration, and contact forces. If the robot has contacts, update contact forces via setContactForces() before calling this function.

Parameters
[in]qConfiguration. Size must be Robot::dimq().
[in]vGeneralized velocity. Size must be Robot::dimv().
[in]aGeneralized acceleration. Size must be Robot::dimv().
[out]tauGeneralized torques for fully actuated system. Size must be Robot::dimv().

◆ RNEADerivatives()

template<typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename MatrixType1 , typename MatrixType2 , typename MatrixType3 >
void robotoc::Robot::RNEADerivatives ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< TangentVectorType1 > &  v,
const Eigen::MatrixBase< TangentVectorType2 > &  a,
const Eigen::MatrixBase< MatrixType1 > &  dRNEA_partial_dq,
const Eigen::MatrixBase< MatrixType2 > &  dRNEA_partial_dv,
const Eigen::MatrixBase< MatrixType3 > &  dRNEA_partial_da 
)
inline

Computes the partial dervatives of the function of inverse dynamics with respect to the configuration, velocity, and acceleration. If the robot has contacts, update contact forces via setContactForces() before calling this function.

Parameters
[in]qConfiguration. Size must be Robot::dimq().
[in]vGeneralized velocity. Size must be Robot::dimv().
[in]aGeneralized acceleration. Size must be Robot::dimv().
[out]dRNEA_partial_dqThe partial derivative of inverse dynamics with respect to the configuration. The size must be Robot::dimv() x Robot::dimv().
[out]dRNEA_partial_dvThe partial derivative of inverse dynamics with respect to the velocity. The size must be Robot::dimv() x Robot::dimv().
[out]dRNEA_partial_daThe partial derivative of inverse dynamics with respect to the acceleration. The size must be Robot::dimv() x Robot::dimv().

◆ RNEAImpact()

template<typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 >
void robotoc::Robot::RNEAImpact ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< TangentVectorType1 > &  dv,
const Eigen::MatrixBase< TangentVectorType2 > &  res 
)
inline

Computes the residual of the impact dynamics for given configuration and impact change in the generalized velocity, and impact forces by using RNEA. Before call this function, update contact forces via setImpactForces().

Parameters
[in]qConfiguration. Size must be Robot::dimq().
[in]dvImpact change in the velocity. Size must be Robot::dimv().
[out]resResidual of impact dynamics. Size must be Robot::dimv().

◆ RNEAImpactDerivatives()

template<typename ConfigVectorType , typename TangentVectorType , typename MatrixType1 , typename MatrixType2 >
void robotoc::Robot::RNEAImpactDerivatives ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< TangentVectorType > &  dv,
const Eigen::MatrixBase< MatrixType1 > &  dRNEA_partial_dq,
const Eigen::MatrixBase< MatrixType2 > &  dRNEA_partial_ddv 
)
inline

Computes the partial dervatives of the function of impuse dynamics with respect to configuration and impact changes in the velocity. Before calling this function, update contact forces via setImpactForces().

Parameters
[in]qConfiguration. Size must be Robot::dimq().
[in]dvImpact change in the velocity. Size must be Robot::dimv().
[out]dRNEA_partial_dqThe partial derivative of impact dynamics with respect to the configuration. The size must be Robot::dimv() x Robot::dimv().
[out]dRNEA_partial_ddvThe partial derivative of impact dynamics with respect to the change in velocity. The size must be Robot::dimv() x Robot::dimv().

◆ robotModelInfo()

const RobotModelInfo & robotoc::Robot::robotModelInfo ( ) const

Gets the robot model info.

Returns
const reference to a the robot model info.

◆ robotProperties()

const RobotProperties & robotoc::Robot::robotProperties ( ) const

Gets a collectio of the properties of this robot model.

Returns
const reference to a collectio of the properties of this robot model.

◆ setContactForces()

void robotoc::Robot::setContactForces ( const ContactStatus contact_status,
const std::vector< Vector6d > &  f 
)

Set contact forces in this robot model for each active contacts.

Parameters
[in]contact_statusContact status.
[in]fThe stack of the contact wrenches represented in the local coordinate of the contact frame. Size must be Robot::maxNumContacts().

◆ setImpactForces()

void robotoc::Robot::setImpactForces ( const ImpactStatus impact_status,
const std::vector< Vector6d > &  f 
)
inline

Set impact forces in this robot model for each active impacts.

Parameters
[in]impact_statusImpact status.
[in]fThe stack of the impact wrenches represented in the local coordinate of the contact frame. Size must be Robot::maxNumContacts().

◆ setJointEffortLimit()

void robotoc::Robot::setJointEffortLimit ( const Eigen::VectorXd &  joint_effort_limit)

Sets the effort limit of each joints.

Parameters
[in]joint_effort_limitThe effort limit of each joints.

◆ setJointVelocityLimit()

void robotoc::Robot::setJointVelocityLimit ( const Eigen::VectorXd &  joint_velocity_limit)

Sets the joint velocity limit of each joints.

Parameters
[in]joint_velocity_limitSets the joint velocity limit of each joints.

◆ setLowerJointPositionLimit()

void robotoc::Robot::setLowerJointPositionLimit ( const Eigen::VectorXd &  lower_joint_position_limit)

Sets the lower limit of the position of each joints.

Parameters
[in]lower_joint_position_limitThe lower limit of the position of each joints.

◆ setRobotProperties()

void robotoc::Robot::setRobotProperties ( const RobotProperties properties)

Sets a collection of the properties for this robot model.

Parameters
[in]propertiesA collection of the properties for this robot model.

◆ setUpperJointPositionLimit()

void robotoc::Robot::setUpperJointPositionLimit ( const Eigen::VectorXd &  upper_joint_position_limit)

Sets the upper limit of the position of each joints.

Parameters
[in]upper_joint_position_limitThe upper limit of the position of each joints.

◆ subtractConfiguration()

template<typename ConfigVectorType1 , typename ConfigVectorType2 , typename TangentVectorType >
void robotoc::Robot::subtractConfiguration ( const Eigen::MatrixBase< ConfigVectorType1 > &  qf,
const Eigen::MatrixBase< ConfigVectorType2 > &  q0,
const Eigen::MatrixBase< TangentVectorType > &  qdiff 
) const
inline

Computes qf - q0 at the tangent space. The result means that the unit velocity from initial configuration q0 to terminal configuration qf.

Parameters
[in]qfTerminal configuration. Size must be Robot::dimq().
[in]q0Initial configuration. Size must be Robot::dimq().
[out]qdiffDifference of the configurations, qf - q0. Size must be Robot::dimv().

◆ surfaceContactFrameNames()

std::vector< std::string > robotoc::Robot::surfaceContactFrameNames ( ) const

Retruns the names of the frames involving the surface contacts.

Returns
Names of the surface contact frames.

◆ surfaceContactFrames()

std::vector< int > robotoc::Robot::surfaceContactFrames ( ) const

Retruns the indices of the frames involving the surface contacts.

Returns
Indices of the surface contact frames.

◆ totalMass()

double robotoc::Robot::totalMass ( ) const

Returns the total mass of this robot model.

Returns
The total mass of this robot model.

◆ totalWeight()

double robotoc::Robot::totalWeight ( ) const

Returns the total weight of this robot model.

Returns
The total weight of this robot model.

◆ transformFromLocalToWorld()

template<typename Vector3dType >
void robotoc::Robot::transformFromLocalToWorld ( const int  frame_id,
const Eigen::Vector3d &  vec_local,
const Eigen::MatrixBase< Vector3dType > &  vec_world 
) const
inline

Transforms 3D quantity from local frame to the world frame.

Parameters
[in]frame_idIndex of the frame whose local coordinate is of interest.
[in]vec_local3-dimensional vector-valued quantity expressed at the local frame.
[out]vec_world3-dimensional vector-valued quantity expressed at the world frame.

◆ updateFrameKinematics() [1/3]

template<typename ConfigVectorType >
void robotoc::Robot::updateFrameKinematics ( const Eigen::MatrixBase< ConfigVectorType > &  q)
inline

Updates the frame kinematics of the robot. The frame placements are calculated.

Parameters
[in]qConfiguration. Size must be Robot::dimq().

◆ updateFrameKinematics() [2/3]

template<typename ConfigVectorType , typename TangentVectorType >
void robotoc::Robot::updateFrameKinematics ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< TangentVectorType > &  v 
)
inline

Updates the frame kinematics of the robot. The frame placements and velocities are calculated.

Parameters
[in]qConfiguration. Size must be Robot::dimq().
[in]vGeneralized velocity. Size must be Robot::dimv().

◆ updateFrameKinematics() [3/3]

template<typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 >
void robotoc::Robot::updateFrameKinematics ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< TangentVectorType1 > &  v,
const Eigen::MatrixBase< TangentVectorType2 > &  a 
)
inline

Updates the frame kinematics of the robot. The frame placements, velocities, and accelerations are calculated.

Parameters
[in]qConfiguration. Size must be Robot::dimq().
[in]vGeneralized velocity. Size must be Robot::dimv().
[in]aGeneralized acceleration. Size must be Robot::dimv().

◆ updateKinematics() [1/3]

template<typename ConfigVectorType >
void robotoc::Robot::updateKinematics ( const Eigen::MatrixBase< ConfigVectorType > &  q)
inline

Updates the kinematics of the robot. The frame placements and and the relevant Jacobians are calculated.

Parameters
[in]qConfiguration. Size must be Robot::dimq().

◆ updateKinematics() [2/3]

template<typename ConfigVectorType , typename TangentVectorType >
void robotoc::Robot::updateKinematics ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< TangentVectorType > &  v 
)
inline

Updates the kinematics of the robot. The frame placements, frame velocity, and the relevant Jacobians are calculated.

Parameters
[in]qConfiguration. Size must be Robot::dimq().
[in]vGeneralized velocity. Size must be Robot::dimv().

◆ updateKinematics() [3/3]

template<typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 >
void robotoc::Robot::updateKinematics ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< TangentVectorType1 > &  v,
const Eigen::MatrixBase< TangentVectorType2 > &  a 
)
inline

Updates the kinematics of the robot. The frame placements, frame velocity, frame acceleration, and the relevant Jacobians are calculated.

Parameters
[in]qConfiguration. Size must be Robot::dimq().
[in]vGeneralized velocity. Size must be Robot::dimv().
[in]aGeneralized acceleration. Size must be Robot::dimv().

◆ upperJointPositionLimit()

Eigen::VectorXd robotoc::Robot::upperJointPositionLimit ( ) const

Returns the upper limit of the position of each joints.

Returns
The upper limit of the position of each joints.

Friends And Related Function Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream &  os,
const Robot robot 
)
friend

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