Class CoM
Defined in File CoM.h
Inheritance Relationships
Base Type
public OpenSoT::Task< Eigen::MatrixXd, Eigen::VectorXd >
(Template Class Task)
Class Documentation
-
class CoM : public OpenSoT::Task<Eigen::MatrixXd, Eigen::VectorXd>
The CoM task computes the wrenches at the contact, in world frame, in order to realize a certain acceleration and variation of angular momentum at the CoM considering the Centroidal Dynamics:
Note: variables are wrenches: w = [f tau]’m*ddr = sum(f) + mg dL = sum(pxf + tau)
Public Functions
-
CoM(std::vector<AffineHelper> wrenches, std::vector<std::string> &links_in_contact, XBot::ModelInterface &robot)
-
~CoM()
-
virtual void _update()
Updates the A, b, Aeq, beq, Aineq, b*Bound matrices.
-
void setLinearReference(const Eigen::Vector3d &desiredPosition)
-
void setLinearReference(const Eigen::Vector3d &desiredPosition, const Eigen::Vector3d &desiredVelocity)
-
void setLinearReference(const Eigen::Vector3d &desiredPosition, const Eigen::Vector3d &desiredVelocity, const Eigen::Vector3d &desiredAcceleration)
-
void setAngularReference(const Eigen::Vector3d &desiredAngularMomentum)
-
void setAngularReference(const Eigen::Vector3d &desiredAngularMomentum, const Eigen::Vector3d &desiredVariationAngularMomentum)
-
void setLinksInContact(const std::vector<std::string> &links_in_contact)
-
std::vector<std::string> getLinksInContact()
-
Eigen::Vector3d getLinearReference() const
-
void getLinearReference(Eigen::Vector3d &desiredPosition, Eigen::Vector3d &desiredVelocity) const
-
void getLinearReference(Eigen::Vector3d &desiredPosition, Eigen::Vector3d &desiredVelocity, Eigen::Vector3d &desiredAcceleration) const
-
Eigen::Vector3d getAngularReference() const
-
void getAngularReference(Eigen::Vector3d &desiredAngularMomentum, Eigen::Vector3d &desiredVariationAngularMomentum) const
-
Eigen::Vector3d getActualPosition() const
-
Eigen::Vector3d getActualVelocity() const
-
Eigen::Vector3d getActualAngularMomentum() const
-
std::string getBaseLink()
getBaseLink an utility function that always returns “world”
- Returns
“world”
-
std::string getDistalLink()
getDistalLink an utility function that always
- Returns
-
void setLambda(double lambda, double lambda2, double lambdaAngularMomentum)
-
const Eigen::Vector3d &getError()
getError returns the position error between actual and reference positions
- Returns
a \(R^{3}\) vector describing cartesian error between actual and reference position
-
const Eigen::Vector3d &getVelocityError()
getError returns the position error between actual and reference positions
- Returns
a \(R^{3}\) vector describing cartesian error between actual and reference position
-
const Eigen::Vector3d &getAngularMomentumError()
-
const Eigen::MatrixXd &computeA(const std::vector<std::string> &links_in_contact)
-
virtual bool reset()
reset permits to reset a task and all related variables.
The correctness of the implementation depends to the particular task. Default implementation does nothing and return false.
- Returns
false
-
CoM(std::vector<AffineHelper> wrenches, std::vector<std::string> &links_in_contact, XBot::ModelInterface &robot)