Class Postural
Defined in File Postural.h
Inheritance Relationships
Base Type
public OpenSoT::Task< Eigen::MatrixXd, Eigen::VectorXd >
(Template Class Task)
Class Documentation
-
class Postural : public OpenSoT::Task<Eigen::MatrixXd, Eigen::VectorXd>
The Postural class implement a postural task on the ACTUATED joints.
Underactuated joints are not considered. NOTICE that input vectors and matrices anyway consider the full 6+n state
Public Functions
-
Postural(const XBot::ModelInterface &robot, AffineHelper qddot, const std::string task_id = "Postural")
-
Postural(const XBot::ModelInterface &robot, const std::string task_id = "Postural")
-
void setReference(const Eigen::VectorXd &qref)
setReference sets a new reference for the postural actuated part.
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
qref – the desired position 6+n vector, first 6 joints are removed
dqref – describe the desired trajectory velocity 6+n vector, first 6 joints are removed
ddqref – describe the desired trajectory acceleration, and it represents a feed-forward term in task computation, 6+n vector, first 6 joints are removed.
-
void setReference(const Eigen::VectorXd &qref, const Eigen::VectorXd &dqref)
-
void setReference(const Eigen::VectorXd &qref, const Eigen::VectorXd &dqref, const Eigen::VectorXd &ddqref)
-
const Eigen::VectorXd &getReference() const
getReference return references (6+n vectors)
- Returns
joint position, velocity and acceleration desired
-
void getReference(Eigen::VectorXd &q_desired) const
-
void getReference(Eigen::VectorXd &q_desired, Eigen::VectorXd &qdot_desired) const
-
void getReference(Eigen::VectorXd &q_desired, Eigen::VectorXd &qdot_desired, Eigen::VectorXd &qddot_desired) const
-
const Eigen::VectorXd &getActualPositions() const
-
const Eigen::VectorXd &getError() const
getError
- Returns
position error vector (6+n vector)
-
const Eigen::VectorXd &getVelocityError() const
getVelocityError
- Returns
velocity error vector (6+n vector)
-
void setLambda(double lambda1, double lambda2)
setLambda
- Parameters
lambda1 –
lambda2 –
-
virtual void setLambda(double lambda)
setLambda
- Parameters
lambda –
-
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
-
virtual bool reset()
reset position reference to actual, velcoity and accelration to 0
- Returns
true
-
const Eigen::VectorXd &getCachedVelocityReference() const
getCachedVelocityReference can be used to get Velocity reference after update(), it will reset next update()
- Returns
internal velcity reference
-
const Eigen::VectorXd &getCachedAccelerationReference() const
getCachedAccelerationReference can be used to get Velocity reference after update(), it will reset next update()
- Returns
internal acceleration reference
-
void setKp(const Eigen::MatrixXd &Kp)
setKp set position gain
- Parameters
Kp – a SPD matrix (n+6 x n+6), first 6 elements are not used
-
void setKd(const Eigen::MatrixXd &Kd)
setKd set velocity gain
- Parameters
Kd – a SPD matrix (n+6 x n+6), first 6 elements are not used
-
void setGains(const Eigen::MatrixXd &Kp, const Eigen::MatrixXd &Kd)
setGains set both position and velocity gains
- Parameters
Kp – a SPD matrix (n+6 x n+6), first 6 elements are not used
Kd – a SPD matrix (n+6 x n+6), first 6 elements are not used
-
const Eigen::MatrixXd &getKp() const
getKp
- Returns
position gain (n+6 x n+6), first 6 elements are not used
-
const Eigen::MatrixXd &getKd() const
getKd
- Returns
velocity gain (n+6 x n+6), first 6 elements are not used
-
void getGains(Eigen::MatrixXd &Kp, Eigen::MatrixXd &Kd)
getGains return both position and velocity gains
- Parameters
Kp – (n+6 x n+6), first 6 elements are not used
Kd – (n+6 x n+6), first 6 elements are not used
-
inline const double getLambda() const
getLambda
- Returns
the lambda weight of the task
-
Postural(const XBot::ModelInterface &robot, AffineHelper qddot, const std::string task_id = "Postural")