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> 37 #include <tf2_ros/transform_broadcaster.h> 38 #include <visualization_msgs/MarkerArray.h> 67 struct MC_CONTROL_DLLAPI
Controller :
public mc_control::fsm::Controller
69 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
80 Controller(std::shared_ptr<mc_rbdyn::RobotModule> robot,
double dt,
const mc_rtc::Configuration & config);
87 void reset(
const mc_control::ControllerResetData & data)
override;
94 void addGUIElements(std::shared_ptr<mc_rtc::gui::StateBuilder> gui);
101 void addGUIMarkers(std::shared_ptr<mc_rtc::gui::StateBuilder> gui);
108 void addLogEntries(mc_rtc::Logger & logger);
117 void internalReset();
124 void leftFootRatio(
double ratio);
131 void loadFootstepPlan(std::string name);
138 void pauseWalkingCallback(
bool verbose =
false);
143 virtual bool run()
override;
150 void startLogSegment(
const std::string & label);
155 void stopLogSegment();
160 bool updatePreview();
165 void updateRealFromKinematics();
170 void warnIfRobotIsInTheAir();
177 return mc_control::fsm::Controller::robot();
186 if(doubleSupportDurationOverride_ > 0.)
188 duration = doubleSupportDurationOverride_;
189 doubleSupportDurationOverride_ = -1.;
193 duration = plan.doubleSupportDuration();
203 return (supportContact().
id > targetContact().
id);
211 return (targetContact().
id > nextContact().
id);
219 return leftFootRatio_;
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);
247 return plan.nextContact();
257 doubleSupportDurationOverride_ = duration;
273 return plan.prevContact();
281 return real_robots->robot();
289 return plan.singleSupportDuration();
313 return plan.supportContact();
321 return plan.targetContact();
327 bool emergencyStop =
false;
328 bool pauseWalking =
false;
329 bool pauseWalkingRequested =
false;
333 std::vector<std::vector<double>>
337 Eigen::Matrix3d pelvisOrientation_ = Eigen::Matrix3d::Identity();
338 Eigen::Vector3d realCom_ = Eigen::Vector3d::Zero();
339 Eigen::Vector3d realComd_ = Eigen::Vector3d::Zero();
347 bool leftFootRatioJumped_ =
false;
348 double ctlTime_ = 0.;
349 double defaultTorsoPitch_ = 0.;
350 double doubleSupportDurationOverride_ = -1.;
351 double leftFootRatio_ = 0.5;
352 double maxCoMHeight_ = 2.;
353 double maxTorsoPitch_ = -0.2;
354 double minCoMHeight_ = 0.;
355 double minTorsoPitch_ = -0.2;
357 mc_rtc::Configuration mpcConfig_;
358 std::string segmentName_ =
"";
359 unsigned nbLogSegments_ = 100;
360 unsigned nbMPCFailures_ = 0;
const Contact & prevContact() const
Get previous contact in plan.
double measuredLeftFootRatio()
Estimate left foot pressure ratio from force sensors.
bool isLastSSP()
True during the last step.
Observe net contact wrench from force/torque measurements.
PlanInterpolator planInterpolator
Footstep plan interpolator.
std::shared_ptr< mc_tasks::OrientationTask > torsoTask
Torso orientation task.
Stabilizer & stabilizer()
This getter is only used for consistency with the rest of mc_rtc.
Footstep plan interpolator.
State of the inverted pendulum model.
mc_rbdyn::Robot & controlRobot()
Get control robot state.
mc_rbdyn::Robot & realRobot()
Get observed robot state.
std::vector< std::vector< double > > halfSitPose
Half-sit joint-angle configuration stored when the controller starts.
double doubleSupportDuration()
Get next double support duration.
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.
Compute velocity by finite difference of position measurements, applying a low-pass filter to it...
FootstepPlan plan
Current footstep plan.
const Contact & targetContact()
Get current target contact.
const Contact & supportContact()
Get current support contact.
constexpr double PREVIEW_UPDATE_PERIOD
Preview update period, same as MPC sampling period.
const Contact & nextContact() const
Get next contact in plan.
double leftFootRatio()
Get fraction of total weight that should be sustained by the left foot.
double singleSupportDuration()
Get next SSP duration.
Model predictive control problem.
Walking stabilization based on linear inverted pendulum tracking.
std::shared_ptr< mc_tasks::OrientationTask > pelvisTask
Pelvis orientation task.
Main controller namespace.
const Sole & sole() const
Get model sole properties.
void nextDoubleSupportDuration(double duration)
Override next DSP duration.
Pendulum & pendulum()
This getter is only used for consistency with the rest of mc_rtc.
std::shared_ptr< Preview > preview
Current solution trajectory from the walking pattern generator.
ModelPredictiveControl & mpc()
Get model predictive control solver.