mc_rtc  2.14.0
ImpedanceTask.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015-2022 CNRS-UM LIRMM, CNRS-AIST JRL
3  */
4 
5 #pragma once
6 
9 
10 #include <mc_filter/LowPass.h>
11 
12 #include <mc_rtc/constants.h>
13 
14 namespace mc_tasks
15 {
16 
17 namespace force
18 {
19 
53 {
54 public:
55  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
56 
72  ImpedanceTask(const std::string & surfaceName,
73  const mc_rbdyn::Robots & robots,
74  unsigned robotIndex,
75  double stiffness = 5.0,
76  double weight = 1000.0,
77  bool showTarget = true,
78  bool showPose = true,
79  bool showCompliance = true);
80 
92  double stiffness = 5.0,
93  double weight = 1000.0,
94  bool showTarget = true,
95  bool showPose = true,
96  bool showCompliance = true);
97 
104  void reset() override;
105 
107  inline const ImpedanceGains & gains() const noexcept { return gains_; }
108 
110  inline ImpedanceGains & gains() noexcept { return gains_; }
111 
113  const sva::PTransformd & targetPose() const noexcept { return targetPoseW_; }
114 
116  void targetPose(const sva::PTransformd & pose) { targetPoseW_ = pose; }
117 
119  const sva::MotionVecd & targetVel() const noexcept { return targetVelW_; }
120 
122  void targetVel(const sva::MotionVecd & worldVel) override { targetVelW_ = worldVel; }
123 
125  const sva::MotionVecd & targetAccel() const noexcept { return targetAccelW_; }
126 
128  void targetAccel(const sva::MotionVecd & accel) { targetAccelW_ = accel; }
129 
131  const sva::PTransformd & deltaCompliancePose() const { return deltaCompPoseW_; }
132 
139  const sva::PTransformd compliancePose() const
140  {
141  sva::PTransformd T_0_d(targetPoseW_.rotation());
142  return T_0_d * deltaCompPoseW_ * T_0_d.inv() * targetPoseW_;
143  }
144 
146  const sva::ForceVecd & targetWrench() const noexcept { return targetWrench_; }
147 
152  void targetWrenchW(const sva::ForceVecd & wrenchW) { targetWrench(frame_->position().dualMul(wrenchW)); }
153 
155  void targetWrench(const sva::ForceVecd & wrench) { targetWrench_ = wrench; }
156 
158  const sva::ForceVecd & measuredWrench() const { return measuredWrench_; }
159 
161  const sva::ForceVecd & filteredMeasuredWrench() const { return filteredMeasuredWrench_; }
162 
164  double cutoffPeriod() const { return lowPass_.cutoffPeriod(); }
165 
167  void cutoffPeriod(double cutoffPeriod)
168  {
169  cutoffPeriod_ = cutoffPeriod;
170  lowPass_.cutoffPeriod(cutoffPeriod_);
171  }
172 
174  inline bool hold() const noexcept { return hold_; }
175 
186  inline void hold(bool hold) noexcept { hold_ = hold; }
187 
189  void load(mc_solver::QPSolver & solver, const mc_rtc::Configuration & config) override;
190 
191 protected:
193 
194  bool showTarget_ = true;
195  bool showPose_ = true;
196  bool showCompliance_ = true;
197 
203  sva::PTransformd deltaCompPoseW_ = sva::PTransformd::Identity();
204  sva::MotionVecd deltaCompVelW_ = sva::MotionVecd::Zero();
205  sva::MotionVecd deltaCompAccelW_ = sva::MotionVecd::Zero();
207 
208  // Limits of relative pose, velocity, and acceleration from target frame to compliance frame.
209  double deltaCompPoseLinLimit_ = 1.0;
210  double deltaCompPoseAngLimit_ = mc_rtc::constants::PI;
211  double deltaCompVelLinLimit_ = 1e3;
212  double deltaCompVelAngLimit_ = 1e3;
213  double deltaCompAccelLinLimit_ = 1e3;
214  double deltaCompAccelAngLimit_ = 1e3;
215 
216  // Target pose, velocity, and acceleration in the world frame
217  sva::PTransformd targetPoseW_ = sva::PTransformd::Identity();
218  sva::MotionVecd targetVelW_ = sva::MotionVecd::Zero();
219  sva::MotionVecd targetAccelW_ = sva::MotionVecd::Zero();
220 
221  // Wrench in the surface frame
222  sva::ForceVecd targetWrench_ = sva::ForceVecd::Zero();
223  sva::ForceVecd measuredWrench_ = sva::ForceVecd::Zero();
224  sva::ForceVecd filteredMeasuredWrench_ = sva::ForceVecd::Zero();
225 
226  double cutoffPeriod_ = 0.05;
228 
229  // Hold mode
230  bool hold_ = false;
231 
232  void update(mc_solver::QPSolver & solver) override;
233 
234  void addToSolver(mc_solver::QPSolver & solver) override;
235  void addToGUI(mc_rtc::gui::StateBuilder & gui) override;
236  void addToLogger(mc_rtc::Logger & logger) override;
237 
238 private:
248 
249  /* \brief Same as targetPose(const sva::PTransformd &) */
250  void target(const sva::PTransformd & pos) override { targetPose(pos); }
251 
252  /* \brief Same as targetPose() */
253  sva::PTransformd target() const override { return targetPose(); }
254 };
255 
256 } // namespace force
257 
258 } // namespace mc_tasks
#define MC_TASKS_DLLAPI
Definition: api.h:50
constexpr double PI
Definition: constants.h:18
Definition: StabilizerStandingState.h:12
Definition: RobotFrame.h:22
Definition: Robots.h:16
Simplify access to values hold within a JSON file.
Definition: Configuration.h:166
Logs controller data to disk.
Definition: Logger.h:30
Definition: StateBuilder.h:28
Definition: QPSolver.h:86
const Eigen::VectorXd & refAccel() const
Get the trajectory reference acceleration.
Control a frame 6D pose.
Definition: TransformTask.h:16
sva::MotionVecd refVelB() const
Get reference velocity in frame coordinates as a motion vector.
Definition: TransformTask.h:198
Represent impedance gains for an ImpedanceTask.
Definition: ImpedanceGains.h:96
static ImpedanceGains Default()
Definition: ImpedanceGains.h:132
Impedance control of the end-effector.
Definition: ImpedanceTask.h:53
void addToSolver(mc_solver::QPSolver &solver) override
Add the task to a solver.
void cutoffPeriod(double cutoffPeriod)
Set the cutoff period for the low-pass filter of measured wrench.
Definition: ImpedanceTask.h:167
void hold(bool hold) noexcept
Set hold mode.
Definition: ImpedanceTask.h:186
void addToLogger(mc_rtc::Logger &logger) override
bool hold() const noexcept
Get whether hold mode is enabled.
Definition: ImpedanceTask.h:174
const ImpedanceGains & gains() const noexcept
Access the impedance gains.
Definition: ImpedanceTask.h:107
mc_filter::LowPass< sva::ForceVecd > lowPass_
Definition: ImpedanceTask.h:227
void reset() override
Reset the task.
void targetWrenchW(const sva::ForceVecd &wrenchW)
Set the target wrench in the world frame. This function will convert the wrench from the world frame ...
Definition: ImpedanceTask.h:152
void targetAccel(const sva::MotionVecd &accel)
Set the target acceleration of the surface in the world frame.
Definition: ImpedanceTask.h:128
const sva::PTransformd & deltaCompliancePose() const
Get the relative pose from target frame to compliance frame represented in the world frame.
Definition: ImpedanceTask.h:131
void targetVel(const sva::MotionVecd &worldVel) override
Set the target velocity of the surface in the world frame.
Definition: ImpedanceTask.h:122
ImpedanceTask(const mc_rbdyn::RobotFrame &frame, double stiffness=5.0, double weight=1000.0, bool showTarget=true, bool showPose=true, bool showCompliance=true)
Constructor.
const sva::ForceVecd & targetWrench() const noexcept
Get the target wrench in the surface frame.
Definition: ImpedanceTask.h:146
const sva::MotionVecd & targetAccel() const noexcept
Get the target acceleration of the surface in the world frame.
Definition: ImpedanceTask.h:125
const sva::MotionVecd & targetVel() const noexcept
Get the target velocity of the surface in the world frame.
Definition: ImpedanceTask.h:119
const sva::PTransformd & targetPose() const noexcept
Get the target pose of the surface in the world frame.
Definition: ImpedanceTask.h:113
const sva::PTransformd compliancePose() const
Get the compliance pose of the surface in the world frame.
Definition: ImpedanceTask.h:139
void targetPose(const sva::PTransformd &pose)
Set the target pose of the surface in the world frame.
Definition: ImpedanceTask.h:116
void load(mc_solver::QPSolver &solver, const mc_rtc::Configuration &config) override
Load parameters from a Configuration object.
const sva::ForceVecd & filteredMeasuredWrench() const
Get the filtered measured wrench in the surface frame.
Definition: ImpedanceTask.h:161
void targetWrench(const sva::ForceVecd &wrench)
Set the target wrench in the surface frame.
Definition: ImpedanceTask.h:155
ImpedanceGains & gains() noexcept
Access the impedance gains.
Definition: ImpedanceTask.h:110
void update(mc_solver::QPSolver &solver) override
Update the task.
void addToGUI(mc_rtc::gui::StateBuilder &gui) override
double cutoffPeriod() const
Get the cutoff period for the low-pass filter of measured wrench.
Definition: ImpedanceTask.h:164
const sva::ForceVecd & measuredWrench() const
Get the measured wrench in the surface frame.
Definition: ImpedanceTask.h:158
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ImpedanceTask(const std::string &surfaceName, const mc_rbdyn::Robots &robots, unsigned robotIndex, double stiffness=5.0, double weight=1000.0, bool showTarget=true, bool showPose=true, bool showCompliance=true)
Constructor.