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 class implements a task that tries to control the acceleration of the CoM w.r.t.
world frame.
Public Functions
-
CoM(const XBot::ModelInterface &robot, const AffineHelper &qddot)
CoM.
- Parameters
robot – the robot model
qddot – an affine structure variable
-
const std::string &getBaseLink() const
getBaseLink
- Returns
“world”
-
void setReference(const Eigen::Vector3d &ref)
setReference sets a new reference for the CoM task.
The task error IS NOT recomputed immediately, you need to call the _update(x) function Notice how the setReference(…) needs to be called before each _update(x) of the Cartesian task, since THE _update() RESETS THE FEED-FORWARD VELOCITY and ACCELERATION TERMS for safety reasons.
- Parameters
pose_ref – the \(R^{3}\) desired position
vel_ref – is a \(R^{3}\) twist describing the desired trajectory velocity
acc_ref – is a \(R^{3}\) twist describing the desired trajectory acceleration, and it represents a feed-forward term in the cartesian task computation.
-
void setReference(const Eigen::Vector3d &pose_ref, const Eigen::Vector3d &vel_ref)
-
void setReference(const Eigen::Vector3d &pose_ref, const Eigen::Vector3d &vel_ref, const Eigen::Vector3d &acc_ref)
-
void getReference(Eigen::Vector3d &ref) const
getReference
- Parameters
ref – position reference
-
void getReference(Eigen::Vector3d &pos_ref, Eigen::Vector3d &vel_ref) const
-
void getReference(Eigen::Vector3d &pos_ref, Eigen::Vector3d &vel_ref, Eigen::Vector3d &acc_ref) const
-
void getActualPose(Eigen::Vector3d &actual) const
getActualPose
- Parameters
actual – pose of the CoM
-
void getPosError(Eigen::Vector3d &error) const
-
virtual bool reset() override
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
-
void setLambda(double lambda1, double lambda2)
setLambda set position and velocity gains of the feedback errors
- Parameters
lambda1 – postion gain
lambda2 – velocity gain
-
virtual void setLambda(double lambda)
setLambda set position gain of the feedback error NOTE: velocity gain is set to 2*std::sqrt(lambda)
- Parameters
lambda – postion gain
-
void getLambda(double &lambda, double &lambda2)
getLambda return both position and velocity convergence gains
- Parameters
lambda – position gain
lambda2 – velocity gain
-
const double getLambda2() const
getLambda2 return velocity convergence gain
- Returns
lambda2 gain
-
const Eigen::Vector3d &getCachedVelocityReference() const
getCachedVelocityReference can be used to get Velocity reference after update(), it will reset next update()
- Returns
internal velcity reference
-
const Eigen::Vector3d &getCachedAccelerationReference() const
getCachedAccelerationReference can be used to get Velocity reference after update(), it will reset next update()
- Returns
internal acceleration reference
-
const Eigen::Matrix3d &getKp() const
-
const Eigen::Matrix3d &getKd() const
-
void setKp(const Eigen::Matrix3d &Kp)
-
void setKd(const Eigen::Matrix3d &Kd)
-
void setGains(const Eigen::Matrix3d &Kp, const Eigen::Matrix3d &Kd)
-
void getGains(Eigen::Matrix3d &Kp, Eigen::Matrix3d &Kd)
-
inline const double getLambda() const
getLambda
- Returns
the lambda weight of the task
-
CoM(const XBot::ModelInterface &robot, const AffineHelper &qddot)