Add a contact in a compliant manner. More...
#include <mc_tasks/ComplianceTask.h>
Public Member Functions | |
ComplianceTask (const mc_rbdyn::Robots &robots, unsigned int robotIndex, const std::string &body, double timestep, const Eigen::Matrix6d &dof=Eigen::Matrix6d::Identity(), double stiffness=5.0, double weight=1000.0, double forceThresh=3., double torqueThresh=1., std::pair< double, double > forceGain=defaultFGain, std::pair< double, double > torqueGain=defaultTGain) | |
Constructor with dof restrictions. More... | |
ComplianceTask (const mc_rbdyn::Robots &robots, unsigned int robotIndex, const std::string &body, double timestep, double stiffness=5.0, double weight=1000.0, double forceThresh=3., double torqueThresh=1., std::pair< double, double > forceGain=defaultFGain, std::pair< double, double > torqueGain=defaultTGain) | |
Constructor. More... | |
void | reset () override |
Reset the task. More... | |
sva::ForceVecd | getFilteredWrench () const |
Get the filtered wrench used by the task as a measure. More... | |
void | setTargetWrench (const sva::ForceVecd &wrench) |
Modify the target wrench. More... | |
sva::ForceVecd | getTargetWrench () |
Get the current target wrench. More... | |
void | stiffness (double s) |
Set the task stiffness. More... | |
double | stiffness () |
Get the task stiffness. More... | |
void | weight (double w) |
Set the task weight. More... | |
double | weight () |
Get the task weight. More... | |
void | forceThresh (double t) |
Set the force threshold. More... | |
double | forceThresh () |
Get the force threshold. More... | |
void | torqueThresh (double t) |
Set the torque threshold. More... | |
double | torqueThresh () |
Get the torque threshold. More... | |
void | forceGain (std::pair< double, double > t) |
Set the force gain. More... | |
std::pair< double, double > | forceGain () |
Get the force gain. More... | |
void | torqueGain (std::pair< double, double > t) |
Set the torque gain. More... | |
std::pair< double, double > | torqueGain () |
Get the torque gain. More... | |
void | dof (const Eigen::Matrix6d &dof) |
Set the current dof matrix. More... | |
Eigen::Matrix6d | dof () |
Get the current dof matrix. 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... | |
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 |
virtual void | load (mc_solver::QPSolver &solver, const mc_rtc::Configuration &config) |
Load parameters from a Configuration object. More... | |
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 |
Static Public Attributes | |
static const EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::pair< double, double > | defaultFGain |
static const std::pair< double, double > | defaultTGain |
Additional Inherited Members | |
Public Types inherited from mc_tasks::MetaTask | |
using | Backend = mc_solver::QPSolver::Backend |
Protected Member Functions inherited from mc_tasks::MetaTask | |
virtual void | addToLogger (mc_rtc::Logger &) |
virtual void | removeFromLogger (mc_rtc::Logger &) |
virtual void | addToGUI (mc_rtc::gui::StateBuilder &) |
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 |
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 |
Add a contact in a compliant manner.
Uses an mc_tasks::EndEffectorTask to drive the selected body until certain force and torque thresholds are reached.
This is a force-compliant variant of mc_tasks::AddContactTask that should be used when a force sensor is available.
mc_tasks::force::ComplianceTask::ComplianceTask | ( | const mc_rbdyn::Robots & | robots, |
unsigned int | robotIndex, | ||
const std::string & | body, | ||
double | timestep, | ||
const Eigen::Matrix6d & | dof = Eigen::Matrix6d::Identity() , |
||
double | stiffness = 5.0 , |
||
double | weight = 1000.0 , |
||
double | forceThresh = 3. , |
||
double | torqueThresh = 1. , |
||
std::pair< double, double > | forceGain = defaultFGain , |
||
std::pair< double, double > | torqueGain = defaultTGain |
||
) |
Constructor with dof restrictions.
robots | Robots where the task will be applied |
robotIndex | Which robot among the robots |
body | Name of the body controlled by this task. |
timestep | Timestep of the controller |
dof | Allows to enable/disable some axis in the control/wrench monitoring |
stiffness | Stiffness of the task |
weight | Weight of the task |
forceThresh | Force threshold to reach |
Torque | threshold to reach |
forceGain | PD gains on the force part |
torqueGain | PD gains on the torque part |
If | the body the task is attempting to control does not have a sensor attached to it |
mc_tasks::force::ComplianceTask::ComplianceTask | ( | const mc_rbdyn::Robots & | robots, |
unsigned int | robotIndex, | ||
const std::string & | body, | ||
double | timestep, | ||
double | stiffness = 5.0 , |
||
double | weight = 1000.0 , |
||
double | forceThresh = 3. , |
||
double | torqueThresh = 1. , |
||
std::pair< double, double > | forceGain = defaultFGain , |
||
std::pair< double, double > | torqueGain = defaultTGain |
||
) |
Constructor.
robots | Robots where the task will be applied |
robotIndex | Which robot among the robots |
body | Name of the body controlled by this task. |
timestep | Timestep of the controller |
stiffness | Stiffness of the task |
weight | Weight of the task |
forceThresh | Force threshold to reach |
Torque | threshold to reach |
forceGain | PD gains on the force part |
torqueGain | PD gains on the torque part |
If | the body the task is attempting to control does not have a sensor attached to it |
|
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.
|
inline |
Get the current dof matrix.
|
inline |
Set the current dof matrix.
|
inlineoverridevirtual |
Returns the task error.
The vector's dimensions depend on the underlying task
Implements mc_tasks::MetaTask.
|
inline |
Get the force gain.
|
inline |
Set the force gain.
|
inline |
Get the force threshold.
|
inline |
Set the force threshold.
sva::ForceVecd mc_tasks::force::ComplianceTask::getFilteredWrench | ( | ) | const |
Get the filtered wrench used by the task as a measure.
|
inline |
Get the current target wrench.
|
overridevirtual |
Reset the task.
Set the end effector objective to the current position of the end-effector
Implements mc_tasks::MetaTask.
|
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.
|
inline |
Modify the target wrench.
|
inlineoverridevirtual |
Returns the task velocity.
The vector's dimensions depend on the underlying task
Implements mc_tasks::MetaTask.
|
inline |
Get the task stiffness.
|
inline |
Set the task stiffness.
|
inline |
Get the torque gain.
|
inline |
Set the torque gain.
|
inline |
Get the torque threshold.
|
inline |
Set the torque threshold.
|
inline |
Get the task weight.
|
inline |
Set the task weight.
|
static |
|
static |