|
| LocalFootstepPlanner () |
| Constructor for LocalFootstepPlanner Class. More...
|
|
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. More...
|
|
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. More...
|
|
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. More...
|
|
void | getFootPositionsBodyFrame (const Eigen::MatrixXd &body_plan, const Eigen::MatrixXd &foot_positions_world, Eigen::MatrixXd &foot_positions_body) |
| Transform the entire foot plan from the world to the body frame. More...
|
|
void | updateMap (const FastTerrainMap &terrain) |
| Update the map of this object. More...
|
|
void | updateMap (const grid_map::GridMap &terrain) |
| Update the map of this object. More...
|
|
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. More...
|
|
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. More...
|
|
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. More...
|
|
void | printContactSchedule (const std::vector< std::vector< bool > > &contact_schedule) |
|
double | getTerrainHeight (double x, double y) |
|
double | getTerrainSlope (double x, double y, double dx, double dy) |
|
void | getTerrainSlope (double x, double y, double yaw, double &roll, double &pitch) |
|
void | setTerrainMap (const grid_map::GridMap &grid_map) |
|
Eigen::VectorXd | computeFutureBodyPlan (double step, const Eigen::VectorXd &body_plan) |
|
|
void | updateContinuousPlan () |
| Update the continuous foot plan to match the discrete.
|
|
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. More...
|
|
Eigen::Vector3d | getNearestValidFoothold (const Eigen::Vector3d &foot_position, const Eigen::Vector3d &foot_position_prev_solve) const |
| Search locally around foothold for optimal location. More...
|
|
Eigen::Vector3d | welzlMinimumCircle (std::vector< Eigen::Vector2d > P, std::vector< Eigen::Vector2d > R) |
| Compute minimum covering circle problem using Welzl's algorithm. More...
|
|
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. More...
|
|
Eigen::Vector3d | getFootData (const Eigen::MatrixXd &foot_state_vars, int horizon_index, int foot_index) |
| Extract foot data from the matrix.
|
|
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.
|
|
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.
|
|
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.
|
|
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.
|
|
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.
|
|
|
FastTerrainMap | terrain_ |
| Struct for terrain map data.
|
|
grid_map::GridMap | terrain_grid_ |
| GridMap for terrain map data.
|
|
const int | num_feet_ = 4 |
| Number of feet.
|
|
double | dt_ |
| Timestep for one finite element.
|
|
int | period_ |
| Gait period in timesteps.
|
|
int | horizon_length_ |
| Horizon length in timesteps.
|
|
std::vector< double > | phase_offsets_ = {0, 0.5, 0.5, 0.0} |
| Phase offsets for the touchdown of each foot.
|
|
std::vector< double > | duty_cycles_ = {0.5, 0.5, 0.5, 0.5} |
| Duty cycles for the stance duration of each foot.
|
|
std::vector< std::vector< bool > > | nominal_contact_schedule_ |
| Nominal contact schedule.
|
|
double | ground_clearance_ |
| Ground clearance.
|
|
double | hip_clearance_ |
| Hip clearance.
|
|
double | grf_weight_ |
| Weighting on the projection of the grf.
|
|
const int | CONNECT_STANCE = 0 |
| Primitive ids - CONNECT_STANCE TODO(yanhaoy, astutt) make these enums.
|
|
const int | LEAP_STANCE = 1 |
| Primitive ids - LEAP_STANCE.
|
|
const int | FLIGHT = 2 |
| Primitive ids - FLIGHT.
|
|
const int | LAND_STANCE = 3 |
| Primitive ids - LAND_STANCE.
|
|
std::shared_ptr< quad_utils::QuadKD > | quadKD_ |
| QuadKD class.
|
|
double | standing_error_threshold_ = 0 |
| Threshold of body error from desired goal to start stepping.
|
|
double | foothold_search_radius_ |
| Radius to locally search for valid footholds (m)
|
|
double | foothold_obj_threshold_ |
| Minimum objective function value for valid foothold.
|
|
std::string | obj_fun_layer_ |
| Terrain layer for foothold search.
|
|
double | toe_radius_ |
| Toe radius.
|
|
A local footstep planning class for quad.
FootstepPlanner is a container for all of the logic utilized in the local footstep planning node. The implementation must provide a clean and high level interface to the core algorithm