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

Kinematics and dynamic model of a point contact. More...

#include <point_contact.hpp>

Public Types

using Matrix6xd = Eigen::Matrix< double, 6, Eigen::Dynamic >
 

Public Member Functions

 PointContact (const pinocchio::Model &model, const ContactModelInfo &contact_model_info)
 Construct a point contact model. More...
 
 PointContact ()
 Default constructor. More...
 
 ~PointContact ()=default
 Default destructor. More...
 
 PointContact (const PointContact &)=default
 Default copy constructor. More...
 
PointContactoperator= (const PointContact &)=default
 Default copy assign operator. More...
 
 PointContact (PointContact &&) noexcept=default
 Default move constructor. More...
 
PointContactoperator= (PointContact &&) noexcept=default
 Default move assign operator. More...
 
void computeJointForceFromContactForce (const Eigen::Vector3d &contact_force, pinocchio::container::aligned_vector< pinocchio::Force > &joint_forces) const
 Converts the 3D contact forces in the local coordinate to the corresponding joint spatial forces. More...
 
template<typename VectorType1 , typename VectorType2 >
void computeBaumgarteResidual (const pinocchio::Model &model, const pinocchio::Data &data, const Eigen::MatrixBase< VectorType1 > &desired_contact_position, const Eigen::MatrixBase< VectorType2 > &baumgarte_residual) const
 Computes the residual of the contact constraints considered by the Baumgarte's stabilization method. Before calling this function, kinematics of the robot model (frame position, velocity, and acceleration) must be updated. More...
 
