Controls an end-effector. More...
#include <mc_tasks/EndEffectorTask.h>
Public Member Functions | |
EndEffectorTask (const mc_rbdyn::RobotFrame &frame, double stiffness=2.0, double weight=1000.0) | |
Constructor. More... | |
EndEffectorTask (const std::string &bodyName, const mc_rbdyn::Robots &robots, unsigned int robotIndex, double stiffness=2.0, double weight=1000.0) | |
Constructor. More... | |
void | reset () override |
Reset the task. More... | |
virtual void | add_ef_pose (const sva::PTransformd &dtr) |
Increment the target position. More... | |
virtual void | set_ef_pose (const sva::PTransformd &tf) |
Change the target position. More... | |
virtual sva::PTransformd | get_ef_pose () |
Returns the current target positions. More... | |
void | dimWeight (const Eigen::VectorXd &dimW) override |
Set the task's dimension weight vector. 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 |
Setup an active joints selector. 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 |
Setup an unactive joints selector. More... | |
void | resetJointsSelector (mc_solver::QPSolver &solver) override |
Reset active joints selection. More... | |
Eigen::VectorXd | eval () const override |
Returns the task error. More... | |
Eigen::VectorXd | speed () const override |
Returns the task velocity. More... | |
void | load (mc_solver::QPSolver &solver, const mc_rtc::Configuration &config) override |
Load parameters from a Configuration object. More... | |
void | name (const std::string &name) override |
virtual void | name (const std::string &name) |
const std::string & | name () const |
Public Member Functions inherited from mc_tasks::MetaTask | |
MetaTask () | |
virtual | ~MetaTask () |
const std::string & | type () const |
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 |
Public Attributes | |
std::shared_ptr< mc_tasks::PositionTask > | positionTask |
std::shared_ptr< mc_tasks::OrientationTask > | orientationTask |
sva::PTransformd | curTransform |
Protected Member Functions | |
void | removeFromSolver (mc_solver::QPSolver &solver) override |
Remove the task from a solver. More... | |
void | addToSolver (mc_solver::QPSolver &solver) override |
Add the task to a solver. More... | |
void | update (mc_solver::QPSolver &) override |
Update the task. More... | |
void | addToLogger (mc_rtc::Logger &logger) override |
void | removeFromLogger (mc_rtc::Logger &logger) override |
void | addToGUI (mc_rtc::gui::StateBuilder &gui) override |
const mc_rbdyn::RobotFrame & | frame () const noexcept |
Protected Member Functions inherited from mc_tasks::MetaTask | |
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 |
Controls an end-effector.
This task is a thin wrapper around the appropriate tasks in Tasks. The task objective is given in the world frame. For relative control see mc_tasks::RelativeEndEffectorTask
mc_tasks::EndEffectorTask::EndEffectorTask | ( | const mc_rbdyn::RobotFrame & | frame, |
double | stiffness = 2.0 , |
||
double | weight = 1000.0 |
||
) |
Constructor.
\pararm frame Control frame
stiffness | Task stiffness |
weight | Task weight |
mc_tasks::EndEffectorTask::EndEffectorTask | ( | const std::string & | bodyName, |
const mc_rbdyn::Robots & | robots, | ||
unsigned int | robotIndex, | ||
double | stiffness = 2.0 , |
||
double | weight = 1000.0 |
||
) |
Constructor.
bodyName | Name of the body to control |
robots | Robots controlled by this task |
robotIndex | Index of the robot controlled by this task |
stiffness | Task stiffness |
weight | Task weight |
|
virtual |
Increment the target position.
dtr | Change in target position |
Reimplemented in mc_tasks::RelativeEndEffectorTask.
|
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.
Reimplemented in mc_tasks::RelativeEndEffectorTask.
|
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.
|
overridevirtual |
Get the current task's dim weight vector.
Implements mc_tasks::MetaTask.
|
overridevirtual |
Set the task's dimension weight vector.
It is the caller responsibility to ensure the dimensionality fits the underlying tasks' error function
dimW | The new tasks's dimension weight vector |
Implements mc_tasks::MetaTask.
|
overridevirtual |
Returns the task error.
The vector's dimensions depend on the underlying task
Implements mc_tasks::MetaTask.
|
inlineprotectednoexcept |
|
virtual |
Returns the current target positions.
Reimplemented in mc_tasks::RelativeEndEffectorTask.
|
overridevirtual |
Load parameters from a Configuration object.
Reimplemented from mc_tasks::MetaTask.
|
inline |
Get the name of the task
|
inline |
Set a name for the task
This name will be used to identify the task in logs, GUI...
The name should be set before being added to the solver.
|
overridevirtual |
Set a name for the task
This name will be used to identify the task in logs, GUI...
The name should be set before being added to the solver.
Reimplemented from mc_tasks::MetaTask.
|
overrideprotectedvirtual |
Remove entries from the logger
This will be called by the solver when the task is removed.
The default implementation removes everything registered with the MetaTask instance as a source, it is likely good enough
Reimplemented from mc_tasks::MetaTask.
|
overrideprotectedvirtual |
Remove the task from a solver.
solver | Solver from which to remove the task |
Implements mc_tasks::MetaTask.
|
overridevirtual |
Reset the task.
Set the task objective to the current end-effector position
Implements mc_tasks::MetaTask.
Reimplemented in mc_tasks::RelativeEndEffectorTask.
|
overridevirtual |
Reset active joints selection.
solver | Solver where the task is involved |
Implements mc_tasks::MetaTask.
|
overridevirtual |
Setup an active joints selector.
This function setups a tasks::qp;:JointsSelector for the task. Only the provided joints will be used to solve the task.
solver | Solver where the task is involved |
activeJointsName | Active joints in the task |
activeDofs | Allow to select only part of the dofs of a joint |
Implements mc_tasks::MetaTask.
|
overridevirtual |
Setup an unactive joints selector.
This function setups a tasks::qp;:JointsSelector for the task. All joints will be used to realize the task except those provided here.
solver | Solver where the task is involved |
unactiveJointsName | Active joints in the task |
unactiveDofs | Allow to select only part of the dofs of a joint |
Implements mc_tasks::MetaTask.
|
virtual |
Change the target position.
tf | New target position |
Reimplemented in mc_tasks::RelativeEndEffectorTask.
|
overridevirtual |
Returns the task velocity.
The vector's dimensions depend on the underlying task
Implements mc_tasks::MetaTask.
|
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.
sva::PTransformd mc_tasks::EndEffectorTask::curTransform |
std::shared_ptr<mc_tasks::OrientationTask> mc_tasks::EndEffectorTask::orientationTask |
std::shared_ptr<mc_tasks::PositionTask> mc_tasks::EndEffectorTask::positionTask |