Class Postural
Defined in File Postural.h
Inheritance Relationships
Base Type
public OpenSoT::Task< Eigen::MatrixXd, Eigen::VectorXd >
(Template Class Task)
Derived Type
public OpenSoT::tasks::velocity::JointAdmittance
(Class JointAdmittance)
Class Documentation
-
class Postural : public OpenSoT::Task<Eigen::MatrixXd, Eigen::VectorXd>
The Postural class implements a task that tries to bring the robust posture to a reference posture.
You can see an example of it in example_postural.cpp
Subclassed by OpenSoT::tasks::velocity::JointAdmittance
Public Functions
-
Postural(const XBot::ModelInterface &robot, const std::string &task_id = "Postural")
-
~Postural()
-
virtual void _update()
Updates the A, b, Aeq, beq, Aineq, b*Bound matrices.
-
void setReference(const Eigen::VectorXd &x_desired)
setReference sets a new reference for the Postural task.
It causes the task error to be recomputed immediately, without the need to call the _update(x) function. It also assumes a null desired velocity at the desired position, meaning we are trying to achieve a regulation task.
- Parameters
x_desired – the \(R^{n_x}\) vector describing the desired joint position
-
void setReference(const Eigen::VectorXd &x_desired, const Eigen::VectorXd &xdot_desired)
setReference sets a new reference for the Postural task.
It causes the task error to be recomputed immediately, without the need to call the _update(x) function Notice how the setReference(x_desired, xdot_desired) needs to be called before each _update(x) of the Postural task, since THE _update() RESETS THE FEED-FORWARD VELOCITY TERM for safety reasons.
- Parameters
x_desired – the \(R^{n_x}\) vector of desired joint positions.
xdot_desired – is a \(R^{n_x}\) vector describing the desired joint velocities, and it represents a feed-forward term in the Postural task computation NOTICE how the velocities are in rad/sample, instead of rad/s. This means that if you have a velocity expressed in SI units, you have to call the function as setReference(x_desired, xdot_desired*dt)
-
const Eigen::VectorXd &getReference() const
getReference returns the Postural task reference
- Returns
the \(R^{n_x}\) Postural task reference
-
const Eigen::VectorXd &getCachedVelocityReference() const
getCachedVelocityReference can be used to get Velocity reference after update(), it will reset next update()
- Returns
internal velcity reference
-
void getReference(Eigen::VectorXd &x_desired, Eigen::VectorXd &xdot_desired) const
getReference gets the current reference and feed-forward velocity for the Postural task.
- Parameters
x_desired – the \(R^{n_x}\) vector describing the desired position of the COM in the world coordinate frame.
xdot_desired – is a \(R^{n_x}\) twist describing the desired trajectory velocity, and it represents a feed-forward term in the task computation
-
virtual void setLambda(double lambda)
-
const Eigen::VectorXd &getActualPositions() const
getActualPositions return the actual state position of the task
- Returns
vector of joints positions
-
const Eigen::VectorXd &getError() const
getError return the error between the desired and actual joint position values
- Returns
vector of errors
-
virtual bool reset()
reset set as actual joint reference the actual pose
- Returns
Public Static Functions
Protected Functions
-
void update_b()
-
Postural(const XBot::ModelInterface &robot, const std::string &task_id = "Postural")