1#ifndef LOCAL_FOOTSTEP_PLANNER_H
2#define LOCAL_FOOTSTEP_PLANNER_H
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>
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>
48 const std::vector<double> &duty_cycles,
49 const std::vector<double> &phase_offsets);
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);
81 const Eigen::VectorXd &foot_positions_world,
82 Eigen::VectorXd &foot_positions_body);
91 const Eigen::MatrixXd &foot_positions_world,
92 Eigen::MatrixXd &foot_positions_body);
104 void updateMap(
const grid_map::GridMap &terrain);
114 const Eigen::VectorXi &ref_primitive_plan_,
116 std::vector<std::vector<bool>> &contact_schedule);
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);
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);
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]) {
185 inline double getTerrainHeight(
double x,
double y) {
186 grid_map::Position pos = {x, y};
189 grid_map::InterpolationMethods::INTER_LINEAR);
193 inline double getTerrainSlope(
double x,
double y,
double dx,
double dy) {
194 std::array<double, 3> surf_norm =
197 double denom = dx * dx + dy * dy;
198 if (denom <= 0 || surf_norm[2] <= 0) {
199 double default_pitch = 0;
200 return default_pitch;
202 double v_proj = (dx * surf_norm[0] + dy * surf_norm[1]) / sqrt(denom);
203 double pitch = atan2(v_proj, surf_norm[2]);
209 inline void getTerrainSlope(
double x,
double y,
double yaw,
double &roll,
211 std::array<double, 3> surf_norm =
214 Eigen::Vector3d norm_vec(surf_norm.data());
215 Eigen::Vector3d axis = Eigen::Vector3d::UnitZ().cross(norm_vec);
217 std::max(std::min(Eigen::Vector3d::UnitZ().dot(norm_vec), 1.), -1.));
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);
229 m.getRPY(roll, pitch, tmp);
233 inline void setTerrainMap(
const grid_map::GridMap &grid_map) {
239 inline Eigen::VectorXd computeFutureBodyPlan(
240 double step,
const Eigen::VectorXd &body_plan) {
242 Eigen::VectorXd future_body_plan = body_plan;
245 future_body_plan.segment(0, 3) =
246 future_body_plan.segment(0, 3) + body_plan.segment(6, 3) * step *
dt_;
248 return future_body_plan;
270 double vel_next,
double phase,
double duration,
271 double &pos,
double &vel,
double &acc);
280 const Eigen::Vector3d &foot_position,
281 const Eigen::Vector3d &foot_position_prev_solve)
const;
290 std::vector<Eigen::Vector2d> R);
301 const Eigen::Vector3d &foot_position_prev,
302 const Eigen::Vector3d &foot_position_next);
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);
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));
324 const std::vector<std::vector<bool>> &contact_schedule,
int horizon_index,
326 if (horizon_index == 0)
return false;
328 return (!
isContact(contact_schedule, horizon_index - 1, foot_index) &&
329 isContact(contact_schedule, horizon_index, foot_index));
336 const std::vector<std::vector<bool>> &contact_schedule,
int horizon_index,
338 if (horizon_index == 0)
return false;
340 return (
isContact(contact_schedule, horizon_index - 1, foot_index) &&
341 !
isContact(contact_schedule, horizon_index, foot_index));
349 const std::vector<std::vector<bool>> &contact_schedule,
int horizon_index,
355 if (
isNewContact(contact_schedule, i_touchdown, foot_index)) {
369 const std::vector<std::vector<bool>> &contact_schedule,
int horizon_index,
375 if (
isNewLiftoff(contact_schedule, i_liftoff, foot_index)) {
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