Controller.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018-2019, CNRS-UM LIRMM
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #pragma once
29 
30 #include <mc_control/api.h>
31 #include <mc_control/fsm/Controller.h>
32 #include <mc_control/mc_controller.h>
33 #include <mc_rtc/logging.h>
34 #include <mc_rtc/ros.h>
35 
36 #include <ros/ros.h>
37 #include <tf2_ros/transform_broadcaster.h>
38 #include <visualization_msgs/MarkerArray.h>
39 
40 #include <lipm_walking/Contact.h>
45 #include <lipm_walking/Pendulum.h>
47 #include <lipm_walking/Sole.h>
50 #include <mutex>
51 #include <thread>
52 
56 namespace lipm_walking
57 {
58 
63 
67 struct MC_CONTROL_DLLAPI Controller : public mc_control::fsm::Controller
68 {
69  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
70 
80  Controller(std::shared_ptr<mc_rbdyn::RobotModule> robot, double dt, const mc_rtc::Configuration & config);
81 
87  void reset(const mc_control::ControllerResetData & data) override;
88 
94  void addGUIElements(std::shared_ptr<mc_rtc::gui::StateBuilder> gui);
95 
101  void addGUIMarkers(std::shared_ptr<mc_rtc::gui::StateBuilder> gui);
102 
108  void addLogEntries(mc_rtc::Logger & logger);
109 
117  void internalReset();
118 
124  void leftFootRatio(double ratio);
125 
131  void loadFootstepPlan(std::string name);
132 
138  void pauseWalkingCallback(bool verbose = false);
139 
143  virtual bool run() override;
144 
150  void startLogSegment(const std::string & label);
151 
155  void stopLogSegment();
156 
160  bool updatePreview();
161 
165  void updateRealFromKinematics();
166 
170  void warnIfRobotIsInTheAir();
171 
175  mc_rbdyn::Robot & controlRobot()
176  {
177  return mc_control::fsm::Controller::robot();
178  }
179 
184  {
185  double duration;
186  if(doubleSupportDurationOverride_ > 0.)
187  {
188  duration = doubleSupportDurationOverride_;
189  doubleSupportDurationOverride_ = -1.;
190  }
191  else
192  {
193  duration = plan.doubleSupportDuration();
194  }
195  return duration;
196  }
197 
201  bool isLastDSP()
202  {
203  return (supportContact().id > targetContact().id);
204  }
205 
209  bool isLastSSP()
210  {
211  return (targetContact().id > nextContact().id);
212  }
213 
217  double leftFootRatio()
218  {
219  return leftFootRatio_;
220  }
221 
226  {
227  double leftFootPressure = realRobot().forceSensor("LeftFootForceSensor").force().z();
228  double rightFootPressure = realRobot().forceSensor("RightFootForceSensor").force().z();
229  leftFootPressure = std::max(0., leftFootPressure);
230  rightFootPressure = std::max(0., rightFootPressure);
231  return leftFootPressure / (leftFootPressure + rightFootPressure);
232  }
233 
238  {
239  return mpc_;
240  }
241 
245  const Contact & nextContact() const
246  {
247  return plan.nextContact();
248  }
249 
255  void nextDoubleSupportDuration(double duration)
256  {
257  doubleSupportDurationOverride_ = duration;
258  }
259 
264  {
265  return pendulum_;
266  }
267 
271  const Contact & prevContact() const
272  {
273  return plan.prevContact();
274  }
275 
279  mc_rbdyn::Robot & realRobot()
280  {
281  return real_robots->robot();
282  }
283 
288  {
289  return plan.singleSupportDuration();
290  }
291 
295  const Sole & sole() const
296  {
297  return sole_;
298  }
299 
304  {
305  return stabilizer_;
306  }
307 
312  {
313  return plan.supportContact();
314  }
315 
320  {
321  return plan.targetContact();
322  }
323 
324 public: /* visible to FSM states */
327  bool emergencyStop = false;
328  bool pauseWalking = false;
329  bool pauseWalkingRequested = false;
330  std::shared_ptr<Preview> preview;
331  std::shared_ptr<mc_tasks::OrientationTask> pelvisTask;
332  std::shared_ptr<mc_tasks::OrientationTask> torsoTask;
333  std::vector<std::vector<double>>
336 private: /* hidden from FSM states */
337  Eigen::Matrix3d pelvisOrientation_ = Eigen::Matrix3d::Identity();
338  Eigen::Vector3d realCom_ = Eigen::Vector3d::Zero();
339  Eigen::Vector3d realComd_ = Eigen::Vector3d::Zero();
340  FloatingBaseObserver floatingBaseObs_;
343  NetWrenchObserver netWrenchObs_;
344  Pendulum pendulum_;
345  Sole sole_;
346  Stabilizer stabilizer_;
347  bool leftFootRatioJumped_ = false;
348  double ctlTime_ = 0.;
349  double defaultTorsoPitch_ = 0.;
350  double doubleSupportDurationOverride_ = -1.; // [s]
351  double leftFootRatio_ = 0.5;
352  double maxCoMHeight_ = 2.;
353  double maxTorsoPitch_ = -0.2;
354  double minCoMHeight_ = 0.;
355  double minTorsoPitch_ = -0.2;
356  double torsoPitch_;
357  mc_rtc::Configuration mpcConfig_;
358  std::string segmentName_ = "";
359  unsigned nbLogSegments_ = 100;
360  unsigned nbMPCFailures_ = 0;
361 };
362 
363 } // namespace lipm_walking
const Contact & prevContact() const
Get previous contact in plan.
Definition: Controller.h:271
double measuredLeftFootRatio()
Estimate left foot pressure ratio from force sensors.
Definition: Controller.h:225
bool isLastSSP()
True during the last step.
Definition: Controller.h:209
Observe net contact wrench from force/torque measurements.
PlanInterpolator planInterpolator
Footstep plan interpolator.
Definition: Controller.h:326
std::shared_ptr< mc_tasks::OrientationTask > torsoTask
Torso orientation task.
Definition: Controller.h:332
Stabilizer & stabilizer()
This getter is only used for consistency with the rest of mc_rtc.
Definition: Controller.h:303
Footstep plan interpolator.
State of the inverted pendulum model.
Definition: Pendulum.h:40
mc_rbdyn::Robot & controlRobot()
Get control robot state.
Definition: Controller.h:175
mc_rbdyn::Robot & realRobot()
Get observed robot state.
Definition: Controller.h:279
std::vector< std::vector< double > > halfSitPose
Half-sit joint-angle configuration stored when the controller starts.
Definition: Controller.h:334
Main controller class.
Definition: Controller.h:67
double doubleSupportDuration()
Get next double support duration.
Definition: Controller.h:183
Kinematics-only floating-base observer.
static EIGEN_MAKE_ALIGNED_OPERATOR_NEW constexpr double SAMPLING_PERIOD
Duration of each sampling step in [s].
bool isLastDSP()
True after the last step.
Definition: Controller.h:201
Compute velocity by finite difference of position measurements, applying a low-pass filter to it...
FootstepPlan plan
Current footstep plan.
Definition: Controller.h:325
const Contact & targetContact()
Get current target contact.
Definition: Controller.h:319
const Contact & supportContact()
Get current support contact.
Definition: Controller.h:311
constexpr double PREVIEW_UPDATE_PERIOD
Preview update period, same as MPC sampling period.
Definition: Controller.h:62
const Contact & nextContact() const
Get next contact in plan.
Definition: Controller.h:245
double leftFootRatio()
Get fraction of total weight that should be sustained by the left foot.
Definition: Controller.h:217
double singleSupportDuration()
Get next SSP duration.
Definition: Controller.h:287
Model predictive control problem.
Walking stabilization based on linear inverted pendulum tracking.
Definition: Stabilizer.h:58
std::shared_ptr< mc_tasks::OrientationTask > pelvisTask
Pelvis orientation task.
Definition: Controller.h:331
Main controller namespace.
Definition: build.dox:1
const Sole & sole() const
Get model sole properties.
Definition: Controller.h:295
void nextDoubleSupportDuration(double duration)
Override next DSP duration.
Definition: Controller.h:255
Contacts wrap foot frames with extra info from the footstep plan.
Definition: Contact.h:58
Foot sole properties.
Definition: Sole.h:38
Pendulum & pendulum()
This getter is only used for consistency with the rest of mc_rtc.
Definition: Controller.h:263
Sequence of footsteps with gait parameters.
Definition: FootstepPlan.h:41
std::shared_ptr< Preview > preview
Current solution trajectory from the walking pattern generator.
Definition: Controller.h:330
ModelPredictiveControl & mpc()
Get model predictive control solver.
Definition: Controller.h:237