robotoc
robotoc - efficient ROBOT Optimal Control solvers
|
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... | |
PointContact & | operator= (const PointContact &)=default |
Default copy assign operator. More... | |
PointContact (PointContact &&) noexcept=default | |
Default move constructor. More... | |
PointContact & | operator= (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 ContactModelInfo & | contactModelInfo () 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) |
Kinematics and dynamic model of a point contact.
using robotoc::PointContact::Matrix6xd = Eigen::Matrix<double, 6, Eigen::Dynamic> |
robotoc::PointContact::PointContact | ( | const pinocchio::Model & | model, |
const ContactModelInfo & | contact_model_info | ||
) |
Construct a point contact model.
[in] | model | The pinocchio model. Before calling this constructor, pinocchio model must be initialized, e.g., by pinocchio::buildModel(). |
[in] | contact_model_info | Info of the point contact model. |
robotoc::PointContact::PointContact | ( | ) |
Default constructor.
|
default |
Default destructor.
|
default |
Default copy constructor.
|
defaultnoexcept |
Default move constructor.
|
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.
[in] | model | Pinocchio model of the robot. |
[in] | data | Pinocchio data of the robot kinematics. |
[out] | baumgarte_partial_dq | The partial derivative with respect to the configuaration. Size must be 3 x Robot::dimv(). |
[out] | baumgarte_partial_dv | The partial derivative with respect to the velocity. Size must be 3 x Robot::dimv(). |
[out] | baumgarte_partial_da | The partial derivative with respect to the acceleration. Size must be 3 x Robot::dimv(). |
|
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.
[in] | model | Pinocchio model of the robot. |
[in] | data | Pinocchio data of the robot kinematics. |
[in] | desired_contact_position | Desired contact position. Size must be 3. |
[out] | baumgarte_residual | Residual of the Bamgarte's constraint. Size must be 3. |
|
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.
[in] | model | Pinocchio model of the robot. |
[in] | data | Pinocchio data of the robot kinematics. |
[out] | position_partial_dq | The result of the partial derivative with respect to the configuaration. Size must be 3 x Robot::dimv(). |
|
inline |
Computes the residual of the contact position constraints. Before calling this function, kinematics of the robot model (frame position) must be updated.
[in] | model | Pinocchio model of the robot. |
[in] | data | Pinocchio data of the robot kinematics. |
[in] | desired_contact_position | Desired contact position. Size must be 3. |
[out] | position_residual | Residual of the contact constraint. Size must be 3. |
|
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.
[in] | model | Pinocchio model of the robot. |
[in] | data | Pinocchio data of the robot kinematics. |
[out] | velocity_partial_dq | The partial derivative with respect to the configuaration. Size must be 3 x Robot::dimv(). |
[out] | velocity_partial_dv | The partial derivative with respect to the velocity. Size must be 3 x Robot::dimv(). |
|
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.
[in] | model | Pinocchio model of the robot. |
[in] | data | Pinocchio data of the robot kinematics. |
[out] | velocity_residual | Residual of the contact velocity constraint. |
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.
[in] | contact_force | The 3D contact forces in the local frame. |
[out] | joint_forces | The corresponding joint spatial forces. |
int robotoc::PointContact::contactFrameId | ( | ) | const |
Returns contact frame id, i.e., the index of the contact frame.
const ContactModelInfo & robotoc::PointContact::contactModelInfo | ( | ) | const |
Gets the contact model info.
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.
[in] | data | Pinocchio data of the robot kinematics. |
void robotoc::PointContact::disp | ( | std::ostream & | os | ) | const |
Displays the point contact onto a ostream.
|
default |
Default copy assign operator.
|
defaultnoexcept |
Default move assign operator.
int robotoc::PointContact::parentJointId | ( | ) | const |
Returns parent joint id, i.e., the index of the parent joint of the contact frame.
void robotoc::PointContact::setBaumgarteGains | ( | const double | baumgarte_position_gain, |
const double | baumgarte_velocity_gain | ||
) |
Sets the gain parameters of the Baumgarte's stabilization method.
[in] | baumgarte_position_gain | The position gain of the Baumgarte's stabilization method. Must be non-negative. |
[in] | baumgarte_velocity_gain | The velocity gain of the Baumgarte's stabilization method. Must be non-negative. |
|
friend |