Tetrapod Project
gait_controller.h
Go to the documentation of this file.
1 #pragma once
2 
4 
5 class GaitController : public Controller {
6  public: GaitController(
7  int controller_freq, double gait_period,
8  std::function<Eigen::Vector3d(double)> fl_traj, std::function<Eigen::Vector3d(double)> fr_traj,
9  std::function<Eigen::Vector3d(double)> rl_traj, std::function<Eigen::Vector3d(double)> rr_traj);
10 
11  /*** Functions ***/
12  public: void increment();
13 
14  public: void UpdateFeetReferences();
15  /*** Variables ***/
16  private: std::function<Eigen::Vector3d(double)> fl_traj;
17 
18  private: std::function<Eigen::Vector3d(double)> fr_traj;
19 
20  private: std::function<Eigen::Vector3d(double)> rl_traj;
21 
22  private: std::function<Eigen::Vector3d(double)> rr_traj;
23 
24  private: double gait_period;
25 
26  private: int iteration = 0;
27 };
int controller_freq
Definition: controller.h:110
std::function< Eigen::Vector3d(double)> rr_traj
std::function< Eigen::Vector3d(double)> fl_traj
void UpdateFeetReferences()
std::function< Eigen::Vector3d(double)> rl_traj
std::function< Eigen::Vector3d(double)> fr_traj
GaitController(int controller_freq, double gait_period, std::function< Eigen::Vector3d(double)> fl_traj, std::function< Eigen::Vector3d(double)> fr_traj, std::function< Eigen::Vector3d(double)> rl_traj, std::function< Eigen::Vector3d(double)> rr_traj)
Eigen::Vector3d Vector3d
Definition: kinematics.h:49