|
mc_rtc
2.14.0
|
Hybrid position-force control on a contacting end-effector. More...
#include <mc_tasks/DampingTask.h>


Public Member Functions | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | DampingTask (const mc_rbdyn::RobotFrame &frame, double stiffness=5.0, double weight=1000.0) |
| Initialize a new damping task. More... | |
| DampingTask (const std::string &robotSurface, const mc_rbdyn::Robots &robots, unsigned robotIndex, double stiffness=5.0, double weight=1000.0) | |
| Initialize a new damping task. More... | |
Public Member Functions inherited from mc_tasks::force::AdmittanceTask | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | AdmittanceTask (const mc_rbdyn::RobotFrame &frame, double stiffness=5.0, double weight=1000.0, bool showTarget=true, bool showPose=true) |
| Initialize a new admittance task. More... | |
| AdmittanceTask (const std::string &robotSurface, const mc_rbdyn::Robots &robots, unsigned robotIndex, double stiffness=5.0, double weight=1000.0, bool showTarget=true, bool showPose=true) | |
| Initialize a new admittance task. More... | |
| void | reset () override |
| Reset the task. More... | |
| const sva::ForceVecd & | admittance () const |
| Get the admittance coefficients of the task. More... | |
| void | admittance (const sva::ForceVecd &admittance) |
| Set the admittance coefficients of the task. More... | |
| sva::PTransformd | surfacePose () const |
| Get the current pose of the control frame in the inertial frame. More... | |
| sva::PTransformd | targetPose () |
| Get the target pose of the control frame in the world frame. More... | |
| void | targetPose (const sva::PTransformd &X_0_target) |
| Set target pose (position and orientation) of the frame in the world frame. More... | |
| sva::PTransformd | poseError () |
| Transform from current frame pose to target. More... | |
| const sva::ForceVecd & | targetWrench () const |
| Get the target wrench in the control frame. More... | |
| void | targetWrenchW (const sva::ForceVecd &wrenchW) |
| Set the target wrench in world frame. More... | |
| void | targetWrench (const sva::ForceVecd &wrench) |
| Set the target wrench in the control frame. More... | |
| sva::ForceVecd | measuredWrench () const |
| Get the measured wrench in the control frame. More... | |
| void | maxLinearVel (const Eigen::Vector3d &maxLinearVel) |
| Set the maximum translation velocity of the task. More... | |
| const Eigen::Vector3d & | maxLinearVel () const noexcept |
| void | maxAngularVel (const Eigen::Vector3d &maxAngularVel) |
| Set the maximum angular velocity of the task. More... | |
| const Eigen::Vector3d & | maxAngularVel () const noexcept |
| void | velFilterGain (double gain) |
| Set the gain of the low-pass filter on the reference velocity. More... | |
| double | velFilterGain () const noexcept |
| Return the gain of the low-pass filter on the reference velocity. More... | |
| void | refVelB (const sva::MotionVecd &velB) |
| Set the reference body velocity. More... | |
| void | load (mc_solver::QPSolver &solver, const mc_rtc::Configuration &config) override |
| Load parameters from a Configuration object. More... | |
Public Member Functions inherited from mc_tasks::TransformTask | |
| TransformTask (const mc_rbdyn::RobotFrame &frame, double stiffness=2.0, double weight=500.0, bool showTarget=true, bool showPose=true) | |
| Constructor. More... | |
| TransformTask (const std::string &surfaceName, const mc_rbdyn::Robots &robots, unsigned int robotIndex, double stiffness=2.0, double weight=500, bool showTarget=true, bool showPose=true) | |
| Constructor. More... | |
| void | reset () override |
| Reset the task. More... | |
| virtual sva::PTransformd | target () const |
| Get the task's target. More... | |
| virtual void | target (const sva::PTransformd &worldPos) |
| Set the task's target. More... | |
| virtual void | targetVel (const sva::MotionVecd &worldVel) |
| Get the task's target velocity. More... | |
| void | targetSurface (unsigned int robotIndex, const std::string &surfaceName, const sva::PTransformd &offset=sva::PTransformd::Identity()) |
| Targets a robot surface with an optional offset. The offset is expressed in the target contact frame. More... | |
| void | targetFrame (const mc_rbdyn::Frame &targetFrame, const sva::PTransformd &offset=sva::PTransformd::Identity()) |
| Targets a given frame with an optional offset. More... | |
| void | targetFrameVelocity (const mc_rbdyn::Frame &targetFrame, const sva::PTransformd &offset=sva::PTransformd::Identity()) |
| Targets a given frame velocity with an optional offset. More... | |
| virtual void | target (const mc_rbdyn::Frame &frame, const sva::PTransformd &offset) |
| Targets a given frame with an optional offset. More... | |
| const std::string & | surface () const noexcept |
| Retrieve the controlled frame name. More... | |
| const mc_rbdyn::RobotFrame & | frame () const noexcept |
| Return the controlled frame (const) More... | |
| sva::PTransformd | surfacePose () const noexcept |
| std::function< bool(const mc_tasks::MetaTask &task, std::string &)> | buildCompletionCriteria (double dt, const mc_rtc::Configuration &config) const override |
| void | addToLogger (mc_rtc::Logger &logger) override |
| void | setGains (const sva::MotionVecd &stiffness, const sva::MotionVecd &damping) |
| Set dimensional stiffness and damping. More... | |
| void | stiffness (const sva::MotionVecd &stiffness) |
| Set dimensional stiffness. More... | |
| sva::MotionVecd | mvStiffness () |
| Get dimensional stiffness as a motion vector. More... | |
| void | damping (const sva::MotionVecd &damping) |
| Set dimensional damping. More... | |
| sva::MotionVecd | mvDamping () |
| Get dimensional damping as a motion vector. More... | |
| void | refVelB (const sva::MotionVecd &velB) |
| Set trajectory task's reference velocity from motion vector in frame coordinates. More... | |
| sva::MotionVecd | refVelB () const |
| Get reference velocity in frame coordinates as a motion vector. More... | |
| void | refAccel (const sva::MotionVecd &accel) |
| Set trajectory task's reference acceleration from motion vector. More... | |
| void | load (mc_solver::QPSolver &solver, const mc_rtc::Configuration &config) override |
| Load parameters from a Configuration object. More... | |
| void | damping (double damping) |
| Set the task damping, leaving its stiffness unchanged. More... | |
| void | damping (const Eigen::VectorXd &damping) |
| Set dimensional damping. More... | |
| double | damping () const |
| Get the current task damping. More... | |
| void | setGains (double stiffness, double damping) |
| Set both stiffness and damping. More... | |
| void | setGains (const Eigen::VectorXd &stiffness, const Eigen::VectorXd &damping) |
| Set dimensional stiffness and damping. More... | |
| void | stiffness (double stiffness) |
| Set the task stiffness/damping. More... | |
| void | stiffness (const Eigen::VectorXd &stiffness) |
| Set dimensional stiffness. More... | |
| double | stiffness () const |
| Get the current task stiffness. More... | |
Public Member Functions inherited from mc_tasks::TrajectoryTaskGeneric | |
| TrajectoryTaskGeneric (const mc_rbdyn::Robots &robots, unsigned int robotIndex, double stiffness, double weight) | |
| Constructor (auto damping) More... | |
| TrajectoryTaskGeneric (const mc_rbdyn::RobotFrame &frame, double stiffness, double weight) | |
| Constructor (auto damping) More... | |
| virtual | ~TrajectoryTaskGeneric ()=default |
| void | refVel (const Eigen::VectorXd &vel) |
| Set the trajectory reference velocity. More... | |
| const Eigen::VectorXd & | refVel () const |
| Get the trajectory reference velocity. More... | |
| void | refAccel (const Eigen::VectorXd &accel) |
| Set the trajectory reference acceleration. More... | |
| const Eigen::VectorXd & | refAccel () const |
| Get the trajectory reference acceleration. More... | |
| void | stiffness (double stiffness) |
| Set the task stiffness/damping. More... | |
| void | stiffness (const Eigen::VectorXd &stiffness) |
| Set dimensional stiffness. More... | |
| void | damping (double damping) |
| Set the task damping, leaving its stiffness unchanged. More... | |
| void | damping (const Eigen::VectorXd &damping) |
| Set dimensional damping. More... | |
| void | setGains (double stiffness, double damping) |
| Set both stiffness and damping. More... | |
| void | setGains (const Eigen::VectorXd &stiffness, const Eigen::VectorXd &damping) |
| Set dimensional stiffness and damping. More... | |
| double | stiffness () const |
| Get the current task stiffness. More... | |
| double | damping () const |
| Get the current task damping. More... | |
| const Eigen::VectorXd & | dimStiffness () const |
| Get the current task dimensional stiffness. More... | |
| const Eigen::VectorXd & | dimDamping () const |
| Get the current task dimensional damping. More... | |
| void | weight (double w) |
| Set the task weight. More... | |
| double | weight () const |
| Returns the task weight. 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 (const std::vector< std::string > &activeJointsName, const std::map< std::string, std::vector< std::array< int, 2 >>> &activeDofs={}, bool checkJoints=true) |
| Create an active joints selector. 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 |
| Create an active joints selector. More... | |
| void | selectUnactiveJoints (const std::vector< std::string > &unactiveJointsName, const std::map< std::string, std::vector< std::array< int, 2 >>> &unactiveDofs={}, bool checkJoints=true) |
| Create an unactive 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 |
| Create an unactive joints selector. More... | |
| virtual void | resetJointsSelector () |
| 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... | |
| const Eigen::VectorXd & | normalAcc () 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 | update (mc_solver::QPSolver &) override |
| Update the task. More... | |
Protected Member Functions inherited from mc_tasks::force::AdmittanceTask | |
| void | addToGUI (mc_rtc::gui::StateBuilder &gui) override |
| void | addToLogger (mc_rtc::Logger &logger) override |
| void | addToSolver (mc_solver::QPSolver &solver) override |
| void | refVelB (const sva::MotionVecd &velB) |
| sva::MotionVecd | refVelB () const |
| virtual sva::PTransformd | target () const |
| virtual void | target (const sva::PTransformd &worldPos) |
| virtual void | target (const mc_rbdyn::Frame &frame, const sva::PTransformd &offset) |
Protected Member Functions inherited from mc_tasks::TransformTask | |
| void | addToGUI (mc_rtc::gui::StateBuilder &gui) override |
| void | refVel (const Eigen::VectorXd &vel) |
| Set the trajectory reference velocity. More... | |
| const Eigen::VectorXd & | refVel () const |
| Get the trajectory reference velocity. More... | |
Protected Member Functions inherited from mc_tasks::TrajectoryTaskGeneric | |
| template<Backend backend, typename ErrorT , typename... Args> | |
| void | finalize (Args &&... args) |
| 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... | |
Protected Member Functions inherited from mc_tasks::MetaTask | |
| virtual void | removeFromLogger (mc_rtc::Logger &) |
| virtual void | removeFromGUI (mc_rtc::gui::StateBuilder &) |
Additional Inherited Members | |
Public Types inherited from mc_tasks::TrajectoryTaskGeneric | |
| using | TrajectoryBase = TrajectoryTaskGeneric |
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::force::AdmittanceTask | |
| Eigen::Vector3d | maxAngularVel_ = {0.1, 0.1, 0.1} |
| Eigen::Vector3d | maxLinearVel_ = {0.1, 0.1, 0.1} |
| double | timestep_ |
| double | velFilterGain_ = 0.8 |
| sva::ForceVecd | admittance_ = sva::ForceVecd(Eigen::Vector6d::Zero()) |
| sva::ForceVecd | targetWrench_ = sva::ForceVecd(Eigen::Vector6d::Zero()) |
| sva::ForceVecd | wrenchError_ = sva::ForceVecd(Eigen::Vector6d::Zero()) |
| sva::MotionVecd | feedforwardVelB_ = sva::MotionVecd(Eigen::Vector6d::Zero()) |
| sva::MotionVecd | refVelB_ = sva::MotionVecd(Eigen::Vector6d::Zero()) |
| bool | showTarget_ = true |
| bool | showPose_ = true |
Protected Attributes inherited from mc_tasks::TransformTask | |
| mc_rbdyn::ConstRobotFramePtr | frame_ |
| bool | showTarget_ = true |
| bool | showPose_ = true |
Protected Attributes inherited from mc_tasks::TrajectoryTaskGeneric | |
| const mc_rbdyn::Robots & | robots |
| unsigned int | rIndex |
| mc_rtc::void_ptr | errorT {nullptr, nullptr} |
| Eigen::VectorXd | refVel_ |
| Eigen::VectorXd | refAccel_ |
| bool | inSolver_ = false |
| mc_rtc::void_ptr | trajectoryT_ {nullptr, nullptr} |
| Eigen::VectorXd | stiffness_ |
| Eigen::VectorXd | damping_ |
| double | weight_ |
| mc_rtc::void_ptr | selectorT_ {nullptr, nullptr} |
Protected Attributes inherited from mc_tasks::MetaTask | |
| Backend | backend_ |
| std::string | type_ |
| std::string | name_ |
| size_t | iterInSolver_ = 0 |
Hybrid position-force control on a contacting end-effector.
The DampingTask is by default a TransformTask, i.e. pure position control of a frame. Admittance coefficients that map force errors to displacements (see [1] and [2]) are initially set to zero.
When the admittance along one axis (Fx, Fy, Fz, Tx, Ty or Tz) is set to a non-zero positive value, this axis switches from position to force control. The goal is then to realize the prescribed target wrench at the control frame (bis repetita placent: wrenches are expressed in the control frame of the task, not in the sensor frame of the corresponding body). The force control law applied is damping control [3].
See the discussion in [4] for a comparison with the ComplianceTask.
[1] https://en.wikipedia.org/wiki/Mechanical_impedance [2] https://en.wikipedia.org/wiki/Impedance_analogy [3] https://doi.org/10.1109/IROS.2010.5651082 [4] https://gite.lirmm.fr/multi-contact/mc_rtc/issues/34
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW mc_tasks::force::DampingTask::DampingTask | ( | const mc_rbdyn::RobotFrame & | frame, |
| double | stiffness = 5.0, |
||
| double | weight = 1000.0 |
||
| ) |
Initialize a new damping task.
| frame | Control frame |
| stiffness | Stiffness of the underlying Transform task |
| weight | Weight of the underlying Transform task |
| If | the frame does not have a force sensor attached |
| mc_tasks::force::DampingTask::DampingTask | ( | const std::string & | robotSurface, |
| const mc_rbdyn::Robots & | robots, | ||
| unsigned | robotIndex, | ||
| double | stiffness = 5.0, |
||
| double | weight = 1000.0 |
||
| ) |
Initialize a new damping task.
| robotSurface | Name of the surface frame to control, in which the desired wrench will also be expressed |
| robots | Robots where the task will be applied |
| robotIndex | Which robot among the robots |
| stiffness | Stiffness of the underlying Transform task |
| weight | Weight of the underlying Transform task |
| If | the body the task is attempting to control does not have a sensor attached to it |
|
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 |
Reimplemented from mc_tasks::force::AdmittanceTask.