robotoc
robotoc - efficient ROBOT Optimal Control solvers
|
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... | |
Robot & | operator= (const Robot &)=default |
Default copy assign operator. More... | |
Robot (Robot &&) noexcept=default | |
Default move constructor. More... | |
Robot & | operator= (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 SE3 & | framePlacement (const int frame_id) const |
Returns the SE(3) of the frame. Before calling this function, updateKinematics() or updateFrameKinematics() must be called. More... | |
const SE3 & | framePlacement (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< ContactType > | contactTypes () 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 RobotModelInfo & | robotModelInfo () const |
Gets the robot model info. More... | |
const RobotProperties & | robotProperties () 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) |
Dynamics and kinematics model of robots. Wraps pinocchio::Model and pinocchio::Data. Includes contacts.
using robotoc::Robot::Vector6d = Eigen::Matrix<double, 6, 1> |
robotoc::Robot::Robot | ( | const RobotModelInfo & | robot_model_info | ) |
Constructs a robot model according to the input model info.
[in] | robot_model_info | Info of a robot model. |
robotoc::Robot::Robot | ( | ) |
Default constructor.
|
default |
Default destructor.
|
default |
Default copy constructor.
|
defaultnoexcept |
Default move constructor.
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.
|
inline |
Computes the partial derivatives of the contact constriants represented by the Baumgarte's stabilization method. Before calling this function, updateKinematics() must be called.
[in] | contact_status | Contact status. |
[out] | baumgarte_partial_dq | The partial derivative with respect to the configuaration. Size must be ContactStatus::dimf() x Robot::dimv(). |
[out] | baumgarte_partial_dv | The partial derivative with respect to the velocity. Size must be ContactStatus::dimf() x Robot::dimv(). |
[out] | baumgarte_partial_da | The partial derivative with respect to the acceleration. Size must be ContactStatus::dimf() x be Robot::dimv(). |
|
inline |
Computes the residual of the contact constriants represented by Baumgarte's stabilization method. Before calling this function, updateKinematics() must be called.
[in] | contact_status | Contact status. |
[out] | baumgarte_residual | Residuals in the contact constraints. Size must be ContactStatus::dimf(). |
|
inline |
Computes the partial derivative of the contact position at the impact. Before calling this function, updateKinematics() must be called.
[in] | impact_status | Impact status. |
[out] | position_partial_dq | The result of the partial derivative with respect to the configuaration. Rows must be at least 3. Cols must be Robot::dimv(). |
|
inline |
Computes the residual of the contact position constraint at the impact. Before calling this function, updateKinematics() must be called.
[in] | impact_status | Impact status. |
[out] | position_residual | Residuals in the contact position constraint. Size must be ImpactStatus::dimf(). |
|
inline |
Computes the partial derivatives of the impact velocity constraint. Before calling this function, updateKinematics() must be called.
[in] | impact_status | Impact status. |
[out] | velocity_partial_dq | The partial derivative with respect to the configuaration. Size must be ImpactStatus::dimf() x Robot::dimv(). |
[out] | velocity_partial_dv | The partial derivative with respect to the velocity. Size must be ImpactStatus::dimf() x Robot::dimv(). |
|
inline |
Computes the residual of the impact velocity constraint. Before calling this function, updateKinematics() must be called.
[in] | impact_status | Impact status. |
[out] | velocity_residual | Residuals in the contact velocity constraint. Size must be ImpactStatus::dimf(). |
|
inline |
Computes the inverse of the joint inertia matrix M.
[in] | M | Joint inertia matrix. Size must be Robot::dimv() x Robot::dimv(). |
[out] | Minv | Inverse of the joint inertia matrix M. Size must be Robot::dimv() x Robot::dimv(). |
|
inline |
Computes the inverse of the contact dynamics matrix [[M J^T], [J O]].
[in] | M | Joint inertia matrix. Size must be Robot::dimv() x Robot::dimv(). |
[in] | J | Contact Jacobian. Size must be ContactStatus::dimf() x Robot::dimv(). |
[out] | MJtJinv | Inverse of the matrix [[M J^T], [J O]]. Size must be (Robot::dimv() + ContactStatus::dimf()) x (Robot::dimv() + ContactStatus::dimf()). |
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.
std::vector< std::string > robotoc::Robot::contactFrameNames | ( | ) | const |
Retruns the names of the contact frames involving the point or.
surface contacts.
std::vector< int > robotoc::Robot::contactFrames | ( | ) | const |
Retruns the indices of the frames involving the point or surface contacts.
ContactType robotoc::Robot::contactType | ( | const int | contact_index | ) | const |
Returns the type of the contact.
[in] | contact_index | Index of a contact of interedted. |
std::vector< ContactType > robotoc::Robot::contactTypes | ( | ) | const |
Returns the types of the contacts.
ContactStatus robotoc::Robot::createContactStatus | ( | ) | const |
Creates a ContactStatus for this robot model.
ImpactStatus robotoc::Robot::createImpactStatus | ( | ) | const |
Creates a ImpactStatus for this robot model.
int robotoc::Robot::dim_passive | ( | ) | const |
Returns the dimensiton of the generalized torques corresponding to the passive joints.
int robotoc::Robot::dimq | ( | ) | const |
Returns the dimensiton of the configuration.
int robotoc::Robot::dimu | ( | ) | const |
Returns the dimensiton of the velocity, i.e, tangent space.
int robotoc::Robot::dimv | ( | ) | const |
Returns the dimensiton of the velocity, i.e, tangent space.
|
inline |
Transport the Jacobian w.r.t. the configuration evaluated at the integrated configuration q + v to q.
[in] | q | Configuration. Size must be Robot::dimq(). |
[in] | v | Generalized velocity. Size must be Robot::dimv(). |
[in] | Jin | The Jacobian w.r.t. the configuration evaluated at q + v. Cols must be Robot::dimv(). |
[out] | Jout | The resultant Jacobian w.r.t. the configuration evaluated at q. The number of columns must be Robot::dimv(). |
|
inline |
Transport the Jacobian w.r.t. the generalized velocity evaluated at the integrated configuration q + v to q.
[in] | q | Configuration. Size must be Robot::dimq(). |
[in] | v | Generalized velocity. Size must be Robot::dimv(). |
[in] | Jin | The Jacobian w.r.t. the generalized velocity evaluated at q + v. Cols must be Robot::dimv(). |
[out] | Jout | The resultant Jacobian w.r.t. the generalized velocity evaluated at q. The number of columns must be Robot::dimv(). |
void robotoc::Robot::disp | ( | std::ostream & | os | ) | const |
Displays the robot model onto a ostream.
|
inline |
Computes the partial derivative of the function of subtraction qf - q0 w.r.t. the initial configuration qf.
[in] | qf | Terminal configuration. Size must be Robot::dimq(). |
[in] | q0 | Initial configuration. Size must be Robot::dimq(). |
[out] | dqdiff_dq0 | The partial derivative of the subtraction. Size must be Robot::dimv() x Robot::dimv(). |
|
inline |
Computes the partial derivative of the function of subtraction qf - q0 w.r.t. the terminal configuration qf.
[in] | qf | Terminal configuration. Size must be Robot::dimq(). |
[in] | q0 | Initial configuration. Size must be Robot::dimq(). |
[out] | dqdiff_dqf | The partial derivative of the subtraction. Size must be Robot::dimv() x Robot::dimv(). |
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.
[in] | frame_id | Index of the frame. |
[in] | reference_frame | Reference frame. Default is pinocchio::LOCAL_WORLD_ALIGNED (world velocity). |
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.
[in] | frame_name | Name of the frame. |
[in] | reference_frame | Reference frame. Default is pinocchio::LOCAL_WORLD_ALIGNED (world velocity). |
int robotoc::Robot::frameId | ( | const std::string & | frame_name | ) | const |
Gets the id of the specified frame.
[in] | frame_name | Frame name of interest. |
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.
[in] | frame_id | Index of the frame. |
[in] | reference_frame | Reference frame. Default is pinocchio::LOCAL_WORLD_ALIGNED (world velocity). |
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.
[in] | frame_name | Name of the frame. |
[in] | reference_frame | Reference frame. Default is pinocchio::LOCAL_WORLD_ALIGNED (world velocity). |
std::string robotoc::Robot::frameName | ( | const int | frame_id | ) | const |
Gets the name of the specified frame.
[in] | frame_id | Frame id of interest. |
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.
[in] | frame_id | Index of the frame. |
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.
[in] | frame_name | Name of the frame. |
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.
[in] | frame_id | Index of the frame. |
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.
[in] | frame_name | Name of the frame. |
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.
[in] | frame_id | Index of the frame. |
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.
[in] | frame_name | Name of the frame. |
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.
[in] | frame_id | Index of the frame. |
[in] | reference_frame | Reference frame. Default is pinocchio::LOCAL_WORLD_ALIGNED (world velocity). |
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.
[in] | frame_name | Name of the frame. |
[in] | reference_frame | Reference frame. Default is pinocchio::LOCAL_WORLD_ALIGNED (world velocity). |
Eigen::VectorXd robotoc::Robot::generateFeasibleConfiguration | ( | ) | const |
Generates feasible configuration randomly.
|
inline |
Gets the Jacobian of the position of the center of mass. Before calling this function, updateKinematics() must be called.
[out] | J | Jacobian. Size must be 3 x Robot::dimv(). |
|
inline |
Computes the Jacobian of the frame position expressed in the local coordinate. Before calling this function, updateKinematics() must be called.
[in] | frame_id | Index of the frame. |
[out] | J | Jacobian. Size must be 6 x Robot::dimv(). |
|
inline |
Jacobian of the transformation mapping of a 3D quantity from local frame to the world frame.
[in] | frame_id | Index of the frame whose local coordinate is of interest. |
[in] | vec_world | 3-dimensional vector-valued quantity expressed at the world frame. |
[out] | J | The Jacobian. Size must be 6 x Robot::dimv(). The result is stored at the top 3 rows. |
bool robotoc::Robot::hasFloatingBase | ( | ) | const |
Returns true if the robot has a floating base and false if not.
void robotoc::Robot::initializeJointLimits | ( | ) |
Initializes the results of jointEffortLimit(), jointVelocityLimit(), lowerJointPositionLimit(), and upperJointPositionLimit() by the URDF.
|
inline |
Transforms the Jacobian w.r.t. configuration to tangentspace.
[in] | q | Configuration. Size must be Robot::dimq(). |
[in,out] | J | Jacobian. Size must be Robot::dimq() x Robot::dimv(). |
|
inline |
Integrates the generalized velocity, that is, performs q_integrated = q + integration_length * v like computation on the configuration manifolds.
[in] | q | Configuration. Size must be Robot::dimq(). |
[in] | v | Generalized velocity. Size must be Robot::dimv(). |
[in] | integration_length | The length of the integration. |
[out] | q_integrated | Configuration. Size must be Robot::dimq(). |
|
inline |
Integrates the generalized velocity, that is, performs q <- q + integration_length * v like computation on the configuration manifolds.
[in] | v | Generalized velocity. Size must be Robot::dimv(). |
[in] | integration_length | The length of the integration. |
[in,out] | q | Configuration. Size must be Robot::dimq(). |
|
inline |
Computes an interpolation of two configurations by (1.0 - t) * s1 + t * s2.
[in] | q1 | Configuration. Size must be Robot::dimq(). |
[in] | q2 | Configuration. Size must be Robot::dimq(). |
[in] | t | Interpolation parameter. Must be between 0 to 1. |
[out] | qout | Configuration. Size must be Robot::dimq(). |
Eigen::VectorXd robotoc::Robot::jointEffortLimit | ( | ) | const |
Returns the effort limit of each joints.
Eigen::VectorXd robotoc::Robot::jointVelocityLimit | ( | ) | const |
Returns the joint velocity limit of each joints.
Eigen::VectorXd robotoc::Robot::lowerJointPositionLimit | ( | ) | const |
Returns the lower limit of the position of each joints.
int robotoc::Robot::max_dimf | ( | ) | const |
Returns the maximum dimension of the contacts.
int robotoc::Robot::maxNumContacts | ( | ) | const |
Returns the maximum number of the contacts.
int robotoc::Robot::maxNumPointContacts | ( | ) | const |
Returns the maximum number of the point contacts.
int robotoc::Robot::maxNumSurfaceContacts | ( | ) | const |
Returns the maximum number of the surface contacts.
|
inline |
Normalizes a configuration vector.
[in,out] | q | The normalized configuration. Size must be Robot::dimq(). |
std::vector< std::string > robotoc::Robot::pointContactFrameNames | ( | ) | const |
Retruns the names of the frames involving the contacts.
std::vector< int > robotoc::Robot::pointContactFrames | ( | ) | const |
Retruns the indices of the frames involving the contacts.
|
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.
[in] | q | Configuration. Size must be Robot::dimq(). |
[in] | v | Generalized velocity. Size must be Robot::dimv(). |
[in] | a | Generalized acceleration. Size must be Robot::dimv(). |
[out] | tau | Generalized torques for fully actuated system. Size must be Robot::dimv(). |
|
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.
[in] | q | Configuration. Size must be Robot::dimq(). |
[in] | v | Generalized velocity. Size must be Robot::dimv(). |
[in] | a | Generalized acceleration. Size must be Robot::dimv(). |
[out] | dRNEA_partial_dq | The partial derivative of inverse dynamics with respect to the configuration. The size must be Robot::dimv() x Robot::dimv(). |
[out] | dRNEA_partial_dv | The partial derivative of inverse dynamics with respect to the velocity. The size must be Robot::dimv() x Robot::dimv(). |
[out] | dRNEA_partial_da | The partial derivative of inverse dynamics with respect to the acceleration. The size must be Robot::dimv() x Robot::dimv(). |
|
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().
[in] | q | Configuration. Size must be Robot::dimq(). |
[in] | dv | Impact change in the velocity. Size must be Robot::dimv(). |
[out] | res | Residual of impact dynamics. Size must be Robot::dimv(). |
|
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().
[in] | q | Configuration. Size must be Robot::dimq(). |
[in] | dv | Impact change in the velocity. Size must be Robot::dimv(). |
[out] | dRNEA_partial_dq | The partial derivative of impact dynamics with respect to the configuration. The size must be Robot::dimv() x Robot::dimv(). |
[out] | dRNEA_partial_ddv | The partial derivative of impact dynamics with respect to the change in velocity. The size must be Robot::dimv() x Robot::dimv(). |
const RobotModelInfo & robotoc::Robot::robotModelInfo | ( | ) | const |
Gets the robot model info.
const RobotProperties & robotoc::Robot::robotProperties | ( | ) | const |
Gets a collectio of the properties of this robot model.
void robotoc::Robot::setContactForces | ( | const ContactStatus & | contact_status, |
const std::vector< Vector6d > & | f | ||
) |
Set contact forces in this robot model for each active contacts.
[in] | contact_status | Contact status. |
[in] | f | The stack of the contact wrenches represented in the local coordinate of the contact frame. Size must be Robot::maxNumContacts(). |
|
inline |
Set impact forces in this robot model for each active impacts.
[in] | impact_status | Impact status. |
[in] | f | The stack of the impact wrenches represented in the local coordinate of the contact frame. Size must be Robot::maxNumContacts(). |
void robotoc::Robot::setJointEffortLimit | ( | const Eigen::VectorXd & | joint_effort_limit | ) |
Sets the effort limit of each joints.
[in] | joint_effort_limit | The effort limit of each joints. |
void robotoc::Robot::setJointVelocityLimit | ( | const Eigen::VectorXd & | joint_velocity_limit | ) |
Sets the joint velocity limit of each joints.
[in] | joint_velocity_limit | Sets the joint velocity limit of each joints. |
void robotoc::Robot::setLowerJointPositionLimit | ( | const Eigen::VectorXd & | lower_joint_position_limit | ) |
Sets the lower limit of the position of each joints.
[in] | lower_joint_position_limit | The lower limit of the position of each joints. |
void robotoc::Robot::setRobotProperties | ( | const RobotProperties & | properties | ) |
Sets a collection of the properties for this robot model.
[in] | properties | A collection of the properties for this robot model. |
void robotoc::Robot::setUpperJointPositionLimit | ( | const Eigen::VectorXd & | upper_joint_position_limit | ) |
Sets the upper limit of the position of each joints.
[in] | upper_joint_position_limit | The upper limit of the position of each joints. |
|
inline |
Computes qf - q0 at the tangent space. The result means that the unit velocity from initial configuration q0 to terminal configuration qf.
[in] | qf | Terminal configuration. Size must be Robot::dimq(). |
[in] | q0 | Initial configuration. Size must be Robot::dimq(). |
[out] | qdiff | Difference of the configurations, qf - q0. Size must be Robot::dimv(). |
std::vector< std::string > robotoc::Robot::surfaceContactFrameNames | ( | ) | const |
Retruns the names of the frames involving the surface contacts.
std::vector< int > robotoc::Robot::surfaceContactFrames | ( | ) | const |
Retruns the indices of the frames involving the surface contacts.
double robotoc::Robot::totalMass | ( | ) | const |
Returns the total mass of this robot model.
double robotoc::Robot::totalWeight | ( | ) | const |
Returns the total weight of this robot model.
|
inline |
Transforms 3D quantity from local frame to the world frame.
[in] | frame_id | Index of the frame whose local coordinate is of interest. |
[in] | vec_local | 3-dimensional vector-valued quantity expressed at the local frame. |
[out] | vec_world | 3-dimensional vector-valued quantity expressed at the world frame. |
|
inline |
Updates the frame kinematics of the robot. The frame placements are calculated.
[in] | q | Configuration. Size must be Robot::dimq(). |
|
inline |
Updates the frame kinematics of the robot. The frame placements and velocities are calculated.
[in] | q | Configuration. Size must be Robot::dimq(). |
[in] | v | Generalized velocity. Size must be Robot::dimv(). |
|
inline |
Updates the frame kinematics of the robot. The frame placements, velocities, and accelerations are calculated.
[in] | q | Configuration. Size must be Robot::dimq(). |
[in] | v | Generalized velocity. Size must be Robot::dimv(). |
[in] | a | Generalized acceleration. Size must be Robot::dimv(). |
|
inline |
Updates the kinematics of the robot. The frame placements and and the relevant Jacobians are calculated.
[in] | q | Configuration. Size must be Robot::dimq(). |
|
inline |
Updates the kinematics of the robot. The frame placements, frame velocity, and the relevant Jacobians are calculated.
[in] | q | Configuration. Size must be Robot::dimq(). |
[in] | v | Generalized velocity. Size must be Robot::dimv(). |
|
inline |
Updates the kinematics of the robot. The frame placements, frame velocity, frame acceleration, and the relevant Jacobians are calculated.
[in] | q | Configuration. Size must be Robot::dimq(). |
[in] | v | Generalized velocity. Size must be Robot::dimv(). |
[in] | a | Generalized acceleration. Size must be Robot::dimv(). |
Eigen::VectorXd robotoc::Robot::upperJointPositionLimit | ( | ) | const |
Returns the upper limit of the position of each joints.
|
friend |