#include <mc_tasks/PostureTask.h>
Public Member Functions | |
PostureTask (const mc_solver::QPSolver &solver, unsigned int rIndex, double stiffness=1, double weight=10) | |
void | reset () override |
Reset the task. More... | |
void | load (mc_solver::QPSolver &solver, const mc_rtc::Configuration &config) override |
Load parameters from a Configuration object. More... | |
void | dimWeight (const Eigen::VectorXd &dimW) override |
Set the task dimensional weight. More... | |
Eigen::VectorXd | dimWeight () const override |
Get the current task's dim weight vector. More... | |
void | selectActiveJoints (mc_solver::QPSolver &solver, const std::vector< std::string > &activeJointsName, const std::map< std::string, std::vector< std::array< int, 2 >>> &activeDofs={}) override |
Select active joints for this task. More... | |
void | selectUnactiveJoints (mc_solver::QPSolver &solver, const std::vector< std::string > &unactiveJointsName, const std::map< std::string, std::vector< std::array< int, 2 >>> &unactiveDofs={}) override |
Select inactive joints for this task. More... | |
void | resetJointsSelector (mc_solver::QPSolver &solver) override |
Reset the joint selector effect. More... | |
Eigen::VectorXd | eval () const override |
Returns the task error. More... | |
Eigen::VectorXd | speed () const override |
Returns the task velocity. More... | |
void | posture (const std::vector< std::vector< double >> &p) |
void | refVel (const Eigen::VectorXd &refVel) noexcept |
const Eigen::VectorXd & | refVel () const noexcept |
void | refAccel (const Eigen::VectorXd &refAccel) noexcept |
const Eigen::VectorXd & | refAccel () const noexcept |
std::vector< std::vector< double > > | posture () const |
void | jointGains (const mc_solver::QPSolver &solver, const std::vector< tasks::qp::JointGains > &jgs) |
void | jointStiffness (const mc_solver::QPSolver &solver, const std::vector< tasks::qp::JointStiffness > &jss) |
void | jointWeights (const std::map< std::string, double > &jws) |
void | target (const std::map< std::string, std::vector< double >> &joints) |
void | stiffness (double s) |
double | stiffness () const |
void | damping (double d) |
double | damping () const |
void | setGains (double stiffness, double damping) |
void | weight (double w) |
double | weight () const |
bool | inSolver () const |
Public Member Functions inherited from mc_tasks::MetaTask | |
MetaTask () | |
virtual | ~MetaTask () |
const std::string & | type () const |
virtual void | name (const std::string &name) |
const std::string & | name () const |
size_t | iterInSolver () const noexcept |
Get the number of iterations since the task was added to the solver. More... | |
void | resetIterInSolver () noexcept |
Set the number of iterations since the task was added to the solver to zero. More... | |
void | incrementIterInSolver () noexcept |
Increment the number of iterations since the task was added to the solver. More... | |
Backend | backend () const noexcept |
Protected Member Functions | |
void | addToSolver (mc_solver::QPSolver &solver) override |
Add the task to a solver. More... | |
void | removeFromSolver (mc_solver::QPSolver &solver) override |
Remove the task from a solver. More... | |
void | update (mc_solver::QPSolver &) override |
Update the task. More... | |
void | addToGUI (mc_rtc::gui::StateBuilder &) override |
void | addToLogger (mc_rtc::Logger &logger) override |
Protected Member Functions inherited from mc_tasks::MetaTask | |
virtual void | removeFromLogger (mc_rtc::Logger &) |
virtual void | removeFromGUI (mc_rtc::gui::StateBuilder &) |
virtual std::function< bool(const mc_tasks::MetaTask &task, std::string &)> | buildCompletionCriteria (double dt, const mc_rtc::Configuration &config) const |
Additional Inherited Members | |
Public Types inherited from mc_tasks::MetaTask | |
using | Backend = mc_solver::QPSolver::Backend |
Static Protected Member Functions inherited from mc_tasks::MetaTask | |
static void | addToSolver (MetaTask &t, mc_solver::QPSolver &solver) |
static void | removeFromSolver (MetaTask &t, mc_solver::QPSolver &solver) |
static void | update (MetaTask &t, mc_solver::QPSolver &solver) |
static void | addToLogger (MetaTask &t, mc_rtc::Logger &logger) |
static void | removeFromLogger (MetaTask &t, mc_rtc::Logger &logger) |
static void | addToGUI (MetaTask &t, mc_rtc::gui::StateBuilder &gui) |
static void | removeFromGUI (MetaTask &t, mc_rtc::gui::StateBuilder &gui) |
static void | ensureHasJoints (const mc_rbdyn::Robot &robot, const std::vector< std::string > &joints, const std::string &prefix) |
Protected Attributes inherited from mc_tasks::MetaTask | |
Backend | backend_ |
std::string | type_ |
std::string | name_ |
size_t | iterInSolver_ = 0 |
A posture task for a given robot
Note that eval/speed/dimWeight have different dimensions based on the backend:
mc_tasks::PostureTask::PostureTask | ( | const mc_solver::QPSolver & | solver, |
unsigned int | rIndex, | ||
double | stiffness = 1 , |
||
double | weight = 10 |
||
) |
|
overrideprotectedvirtual |
Add elements to the GUI through the helper
This will be called by the solver when the task is added.
The default implementation adds the type of the task under the {"Tasks", name_} category.
Reimplemented from mc_tasks::MetaTask.
|
overrideprotectedvirtual |
Add entries to the logger
This will be called by the solver if it holds a valid logger instance when the task is added.
The default implementation adds nothing to the log.
Reimplemented from mc_tasks::MetaTask.
|
overrideprotectedvirtual |
Add the task to a solver.
solver | Solver where to add the task |
Implements mc_tasks::MetaTask.
double mc_tasks::PostureTask::damping | ( | ) | const |
Get the task's current damping
void mc_tasks::PostureTask::damping | ( | double | d | ) |
Set the task damping, leaving its stiffness unchanged
damping | Task stiffness |
|
overridevirtual |
Get the current task's dim weight vector.
Implements mc_tasks::MetaTask.
|
overridevirtual |
Set the task dimensional weight.
For simple cases (using 0/1 as weights) prefer selectActiveJoints or selectUnactiveJoints which are simpler to use
Implements mc_tasks::MetaTask.
|
overridevirtual |
Returns the task error.
The vector's dimensions depend on the underlying task
Implements mc_tasks::MetaTask.
bool mc_tasks::PostureTask::inSolver | ( | ) | const |
True if the task is in the solver
void mc_tasks::PostureTask::jointGains | ( | const mc_solver::QPSolver & | solver, |
const std::vector< tasks::qp::JointGains > & | jgs | ||
) |
Set joint gains for the posture task
void mc_tasks::PostureTask::jointStiffness | ( | const mc_solver::QPSolver & | solver, |
const std::vector< tasks::qp::JointStiffness > & | jss | ||
) |
Set joint stiffness for the posture task
void mc_tasks::PostureTask::jointWeights | ( | const std::map< std::string, double > & | jws | ) |
Set joint weights for the posture task
|
overridevirtual |
Load parameters from a Configuration object.
Reimplemented from mc_tasks::MetaTask.
std::vector<std::vector<double> > mc_tasks::PostureTask::posture | ( | ) | const |
Get current posture objective
void mc_tasks::PostureTask::posture | ( | const std::vector< std::vector< double >> & | p | ) |
Change posture objective
|
noexcept |
Access the reference acceleration
|
noexcept |
Change reference acceleration
refAccel
Should be of size nrDof
|
noexcept |
Access the reference velocity
|
noexcept |
Change reference velocity
refVel
Should be of size nrDof
|
overrideprotectedvirtual |
Remove the task from a solver.
solver | Solver from which to remove the task |
Implements mc_tasks::MetaTask.
|
overridevirtual |
Reset the task.
Implements mc_tasks::MetaTask.
|
overridevirtual |
|
overridevirtual |
Select active joints for this task.
Manipulate dimWeight() to achieve its effect
Implements mc_tasks::MetaTask.
|
overridevirtual |
Select inactive joints for this task.
Manipulate dimWeight() to achieve its effect
Implements mc_tasks::MetaTask.
void mc_tasks::PostureTask::setGains | ( | double | stiffness, |
double | damping | ||
) |
Set both stiffness and damping
stiffness | Task stiffness |
damping | Task damping |
|
overridevirtual |
Returns the task velocity.
The vector's dimensions depend on the underlying task
Implements mc_tasks::MetaTask.
double mc_tasks::PostureTask::stiffness | ( | ) | const |
Get the current task's stiffness
void mc_tasks::PostureTask::stiffness | ( | double | s | ) |
Set the task stiffness/damping
Damping is automatically set to 2*sqrt(stiffness)
stiffness | Task stiffness |
void mc_tasks::PostureTask::target | ( | const std::map< std::string, std::vector< double >> & | joints | ) |
Set specific joint targets
joints | Map of joint's name to joint's configuration |
|
overrideprotectedvirtual |
Update the task.
This function (usually) has to be called at every iteration of the solver once it has been added. It should update the state of the task.
solver | Solver in which the task is inserted |
Implements mc_tasks::MetaTask.
double mc_tasks::PostureTask::weight | ( | ) | const |
Get task's weight
void mc_tasks::PostureTask::weight | ( | double | w | ) |
Set task's weight