Class SubTask
Defined in File SubTask.h
Inheritance Relationships
Base Type
public OpenSoT::Task< Eigen::MatrixXd, Eigen::VectorXd >
(Template Class Task)
Class Documentation
-
class SubTask : public OpenSoT::Task<Eigen::MatrixXd, Eigen::VectorXd>
SubTask represents a task which is obtained as a sub task in the form \(T(A_s,b_s)\), where \(A_s\) is a reduced task error jacobian and \(b_s\) its corresponding task error.
Updating a SubTask calls the update method for the corresponding father task which it reduces, and recreates the reduced A,b and Weight matrices. In the same way, the constraints of the SubTask are those of the father Task, as well as the weight matrix W (the \(W_\text{subtask}\) is a submatrix of \(W\)) On the other side, the \(\lambda\) for the SubTask is unique to the SubTask.
Public Functions
-
SubTask(TaskPtr taskPtr, const std::list<unsigned int> rowIndices)
SubTask create a SubTask object by specifying the father Task through a pointer, and a list of row indices.
Notice the row indices start from 0 (c style)
- Parameters
taskPtr – a pointer to the father task
rowIndices – a list of indices. The index to the first row is 0.
-
inline virtual ~SubTask()
-
virtual void setWeight(const Eigen::MatrixXd &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
-
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) Notice that in subtasks, you will get the constraint list of the father Task from which the SubTask is generated.
- Returns
the list of constraints to which the father Task is subject.
-
virtual const unsigned int getTaskSize() const
Gets the task size.
- Returns
the number of rows of A
-
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
-
virtual bool setActiveJointsMask(const std::vector<bool> &active_joints_mask)
setActiveJointsMask set a mask on the jacobian
- Parameters
active_joints_mask –
- Returns
true if success
-
inline TaskPtr getTask()
getTask return the internal pointer of the task used to create the subtask
- Returns
internal pointer to task
Public Static Functions
Protected Functions
-
virtual void _log(XBot::MatLogger2::Ptr logger)
_log can be used to log internal Task variables
- Parameters
logger – a shared pointer to a MatLogger
-
void generateA()
-
void generateHessianAtype()
-
void generateb()
-
void generateWeight()
-
virtual void _update()
Updates the A, b, Aeq, beq, Aineq, b*Bound matrices.
- Parameters
x – variable state at the current step (input)
Protected Static Attributes
-
static const std::string _SUBTASK_SEPARATION_
-
SubTask(TaskPtr taskPtr, const std::list<unsigned int> rowIndices)