Quad-SDK
local_footstep_planner.h
1#ifndef LOCAL_FOOTSTEP_PLANNER_H
2#define LOCAL_FOOTSTEP_PLANNER_H
3
4#include <eigen_conversions/eigen_msg.h>
5#include <local_planner/local_planner_modes.h>
6#include <nav_msgs/Path.h>
7#include <quad_msgs/FootPlanDiscrete.h>
8#include <quad_msgs/FootState.h>
9#include <quad_msgs/MultiFootPlanContinuous.h>
10#include <quad_msgs/MultiFootPlanDiscrete.h>
11#include <quad_msgs/MultiFootState.h>
12#include <quad_msgs/RobotPlan.h>
13#include <quad_msgs/RobotState.h>
14#include <quad_utils/fast_terrain_map.h>
15#include <quad_utils/function_timer.h>
16#include <quad_utils/math_utils.h>
17#include <quad_utils/quad_kd.h>
18#include <quad_utils/ros_utils.h>
19#include <ros/ros.h>
20
21#include <eigen3/Eigen/Eigen>
22#include <grid_map_core/grid_map_core.hpp>
23#include <grid_map_ros/GridMapRosConverter.hpp>
24#include <grid_map_ros/grid_map_ros.hpp>
25
27
33 public:
39
47 void setTemporalParams(double dt, int period, int horizon_length,
48 const std::vector<double> &duty_cycles,
49 const std::vector<double> &phase_offsets);
50
66 void setSpatialParams(double ground_clearance, double hip_clearance,
67 double grf_weight, double standing_error_threshold,
68 std::shared_ptr<quad_utils::QuadKD> kinematics,
69 double foothold_search_radius,
70 double foothold_obj_threshold,
71 std::string obj_fun_layer, double toe_radius);
72
80 void getFootPositionsBodyFrame(const Eigen::VectorXd &body_plan,
81 const Eigen::VectorXd &foot_positions_world,
82 Eigen::VectorXd &foot_positions_body);
83
90 void getFootPositionsBodyFrame(const Eigen::MatrixXd &body_plan,
91 const Eigen::MatrixXd &foot_positions_world,
92 Eigen::MatrixXd &foot_positions_body);
93
98 void updateMap(const FastTerrainMap &terrain);
99
104 void updateMap(const grid_map::GridMap &terrain);
105
113 void computeContactSchedule(int current_plan_index,
114 const Eigen::VectorXi &ref_primitive_plan_,
115 int control_mode,
116 std::vector<std::vector<bool>> &contact_schedule);
117
135 void computeFootPlan(int current_plan_index,
136 const std::vector<std::vector<bool>> &contact_schedule,
137 const Eigen::MatrixXd &body_plan,
138 const Eigen::MatrixXd &grf_plan,
139 const Eigen::MatrixXd &ref_body_plan,
140 const Eigen::VectorXd &foot_positions_current,
141 const Eigen::VectorXd &foot_velocities_current,
142 double first_element_duration,
143 quad_msgs::MultiFootState &past_footholds_msg,
144 Eigen::MatrixXd &foot_positions,
145 Eigen::MatrixXd &foot_velocities,
146 Eigen::MatrixXd &foot_accelerations);
147
162 void loadFootPlanMsgs(
163 const std::vector<std::vector<bool>> &contact_schedule,
164 int current_plan_index, double first_element_duration,
165 const Eigen::MatrixXd &foot_positions,
166 const Eigen::MatrixXd &foot_velocities,
167 const Eigen::MatrixXd &foot_accelerations,
168 quad_msgs::MultiFootPlanDiscrete &future_footholds_msg,
169 quad_msgs::MultiFootPlanContinuous &foot_plan_continuous_msg);
170
171 inline void printContactSchedule(
172 const std::vector<std::vector<bool>> &contact_schedule) {
173 for (int i = 0; i < contact_schedule.size(); i++) {
174 for (int j = 0; j < contact_schedule.at(i).size(); j++) {
175 if (contact_schedule[i][j]) {
176 printf("1 ");
177 } else {
178 printf("0 ");
179 }
180 }
181 printf("\n");
182 }
183 }
184
185 inline double getTerrainHeight(double x, double y) {
186 grid_map::Position pos = {x, y};
187 double height = this->terrain_grid_.atPosition(
188 "z_smooth", terrain_grid_.getClosestPositionInMap(pos),
189 grid_map::InterpolationMethods::INTER_LINEAR);
190 return (height);
191 }
192
193 inline double getTerrainSlope(double x, double y, double dx, double dy) {
194 std::array<double, 3> surf_norm =
196
197 double denom = dx * dx + dy * dy;
198 if (denom <= 0 || surf_norm[2] <= 0) {
199 double default_pitch = 0;
200 return default_pitch;
201 } else {
202 double v_proj = (dx * surf_norm[0] + dy * surf_norm[1]) / sqrt(denom);
203 double pitch = atan2(v_proj, surf_norm[2]);
204
205 return pitch;
206 }
207 }
208
209 inline void getTerrainSlope(double x, double y, double yaw, double &roll,
210 double &pitch) {
211 std::array<double, 3> surf_norm =
213
214 Eigen::Vector3d norm_vec(surf_norm.data());
215 Eigen::Vector3d axis = Eigen::Vector3d::UnitZ().cross(norm_vec);
216 double ang = acos(
217 std::max(std::min(Eigen::Vector3d::UnitZ().dot(norm_vec), 1.), -1.));
218
219 if (ang < 1e-3) {
220 roll = 0;
221 pitch = 0;
222 return;
223 } else {
224 Eigen::Matrix3d rot(Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()));
225 axis = rot.transpose() * (axis / axis.norm());
226 tf2::Quaternion quat(tf2::Vector3(axis(0), axis(1), axis(2)), ang);
227 tf2::Matrix3x3 m(quat);
228 double tmp;
229 m.getRPY(roll, pitch, tmp);
230 }
231 }
232
233 inline void setTerrainMap(const grid_map::GridMap &grid_map) {
234 terrain_grid_ = grid_map;
235 }
236
237 // Compute future states by integrating linear states (hold orientation
238 // states)
239 inline Eigen::VectorXd computeFutureBodyPlan(
240 double step, const Eigen::VectorXd &body_plan) {
241 // Initialize vector
242 Eigen::VectorXd future_body_plan = body_plan;
243
244 // Integrate the linear state
245 future_body_plan.segment(0, 3) =
246 future_body_plan.segment(0, 3) + body_plan.segment(6, 3) * step * dt_;
247
248 return future_body_plan;
249 }
250
251 private:
256
269 void cubicHermiteSpline(double pos_prev, double vel_prev, double pos_next,
270 double vel_next, double phase, double duration,
271 double &pos, double &vel, double &acc);
272
279 Eigen::Vector3d getNearestValidFoothold(
280 const Eigen::Vector3d &foot_position,
281 const Eigen::Vector3d &foot_position_prev_solve) const;
282
289 Eigen::Vector3d welzlMinimumCircle(std::vector<Eigen::Vector2d> P,
290 std::vector<Eigen::Vector2d> R);
291
300 double computeSwingApex(int leg_idx, const Eigen::VectorXd &body_plan,
301 const Eigen::Vector3d &foot_position_prev,
302 const Eigen::Vector3d &foot_position_next);
303
307 inline Eigen::Vector3d getFootData(const Eigen::MatrixXd &foot_state_vars,
308 int horizon_index, int foot_index) {
309 return foot_state_vars.block<1, 3>(horizon_index, 3 * foot_index);
310 }
311
315 inline bool isContact(const std::vector<std::vector<bool>> &contact_schedule,
316 int horizon_index, int foot_index) {
317 return (contact_schedule.at(horizon_index).at(foot_index));
318 }
319
323 inline bool isNewContact(
324 const std::vector<std::vector<bool>> &contact_schedule, int horizon_index,
325 int foot_index) {
326 if (horizon_index == 0) return false;
327
328 return (!isContact(contact_schedule, horizon_index - 1, foot_index) &&
329 isContact(contact_schedule, horizon_index, foot_index));
330 }
331
335 inline bool isNewLiftoff(
336 const std::vector<std::vector<bool>> &contact_schedule, int horizon_index,
337 int foot_index) {
338 if (horizon_index == 0) return false;
339
340 return (isContact(contact_schedule, horizon_index - 1, foot_index) &&
341 !isContact(contact_schedule, horizon_index, foot_index));
342 }
343
349 const std::vector<std::vector<bool>> &contact_schedule, int horizon_index,
350 int foot_index) {
351 // Loop through the rest of this contact schedule, if a new contact is found
352 // return its index
353 for (int i_touchdown = horizon_index; i_touchdown < horizon_length_;
354 i_touchdown++) {
355 if (isNewContact(contact_schedule, i_touchdown, foot_index)) {
356 return i_touchdown;
357 }
358 }
359
360 // If no contact is found, return the last index in the horizon
361 return (horizon_length_ - 1);
362 }
363
369 const std::vector<std::vector<bool>> &contact_schedule, int horizon_index,
370 int foot_index) {
371 // Loop through the rest of this contact schedule, if a new liftoff is found
372 // return its index
373 for (int i_liftoff = horizon_index; i_liftoff < horizon_length_;
374 i_liftoff++) {
375 if (isNewLiftoff(contact_schedule, i_liftoff, foot_index)) {
376 return i_liftoff;
377 }
378 }
379
380 // If no contact is found, return the last index in the horizon
381 return (horizon_length_ - 1);
382 }
383
386
388 grid_map::GridMap terrain_grid_;
389
391 const int num_feet_ = 4;
392
394 double dt_;
395
398
401
403 std::vector<double> phase_offsets_ = {0, 0.5, 0.5, 0.0};
404
406 std::vector<double> duty_cycles_ = {0.5, 0.5, 0.5, 0.5};
407
409 std::vector<std::vector<bool>> nominal_contact_schedule_;
410
413
416
419
421 const int CONNECT_STANCE = 0;
422
424 const int LEAP_STANCE = 1;
425
427 const int FLIGHT = 2;
428
430 const int LAND_STANCE = 3;
431
433 std::shared_ptr<quad_utils::QuadKD> quadKD_;
434
437
440
443
445 std::string obj_fun_layer_;
446
449};
450
451#endif // LOCAL_FOOTSTEP_PLANNER_H
A terrain map class built for fast and efficient sampling.
Definition: fast_terrain_map.h:16
std::array< double, 3 > getSurfaceNormalFiltered(const double x, const double y) const
Return the filtered surface normal at a requested location.
Definition: fast_terrain_map.cpp:345
A local footstep planning class for quad.
Definition: local_footstep_planner.h:32
std::vector< double > phase_offsets_
Phase offsets for the touchdown of each foot.
Definition: local_footstep_planner.h:403
double foothold_obj_threshold_
Minimum objective function value for valid foothold.
Definition: local_footstep_planner.h:442
Eigen::Vector3d welzlMinimumCircle(std::vector< Eigen::Vector2d > P, std::vector< Eigen::Vector2d > R)
Compute minimum covering circle problem using Welzl's algorithm.
Definition: local_footstep_planner.cpp:624
void getFootPositionsBodyFrame(const Eigen::VectorXd &body_plan, const Eigen::VectorXd &foot_positions_world, Eigen::VectorXd &foot_positions_body)
Transform a vector of foot positions from the world to the body frame.
Definition: local_footstep_planner.cpp:63
const int LEAP_STANCE
Primitive ids - LEAP_STANCE.
Definition: local_footstep_planner.h:424
void setTemporalParams(double dt, int period, int horizon_length, const std::vector< double > &duty_cycles, const std::vector< double > &phase_offsets)
Set the temporal parameters of this object.
Definition: local_footstep_planner.cpp:9
LocalFootstepPlanner()
Constructor for LocalFootstepPlanner Class.
Definition: local_footstep_planner.cpp:7
double dt_
Timestep for one finite element.
Definition: local_footstep_planner.h:394
grid_map::GridMap terrain_grid_
GridMap for terrain map data.
Definition: local_footstep_planner.h:388
bool isContact(const std::vector< std::vector< bool > > &contact_schedule, int horizon_index, int foot_index)
Check if a foot is in contact at a given index.
Definition: local_footstep_planner.h:315
double grf_weight_
Weighting on the projection of the grf.
Definition: local_footstep_planner.h:418
int horizon_length_
Horizon length in timesteps.
Definition: local_footstep_planner.h:400
double computeSwingApex(int leg_idx, const Eigen::VectorXd &body_plan, const Eigen::Vector3d &foot_position_prev, const Eigen::Vector3d &foot_position_next)
Compute swing apex height.
Definition: local_footstep_planner.cpp:713
double standing_error_threshold_
Threshold of body error from desired goal to start stepping.
Definition: local_footstep_planner.h:436
const int FLIGHT
Primitive ids - FLIGHT.
Definition: local_footstep_planner.h:427
FastTerrainMap terrain_
Struct for terrain map data.
Definition: local_footstep_planner.h:385
int getNextLiftoffIndex(const std::vector< std::vector< bool > > &contact_schedule, int horizon_index, int foot_index)
Compute the index of the next liftoff for a foot. If none exist return the last.
Definition: local_footstep_planner.h:368
void computeFootPlan(int current_plan_index, const std::vector< std::vector< bool > > &contact_schedule, const Eigen::MatrixXd &body_plan, const Eigen::MatrixXd &grf_plan, const Eigen::MatrixXd &ref_body_plan, const Eigen::VectorXd &foot_positions_current, const Eigen::VectorXd &foot_velocities_current, double first_element_duration, quad_msgs::MultiFootState &past_footholds_msg, Eigen::MatrixXd &foot_positions, Eigen::MatrixXd &foot_velocities, Eigen::MatrixXd &foot_accelerations)
Update the discrete footstep plan with the current plan.
Definition: local_footstep_planner.cpp:167
double hip_clearance_
Hip clearance.
Definition: local_footstep_planner.h:415
void loadFootPlanMsgs(const std::vector< std::vector< bool > > &contact_schedule, int current_plan_index, double first_element_duration, const Eigen::MatrixXd &foot_positions, const Eigen::MatrixXd &foot_velocities, const Eigen::MatrixXd &foot_accelerations, quad_msgs::MultiFootPlanDiscrete &future_footholds_msg, quad_msgs::MultiFootPlanContinuous &foot_plan_continuous_msg)
Convert the foot positions and contact schedule into ros messages for the foot plan.
Definition: local_footstep_planner.cpp:517
std::vector< double > duty_cycles_
Duty cycles for the stance duration of each foot.
Definition: local_footstep_planner.h:406
Eigen::Vector3d getFootData(const Eigen::MatrixXd &foot_state_vars, int horizon_index, int foot_index)
Extract foot data from the matrix.
Definition: local_footstep_planner.h:307
double ground_clearance_
Ground clearance.
Definition: local_footstep_planner.h:412
bool isNewLiftoff(const std::vector< std::vector< bool > > &contact_schedule, int horizon_index, int foot_index)
Check if a foot is newly in swing at a given index.
Definition: local_footstep_planner.h:335
const int num_feet_
Number of feet.
Definition: local_footstep_planner.h:391
int period_
Gait period in timesteps.
Definition: local_footstep_planner.h:397
Eigen::Vector3d getNearestValidFoothold(const Eigen::Vector3d &foot_position, const Eigen::Vector3d &foot_position_prev_solve) const
Search locally around foothold for optimal location.
Definition: local_footstep_planner.cpp:571
const int LAND_STANCE
Primitive ids - LAND_STANCE.
Definition: local_footstep_planner.h:430
void setSpatialParams(double ground_clearance, double hip_clearance, double grf_weight, double standing_error_threshold, std::shared_ptr< quad_utils::QuadKD > kinematics, double foothold_search_radius, double foothold_obj_threshold, std::string obj_fun_layer, double toe_radius)
Set the spatial parameters of this object.
Definition: local_footstep_planner.cpp:38
void updateContinuousPlan()
Update the continuous foot plan to match the discrete.
void updateMap(const FastTerrainMap &terrain)
Update the map of this object.
Definition: local_footstep_planner.cpp:55
void computeContactSchedule(int current_plan_index, const Eigen::VectorXi &ref_primitive_plan_, int control_mode, std::vector< std::vector< bool > > &contact_schedule)
Compute the contact schedule based on the current phase.
Definition: local_footstep_planner.cpp:86
void cubicHermiteSpline(double pos_prev, double vel_prev, double pos_next, double vel_next, double phase, double duration, double &pos, double &vel, double &acc)
Compute the cubic hermite spline.
Definition: local_footstep_planner.cpp:128
bool isNewContact(const std::vector< std::vector< bool > > &contact_schedule, int horizon_index, int foot_index)
Check if a foot is newly in contact at a given index.
Definition: local_footstep_planner.h:323
std::vector< std::vector< bool > > nominal_contact_schedule_
Nominal contact schedule.
Definition: local_footstep_planner.h:409
std::shared_ptr< quad_utils::QuadKD > quadKD_
QuadKD class.
Definition: local_footstep_planner.h:433
double toe_radius_
Toe radius.
Definition: local_footstep_planner.h:448
int getNextContactIndex(const std::vector< std::vector< bool > > &contact_schedule, int horizon_index, int foot_index)
Compute the index of the next contact for a foot. If none exist return the last.
Definition: local_footstep_planner.h:348
const int CONNECT_STANCE
Primitive ids - CONNECT_STANCE TODO(yanhaoy, astutt) make these enums.
Definition: local_footstep_planner.h:421
double foothold_search_radius_
Radius to locally search for valid footholds (m)
Definition: local_footstep_planner.h:439
std::string obj_fun_layer_
Terrain layer for foothold search.
Definition: local_footstep_planner.h:445