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

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

#include <surface_contact.hpp>

Public Types

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

Public Member Functions

 SurfaceContact (const pinocchio::Model &model, const ContactModelInfo &contact_model_info)
 Construct a surface contact model. More...
 
 SurfaceContact ()
 Default constructor. More...
 
 ~SurfaceContact ()=default
 Destructor. More...
 
 SurfaceContact (const SurfaceContact &)=default
 Default copy constructor. More...
 
SurfaceContactoperator= (const SurfaceContact &)=default
 Default copy assign operator. More...
 
 SurfaceContact (SurfaceContact &&) noexcept=default
 Default move constructor. More...
 
SurfaceContactoperator= (SurfaceContact &&) noexcept=default
 Default move assign operator. More...
 
void computeJointForceFromContactWrench (const Vector6d &contact_wrench, pinocchio::container::aligned_vector< pinocchio::Force > &joint_forces) const
 Converts the 6D contact wrench in the local coordinate to the corresponding joint spatial forces. More...
 
template<typename VectorType >
void computeBaumgarteResidual (const pinocchio::Model &model, const pinocchio::Data &data, const SE3 &desired_contact_placement, const Eigen::MatrixBase< VectorType > &baumgarte_residual)
 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 VectorType >
void computeContactPositionResidual (const pinocchio::Model &model, const pinocchio::Data &data, const SE3 &desired_contact_placement, const Eigen::MatrixBase< VectorType > &position_residual)
 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 SE3contactPlacement (const pinocchio::Data &data) const
 Returns the contact placement 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 surface contact onto a ostream. More...
 

Friends

std::ostream & operator<< (std::ostream &os, const SurfaceContact &surface_contact)
 

Detailed Description

Kinematics and dynamic model of a surface contact.

Member Typedef Documentation

◆ Matrix66d

using robotoc::SurfaceContact::Matrix66d = Eigen::Matrix<double, 6, 6>

◆ Matrix6xd

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

◆ Vector6d

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

Constructor & Destructor Documentation

◆ SurfaceContact() [1/4]

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

Construct a surface 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.

◆ SurfaceContact() [2/4]

robotoc::SurfaceContact::SurfaceContact ( )

Default constructor.

◆ ~SurfaceContact()

robotoc::SurfaceContact::~SurfaceContact ( )
default

Destructor.

◆ SurfaceContact() [3/4]

robotoc::SurfaceContact::SurfaceContact ( const SurfaceContact )
default

Default copy constructor.

◆ SurfaceContact() [4/4]

robotoc::SurfaceContact::SurfaceContact ( SurfaceContact &&  )
defaultnoexcept

Default move constructor.

Member Function Documentation

◆ computeBaumgarteDerivatives()

template<typename MatrixType1 , typename MatrixType2 , typename MatrixType3 >
void robotoc::SurfaceContact::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 6 x Robot::dimv().
[out]baumgarte_partial_dvThe partial derivative with respect to the velocity. Size must be 6 x Robot::dimv().
[out]baumgarte_partial_daThe partial derivative with respect to the acceleration. Size must be 6 x Robot::dimv().

◆ computeBaumgarteResidual()

template<typename VectorType >
void robotoc::SurfaceContact::computeBaumgarteResidual ( const pinocchio::Model &  model,
const pinocchio::Data &  data,
const SE3 desired_contact_placement,
const Eigen::MatrixBase< VectorType > &  baumgarte_residual 
)
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_placementDesired contact placement.
[out]baumgarte_residualResidual of the Bamgarte's constraint. Size must be 6.

◆ computeContactPositionDerivative()

template<typename MatrixType >
void robotoc::SurfaceContact::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 6 x Robot::dimv().

◆ computeContactPositionResidual()

template<typename VectorType >
void robotoc::SurfaceContact::computeContactPositionResidual ( const pinocchio::Model &  model,
const pinocchio::Data &  data,
const SE3 desired_contact_placement,
const Eigen::MatrixBase< VectorType > &  position_residual 
)
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_placementDesired contact placement.
[out]position_residualResidual of the contact constraint. Size must be 6.

◆ computeContactVelocityDerivatives()

template<typename MatrixType1 , typename MatrixType2 >
void robotoc::SurfaceContact::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 6 x Robot::dimv().
[out]velocity_partial_dvThe partial derivative with respect to the velocity. Size must be 6 x Robot::dimv().

◆ computeContactVelocityResidual()

template<typename VectorType >
void robotoc::SurfaceContact::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.

◆ computeJointForceFromContactWrench()

void robotoc::SurfaceContact::computeJointForceFromContactWrench ( const Vector6d contact_wrench,
pinocchio::container::aligned_vector< pinocchio::Force > &  joint_forces 
) const

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

Parameters
[in]contact_wrenchThe 6D contact wrench in the local frame.
[out]joint_forcesThe corresponding joint spatial forces.

◆ contactFrameId()

int robotoc::SurfaceContact::contactFrameId ( ) const

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

Returns
Contact frame id.

◆ contactModelInfo()

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

Gets the contact model info.

Returns
const reference to the contact model info.

◆ contactPlacement()

const SE3 & robotoc::SurfaceContact::contactPlacement ( const pinocchio::Data &  data) const

Returns the contact placement 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 placmenet.

◆ disp()

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

Displays the surface contact onto a ostream.

◆ operator=() [1/2]

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

Default copy assign operator.

◆ operator=() [2/2]

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

Default move assign operator.

◆ parentJointId()

int robotoc::SurfaceContact::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::SurfaceContact::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 SurfaceContact surface_contact 
)
friend

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