CoMTask.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 
8 
9 namespace mc_tasks
10 {
11 
14 {
15 public:
27  CoMTask(const mc_rbdyn::Robots & robots, unsigned int robotIndex, double stiffness = 5.0, double weight = 100.);
28 
29  void reset() override;
30 
36  void move_com(const Eigen::Vector3d & com);
37 
43  void com(const Eigen::Vector3d & com);
44 
49  const Eigen::Vector3d & com() const;
50 
55  const Eigen::Vector3d & actual() const;
56 
58  void load(mc_solver::QPSolver &, const mc_rtc::Configuration & config) override;
59 
60 protected:
62  void addToLogger(mc_rtc::Logger & logger) override;
63 
64 private:
65  unsigned int robot_index_;
66 };
67 
68 } // namespace mc_tasks
#define MC_TASKS_DLLAPI
Definition: api.h:50
Definition: StabilizerStandingState.h:12
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
Control a robot's CoM.
Definition: CoMTask.h:14
void load(mc_solver::QPSolver &, const mc_rtc::Configuration &config) override
Load from configuration.
CoMTask(const mc_rbdyn::Robots &robots, unsigned int robotIndex, double stiffness=5.0, double weight=100.)
Constructor.
void addToLogger(mc_rtc::Logger &logger) override
void com(const Eigen::Vector3d &com)
Set the CoM target to a given position.
const Eigen::Vector3d & actual() const
Actual CoM position (computed at the previous iteration)
void reset() override
Reset the task.
void addToGUI(mc_rtc::gui::StateBuilder &) override
void move_com(const Eigen::Vector3d &com)
Change the CoM target by a given amount.
const Eigen::Vector3d & com() const
Return the current CoM target.
Generic wrapper for a trajectory dynamic over an error function.
Definition: TrajectoryTaskGeneric.h:27