template<typename MatrixType1 , typename MatrixType2 , typename MatrixType3 >
void computeBaumgarteDerivatives (const pinocchio::Model &model, pinocchio::Data &data, 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 constraints considered by the Baumgarte's stabilization method. Before calling this function, kinematics derivatives of the robot model (position, velocity, and acceleration) must be updated. More...
 
template<typename VectorType >
void computeContactVelocityResidual (const pinocchio::Model &model, const pinocchio::Data &data, const Eigen::MatrixBase< VectorType > &velocity_residual) const
 Computes the residual of the contact velocity constraints. Before calling this function, kinematics of the robot model (frame position and velocity) must be updated. More...
 
template<typename MatrixType1 , typename MatrixType2 >
void computeContactVelocityDerivatives (const pinocchio::Model &model, pinocchio::Data &data, const Eigen::MatrixBase< MatrixType1 > &velocity_partial_dq, const Eigen::MatrixBase< MatrixType2 > &velocity_partial_dv)
 Computes the partial derivatives of the contact velocity constraints. Before calling this function, kinematics derivatives of the robot model (position and velocity) must be updated. More...
 
template<typename VectorType1 , typename VectorType2 >
void computeContactPositionResidual (const pinocchio::Model &model, const pinocchio::Data &data, const Eigen::MatrixBase< VectorType1 > &desired_contact_position, const Eigen::MatrixBase< VectorType2 > &position_residual) const
 Computes the residual of the contact position constraints. Before calling this function, kinematics of the robot model (frame position) must be updated. More...
 
template<typename MatrixType >
void computeContactPositionDerivative (const pinocchio::Model &model, pinocchio::Data &data, const Eigen::MatrixBase< MatrixType > &position_partial_dq)
 Computes the partial derivative of the contact position
constraint with respect to the configuration. Before calling this function, kinematics derivative of the robot model with respect to the frame position must be updated. More...
 
const Eigen::Vector3d & contactPosition (const pinocchio::Data &data) const
 Returns the contact position at the current kinematics of the robot. Before calling this function, kinematics of the robot model (frame position) must be updated. More...
 
void setBaumgarteGains (const double baumgarte_position_gain, const double baumgarte_velocity_gain)
 Sets the gain parameters of the Baumgarte's stabilization method. More...
 
int contactFrameId () const
 Returns contact frame id, i.e., the index of the contact frame. More...
 
int parentJointId () const
 Returns parent joint id, i.e., the index of the parent joint of the contact frame. More...
 
const ContactModelInfocontactModelInfo () const
 Gets the contact model info. More...
 
void disp (std::ostream &os) const
 Displays the point contact onto a ostream. More...
 

Friends

std::ostream & operator<< (std::ostream &os, const PointContact &point_contact)
 

Detailed Description

Kinematics and dynamic model of a point contact.

Member Typedef Documentation

◆ Matrix6xd

using robotoc::PointContact::Matrix6xd = Eigen::Matrix<double, 6, Eigen::Dynamic>

Constructor & Destructor Documentation

◆ PointContact() [1/4]

robotoc::PointContact::PointContact ( const pinocchio::Model &  model,
const ContactModelInfo contact_model_info 
)

Construct a point contact model.

Parameters
[in]modelThe pinocchio model. Before calling this constructor, pinocchio model must be initialized, e.g., by pinocchio::buildModel().
[in]contact_model_infoInfo of the point contact model.

◆ PointContact() [2/4]

robotoc::PointContact::PointContact ( )

Default constructor.

◆ ~PointContact()

robotoc::PointContact::~PointContact ( )
default

Default destructor.

◆ PointContact() [3/4]

robotoc::PointContact::PointContact ( const PointContact )
default

Default copy constructor.

◆ PointContact() [4/4]

robotoc::PointContact::PointContact ( PointContact &&  )
defaultnoexcept

Default move constructor.

Member Function Documentation

◆ computeBaumgarteDerivatives()

template<typename MatrixType1 , typename MatrixType2 , typename MatrixType3 >
void robotoc::PointContact::computeBaumgarteDerivatives ( const pinocchio::Model &  model,
pinocchio::Data &  data,
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 constraints considered by the Baumgarte's stabilization method. Before calling this function, kinematics derivatives of the robot model (position, velocity, and acceleration) must be updated.

Parameters
[in]modelPinocchio model of the robot.
[in]dataPinocchio data of the robot kinematics.
[out]baumgarte_partial_dqThe partial derivative with respect to the configuaration. Size must be 3 x Robot::dimv().
[out]baumgarte_partial_dvThe partial derivative with respect to the velocity. Size must be 3 x Robot::dimv().
[out]baumgarte_partial_daThe partial derivative with respect to the acceleration. Size must be 3 x Robot::dimv().

◆ computeBaumgarteResidual()

template<typename VectorType1 , typename VectorType2 >
void robotoc::PointContact::computeBaumgarteResidual ( const pinocchio::Model &  model,
const pinocchio::Data &  data,
const Eigen::MatrixBase< VectorType1 > &  desired_contact_position,
const Eigen::MatrixBase< VectorType2 > &  baumgarte_residual 
) const
inline

Computes the residual of the contact constraints considered by the Baumgarte's stabilization method. Before calling this function, kinematics of the robot model (frame position, velocity, and acceleration) must be updated.

Parameters
[in]modelPinocchio model of the robot.
[in]dataPinocchio data of the robot kinematics.
[in]desired_contact_positionDesired contact position. Size must be 3.
[out]baumgarte_residualResidual of the Bamgarte's constraint. Size must be 3.

◆ computeContactPositionDerivative()

template<typename MatrixType >
void robotoc::PointContact::computeContactPositionDerivative ( const pinocchio::Model &  model,
pinocchio::Data &  data,
const Eigen::MatrixBase< MatrixType > &  position_partial_dq 
)
inline

Computes the partial derivative of the contact position
constraint with respect to the configuration. Before calling this function, kinematics derivative of the robot model with respect to the frame position must be updated.

Parameters
[in]modelPinocchio model of the robot.
[in]dataPinocchio data of the robot kinematics.
[out]position_partial_dqThe result of the partial derivative
with respect to the configuaration. Size must be 3 x Robot::dimv().

◆ computeContactPositionResidual()

template<typename VectorType1 , typename VectorType2 >
void robotoc::PointContact::computeContactPositionResidual ( const pinocchio::Model &  model,
const pinocchio::Data &  data,
const Eigen::MatrixBase< VectorType1 > &  desired_contact_position,
const Eigen::MatrixBase< VectorType2 > &  position_residual 
) const
inline

Computes the residual of the contact position constraints. Before calling this function, kinematics of the robot model (frame position) must be updated.

Parameters
[in]modelPinocchio model of the robot.
[in]dataPinocchio data of the robot kinematics.
[in]desired_contact_positionDesired contact position. Size must be 3.
[out]position_residualResidual of the contact constraint. Size must be 3.

◆ computeContactVelocityDerivatives()

template<typename MatrixType1 , typename MatrixType2 >
void robotoc::PointContact::computeContactVelocityDerivatives ( const pinocchio::Model &  model,
pinocchio::Data &  data,
const Eigen::MatrixBase< MatrixType1 > &  velocity_partial_dq,
const Eigen::MatrixBase< MatrixType2 > &  velocity_partial_dv 
)
inline

Computes the partial derivatives of the contact velocity constraints. Before calling this function, kinematics derivatives of the robot model (position and velocity) must be updated.

Parameters
[in]modelPinocchio model of the robot.
[in]dataPinocchio data of the robot kinematics.
[out]velocity_partial_dqThe partial derivative with respect to the configuaration. Size must be 3 x Robot::dimv().
[out]velocity_partial_dvThe partial derivative with respect to the velocity. Size must be 3 x Robot::dimv().

◆ computeContactVelocityResidual()

template<typename VectorType >
void robotoc::PointContact::computeContactVelocityResidual ( const pinocchio::Model &  model,
const pinocchio::Data &  data,
const Eigen::MatrixBase< VectorType > &  velocity_residual 
) const
inline

Computes the residual of the contact velocity constraints. Before calling this function, kinematics of the robot model (frame position and velocity) must be updated.

Parameters
[in]modelPinocchio model of the robot.
[in]dataPinocchio data of the robot kinematics.
[out]velocity_residualResidual of the contact velocity constraint.

◆ computeJointForceFromContactForce()

void robotoc::PointContact::computeJointForceFromContactForce ( const Eigen::Vector3d &  contact_force,
pinocchio::container::aligned_vector< pinocchio::Force > &  joint_forces 
) const

Converts the 3D contact forces in the local coordinate to the corresponding joint spatial forces.

Parameters
[in]contact_forceThe 3D contact forces in the local frame.
[out]joint_forcesThe corresponding joint spatial forces.

◆ contactFrameId()

int robotoc::PointContact::contactFrameId ( ) const

Returns contact frame id, i.e., the index of the contact frame.

Returns
Contact frame id.

◆ contactModelInfo()

const ContactModelInfo & robotoc::PointContact::contactModelInfo ( ) const

Gets the contact model info.

Returns
const reference to the contact model info.

◆ contactPosition()

const Eigen::Vector3d & robotoc::PointContact::contactPosition ( const pinocchio::Data &  data) const

Returns the contact position at the current kinematics of the robot. Before calling this function, kinematics of the robot model (frame position) must be updated.

Parameters
[in]dataPinocchio data of the robot kinematics.
Returns
Const reference to the contact position.

◆ disp()

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

Displays the point contact onto a ostream.

◆ operator=() [1/2]

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

Default copy assign operator.

◆ operator=() [2/2]

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

Default move assign operator.

◆ parentJointId()

int robotoc::PointContact::parentJointId ( ) const

Returns parent joint id, i.e., the index of the parent joint of the contact frame.

Returns
Parent joint id.

◆ setBaumgarteGains()

void robotoc::PointContact::setBaumgarteGains ( const double  baumgarte_position_gain,
const double  baumgarte_velocity_gain 
)

Sets the gain parameters of the Baumgarte's stabilization method.

Parameters
[in]baumgarte_position_gainThe position gain of the Baumgarte's stabilization method. Must be non-negative.
[in]baumgarte_velocity_gainThe velocity gain of the Baumgarte's stabilization method. Must be non-negative.

Friends And Related Function Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream &  os,
const PointContact point_contact 
)
friend

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