robotoc
robotoc - efficient ROBOT Optimal Control solvers
Loading...
Searching...
No Matches
flying_trot_foot_step_planner.hpp
Go to the documentation of this file.
1#ifndef ROBOTOC_FLYING_TROT_FOOT_STEP_PLANNER_HPP_
2#define ROBOTOC_FLYING_TROT_FOOT_STEP_PLANNER_HPP_
3
4#include <vector>
5#include <iostream>
6
7#include "Eigen/Core"
8#include "Eigen/Geometry"
9
12#include "robotoc/robot/se3.hpp"
17
18
19namespace robotoc {
20
26public:
31 FlyingTrotFootStepPlanner(const Robot& quadruped_robot);
32
37
42
47
52
57
61 FlyingTrotFootStepPlanner& operator=(FlyingTrotFootStepPlanner&&) noexcept = default;
62
68 void setGaitPattern(const Eigen::Vector3d& step_length, const double step_yaw);
69
78 void setRaibertGaitPattern(const Eigen::Vector3d& vcom_cmd,
79 const double yaw_rate_cmd, const double flying_time,
80 const double stance_time, const double gain);
81
86 void setContactSurfaces(const std::vector<Eigen::Matrix3d>& contact_surfaces);
87
93 const std::vector<std::vector<Eigen::Matrix3d>>& contact_surfaces);
94
95 void init(const Eigen::VectorXd& q) override;
96
97 bool plan(const double t, const Eigen::VectorXd& q, const Eigen::VectorXd& v,
98 const ContactStatus& contact_status,
99 const int planning_steps) override;
100
104 const aligned_vector<SE3>& contactPlacements(const int step) const override;
105
106 const std::vector<Eigen::Vector3d>& contactPositions(const int step) const override;
107
108 const std::vector<Eigen::Matrix3d>& contactSurfaces(const int step) const override;
109
110 const Eigen::Vector3d& CoM(const int step) const override;
111
112 const Eigen::Matrix3d& R(const int step) const override;
113
114 int size() const override { return planning_size_; }
115
116 friend std::ostream& operator<<(std::ostream& os,
117 const FlyingTrotFootStepPlanner& planner);
118
119 friend std::ostream& operator<<(std::ostream& os,
120 const std::shared_ptr<FlyingTrotFootStepPlanner>& planner);
121
122 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
123
124private:
125 Robot robot_;
126 RaibertHeuristic raibert_heuristic_;
127 MovingWindowFilter<2> vcom_moving_window_filter_;
128 bool enable_raibert_heuristic_;
129 int LF_foot_id_, LH_foot_id_, RF_foot_id_, RH_foot_id_, current_step_, planning_size_;
130 aligned_vector<aligned_vector<SE3>> contact_placement_ref_;
131 std::vector<std::vector<Eigen::Vector3d>> contact_position_ref_;
132 std::vector<std::vector<Eigen::Matrix3d>> contact_surface_ref_;
133 std::vector<Eigen::Vector3d> com_ref_, com_to_contact_position_local_;
134 std::vector<Eigen::Matrix3d> R_;
135 Eigen::Vector3d vcom_, vcom_cmd_, step_length_;
136 Eigen::Matrix3d R_yaw_, R_current_;
137 double yaw_rate_cmd_;
138};
139
140} // namespace robotoc
141
142#endif // ROBOTOC_FLYING_TROT_FOOT_STEP_PLANNER_HPP_
Base interface of contact planners.
Definition: contact_planner_base.hpp:21
Contact status of robot model.
Definition: contact_status.hpp:32
Foot step planner for the flying trot gait of quadrupeds.
Definition: flying_trot_foot_step_planner.hpp:25
void setGaitPattern(const Eigen::Vector3d &step_length, const double step_yaw)
Sets the gait pattern by step length and yaw step command.
FlyingTrotFootStepPlanner(const FlyingTrotFootStepPlanner &)=default
Default copy constructor.
void setRaibertGaitPattern(const Eigen::Vector3d &vcom_cmd, const double yaw_rate_cmd, const double flying_time, const double stance_time, const double gain)
Sets the gait pattern by Raibert heuristic.
int size() const override
Gets the size of each planned quantities.
Definition: flying_trot_foot_step_planner.hpp:114
const aligned_vector< SE3 > & contactPlacements(const int step) const override
This is invalid in FlyingTrotFootStepPlanner.
FlyingTrotFootStepPlanner(FlyingTrotFootStepPlanner &&) noexcept=default
Default move constructor.
FlyingTrotFootStepPlanner()
Default constructor.
const Eigen::Vector3d & CoM(const int step) const override
Gets the CoM position of a specified step.
bool plan(const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const ContactStatus &contact_status, const int planning_steps) override
Plans the foot steps in the MPC (receding-horizon) fashion.
friend std::ostream & operator<<(std::ostream &os, const std::shared_ptr< FlyingTrotFootStepPlanner > &planner)
const std::vector< Eigen::Matrix3d > & contactSurfaces(const int step) const override
Gets the contact surfaces of a specified step.
void setContactSurfaces(const std::vector< Eigen::Matrix3d > &contact_surfaces)
Sets the rotation of the contact surfaces.
void init(const Eigen::VectorXd &q) override
Initializes the planner.
const Eigen::Matrix3d & R(const int step) const override
Gets the rotation matrix of the base at a specified step.
friend std::ostream & operator<<(std::ostream &os, const FlyingTrotFootStepPlanner &planner)
FlyingTrotFootStepPlanner(const Robot &quadruped_robot)
Constructs the planner.
FlyingTrotFootStepPlanner & operator=(const FlyingTrotFootStepPlanner &)=default
Default copy assign operator.
const std::vector< Eigen::Vector3d > & contactPositions(const int step) const override
Gets the contact positions of a specified step.
Moving window filter for foot step planning.
Definition: moving_window_filter.hpp:17
Raibert heuristic for foot step planning.
Definition: raibert_heuristic.hpp:23
Dynamics and kinematics model of robots. Wraps pinocchio::Model and pinocchio::Data....
Definition: robot.hpp:32
Definition: constraint_component_base.hpp:17
std::vector< T, Eigen::aligned_allocator< T > > aligned_vector
std vector with Eigen::aligned_allocator.
Definition: aligned_vector.hpp:14
pinocchio::SE3 SE3
Using pinocchio::SE3 without its namespace.
Definition: se3.hpp:15