mc_tasks::force::ComplianceTask Struct Reference

Add a contact in a compliant manner. More...

#include <mc_tasks/ComplianceTask.h>

Inheritance diagram for mc_tasks::force::ComplianceTask:
Collaboration diagram for mc_tasks::force::ComplianceTask:

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
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ ComplianceTask() [1/2]

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.

Parameters
robotsRobots where the task will be applied
robotIndexWhich robot among the robots
bodyName of the body controlled by this task.
timestepTimestep of the controller
dofAllows to enable/disable some axis in the control/wrench monitoring
stiffnessStiffness of the task
weightWeight of the task
forceThreshForce threshold to reach
Torquethreshold to reach
forceGainPD gains on the force part
torqueGainPD gains on the torque part
Exceptions
Ifthe body the task is attempting to control does not have a sensor attached to it

◆ ComplianceTask() [2/2]

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.

Parameters
robotsRobots where the task will be applied
robotIndexWhich robot among the robots
bodyName of the body controlled by this task.
timestepTimestep of the controller
stiffnessStiffness of the task
weightWeight of the task
forceThreshForce threshold to reach
Torquethreshold to reach
forceGainPD gains on the force part
torqueGainPD gains on the torque part
Exceptions
Ifthe body the task is attempting to control does not have a sensor attached to it

Member Function Documentation

◆ dimWeight() [1/2]

Eigen::VectorXd mc_tasks::force::ComplianceTask::dimWeight ( ) const
overridevirtual

Get the current task's dim weight vector.

Implements mc_tasks::MetaTask.

◆ dimWeight() [2/2]

void mc_tasks::force::ComplianceTask::dimWeight ( const Eigen::VectorXd &  dimW)
overridevirtual

Set the task's dimension weight vector.

It is the caller responsibility to ensure the dimensionality fits the underlying tasks' error function

Parameters
dimWThe new tasks's dimension weight vector

Implements mc_tasks::MetaTask.

◆ dof() [1/2]

Eigen::Matrix6d mc_tasks::force::ComplianceTask::dof ( )
inline

Get the current dof matrix.

◆ dof() [2/2]

void mc_tasks::force::ComplianceTask::dof ( const Eigen::Matrix6d &  dof)
inline

Set the current dof matrix.

◆ eval()

Eigen::VectorXd mc_tasks::force::ComplianceTask::eval ( ) const
inlineoverridevirtual

Returns the task error.

The vector's dimensions depend on the underlying task

Implements mc_tasks::MetaTask.

◆ forceGain() [1/2]

std::pair<double, double> mc_tasks::force::ComplianceTask::forceGain ( )
inline

Get the force gain.

◆ forceGain() [2/2]

void mc_tasks::force::ComplianceTask::forceGain ( std::pair< double, double >  t)
inline

Set the force gain.

◆ forceThresh() [1/2]

double mc_tasks::force::ComplianceTask::forceThresh ( )
inline

Get the force threshold.

◆ forceThresh() [2/2]

void mc_tasks::force::ComplianceTask::forceThresh ( double  t)
inline

Set the force threshold.

◆ getFilteredWrench()

sva::ForceVecd mc_tasks::force::ComplianceTask::getFilteredWrench ( ) const

Get the filtered wrench used by the task as a measure.

◆ getTargetWrench()

sva::ForceVecd mc_tasks::force::ComplianceTask::getTargetWrench ( )
inline

Get the current target wrench.

◆ reset()

void mc_tasks::force::ComplianceTask::reset ( )
overridevirtual

Reset the task.

Set the end effector objective to the current position of the end-effector

Implements mc_tasks::MetaTask.

◆ resetJointsSelector()

void mc_tasks::force::ComplianceTask::resetJointsSelector ( mc_solver::QPSolver solver)
overridevirtual

Reset active joints selection.

Parameters
solverSolver where the task is involved

Implements mc_tasks::MetaTask.

◆ selectActiveJoints()

void mc_tasks::force::ComplianceTask::selectActiveJoints ( mc_solver::QPSolver solver,
const std::vector< std::string > &  activeJointsName,
const std::map< std::string, std::vector< std::array< int, 2 >>> &  activeDofs = {} 
)
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.

Note
Calling this method or the related selectUnactiveJoints should reset the current joints' selection
Parameters
solverSolver where the task is involved
activeJointsNameActive joints in the task
activeDofsAllow to select only part of the dofs of a joint

Implements mc_tasks::MetaTask.

◆ selectUnactiveJoints()

void mc_tasks::force::ComplianceTask::selectUnactiveJoints ( mc_solver::QPSolver solver,
const std::vector< std::string > &  unactiveJointsName,
const std::map< std::string, std::vector< std::array< int, 2 >>> &  unactiveDofs = {} 
)
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.

Note
Calling this method or the related selectActiveJoints should reset the current joints' selection
Parameters
solverSolver where the task is involved
unactiveJointsNameActive joints in the task
unactiveDofsAllow to select only part of the dofs of a joint

Implements mc_tasks::MetaTask.

◆ setTargetWrench()

void mc_tasks::force::ComplianceTask::setTargetWrench ( const sva::ForceVecd &  wrench)
inline

Modify the target wrench.

◆ speed()

Eigen::VectorXd mc_tasks::force::ComplianceTask::speed ( ) const
inlineoverridevirtual

Returns the task velocity.

The vector's dimensions depend on the underlying task

Implements mc_tasks::MetaTask.

◆ stiffness() [1/2]

double mc_tasks::force::ComplianceTask::stiffness ( )
inline

Get the task stiffness.

◆ stiffness() [2/2]

void mc_tasks::force::ComplianceTask::stiffness ( double  s)
inline

Set the task stiffness.

◆ torqueGain() [1/2]

std::pair<double, double> mc_tasks::force::ComplianceTask::torqueGain ( )
inline

Get the torque gain.

◆ torqueGain() [2/2]

void mc_tasks::force::ComplianceTask::torqueGain ( std::pair< double, double >  t)
inline

Set the torque gain.

◆ torqueThresh() [1/2]

double mc_tasks::force::ComplianceTask::torqueThresh ( )
inline

Get the torque threshold.

◆ torqueThresh() [2/2]

void mc_tasks::force::ComplianceTask::torqueThresh ( double  t)
inline

Set the torque threshold.

◆ weight() [1/2]

double mc_tasks::force::ComplianceTask::weight ( )
inline

Get the task weight.

◆ weight() [2/2]

void mc_tasks::force::ComplianceTask::weight ( double  w)
inline

Set the task weight.

Member Data Documentation

◆ defaultFGain

const EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::pair<double, double> mc_tasks::force::ComplianceTask::defaultFGain
static

◆ defaultTGain

const std::pair<double, double> mc_tasks::force::ComplianceTask::defaultTGain
static

The documentation for this struct was generated from the following file: