Template Class Task

Nested Relationships

Nested Types

Class Documentation

template<class Matrix_type, class Vector_type>
class Task

Task represents a task in the form \(T(A,b,c)\) where \(A\) is the task error jacobian, \(b\) is the task error and \(c\) is used for LP.

Public Types

typedef Task<Matrix_type, Vector_type> TaskType
typedef std::shared_ptr<TaskType> TaskPtr
typedef Constraint<Matrix_type, Vector_type> ConstraintType
typedef std::shared_ptr<ConstraintType> ConstraintPtr

Public Functions

inline Task(const std::string task_id, const unsigned int x_size)

Task define a task in terms of Ax = b.

Parameters
  • task_id – is a unique id

  • x_size – is the number of variables of the task

inline virtual ~Task()
inline bool getWeightIsDiagonalFlag()

getWeightIsDiagonal return the flag _weight_is_diagonal

Returns

true or false

inline void setWeightIsDiagonalFlag(const bool flag)

setWeightIsDiagonalFlag set the flag _weight_is_diagonal (NOTE that no check on Weight matrix is performed, we trust you)

Parameters

flag – true or false

inline void setActive(const bool active_flag)

Activated / deactivates the task by setting the A matrix to zero.

Important note: after activating a task, call the update() function in order to recompute a proper A matrix.

inline bool isActive() const

Returns a boolean which specifies if the task is active.

inline const Matrix_type &getA() const

getA

Returns

the A matrix of the task

inline const HessianType getHessianAtype()

getHessianAtype

Returns

the Hessian type

inline const Vector_type &getb() const

getb

Returns

the b matrix of the task

inline const Matrix_type &getWA() const

getWA

Returns

the product between W and A

inline const Matrix_type &getATranspose() const

getATranspose()

Returns

A transposed

inline const Vector_type &getWb() const

getWb

Returns

the product between W and b

inline const Vector_type &getc() const

getc

Returns

the _c vector of the task

inline const Matrix_type &getWeight() const

getWeight

Returns

the weight of the norm of the task error

inline virtual void setWeight(const Matrix_type &W)

setWeight sets the task weight.

Note the Weight needs to be positive definite. If your original intent was to get a subtask (i.e., reduce the number of rows of the task Jacobian), please use the class SubTask

Parameters

W – matrix weight

inline virtual void setWeight(const double &w)

setWeight sets the task diagonal weight.

Note the Weight needs to be positive definite. If your original intent was to get a subtask (i.e., reduce the number of rows of the task Jacobian), please use the class SubTask

Parameters

w – scalar diagonal weight

inline const double getLambda() const

getLambda

Returns

the lambda weight of the task

inline virtual void setLambda(double lambda)
inline virtual std::list<ConstraintPtr> &getConstraints()

getConstraints return a reference to the constraint list.

Use the standard list methods to add, remove, clear, … the constraints list. e.g.: task.getConstraints().push_back(new_constraint)

Returns

inline const unsigned int getXSize() const

Gets the number of variables for the task.

Returns

the number of columns of A

inline virtual const unsigned int getTaskSize() const

Gets the task size.

Returns

the number of rows of A

inline void update()

Updates the A, b, Aeq, beq, Aineq, b*Bound matrices.

inline std::string getTaskID()

getTaskID return the task id

Returns

a string with the task id

inline virtual std::vector<bool> getActiveJointsMask()

getActiveJointsMask return a vector of length NumberOfDOFs.

If an element is false the corresponding column of the task jacobian is set to 0.

Returns

a vector of bool

inline virtual bool setActiveJointsMask(const std::vector<bool> &active_joints_mask)

setActiveJointsMask set a mask on the Jacobian.

The changes take effect immediately.

Parameters

active_joints_mask

Returns

true if success

inline virtual void log(XBot::MatLogger2::Ptr logger)

log logs common Task internal variables

Parameters

logger – a shared pointer to a MathLogger

inline double computeCost(const Eigen::VectorXd &x)

computeCost computes the residual of the task:

residual = (Ax - b)^T * W * (Ax - b)

Parameters

x – solution NOTE: the solution should be the one where the task was evaluated to compute the internal A matrix and b vector! NOTE: computation can be improved as done in the solver…

Returns

the cost of the task for given solution

inline bool checkConsistency()

checkConsistency checks if all internal matrices and vectors are correctly instantiated and the right size

Returns

true if everything is ok

Protected Functions

virtual void _update() = 0

Updates the A, b, Aeq, beq, Aineq, b*Bound matrices.

inline virtual void applyActiveJointsMask(Matrix_type &A)

applyActiveJointsMask apply the active joint mask to the A matrix: in tasks in which b does not depend on A, this is done setting to 0 the columns of A corresponding to the index set to false of the _active_joint_mask vector

Parameters

A – matrix of the Task

inline virtual void _log(XBot::MatLogger2::Ptr logger)

_log can be used to log internal Task variables

Parameters

logger – a shared pointer to a MatLogger

inline 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

Protected Attributes

std::string _task_id

_task_id unique name of the task

unsigned int _x_size

_x_size size of the controlled variables

HessianType _hessianType

_hessianType Type of Hessian associated to the Task

Matrix_type _A

_A Jacobian of the Task

Vector_type _b

_b error associated to the Task

Vector_type _c

_c vector used for LP Tasks

Matrix_type _W

_W Weight multiplied to the task Jacobian

double _lambda

_lambda error scaling, NOTE: _lambda >= 0.0

bool _weight_is_diagonal

_weight_is_diagonal, if true the computation of W*A and W*b is optimized (default is false)

std::list<ConstraintPtr> _constraints

_bounds related to the Task

std::vector<bool> _active_joints_mask

_active_joint_mask is vector of bool that represent the active joints of the task.

If false the corresponding column of the task jacobian is set to 0.

struct istrue

Public Functions

inline bool operator()(int val) const