Namespaces | Classes | Typedefs | Enumerations | Functions
jsk_footstep_planner Namespace Reference

Namespaces

 projection_state
 

Classes

class  ANNGrid
 ANNGrid is a class to provide approximate near neighbors search based on 2.5-D representation. All the z values of pointcloud is ignored and it sorted as 2-D array. More...
 
class  ANNGridCell
 
class  AStarSolver
 
class  BestFirstSearchSolver
 
class  BreadthFirstSearchSolver
 
class  CostedGridState
 
class  DepthFirstSearchSolver
 
class  FootstepAStarSolver
 
class  FootstepGraph
 
class  FootstepMarker
 
struct  FootstepParameters
 
class  FootstepPlanner
 Actionlib server for footstep planning. More...
 
class  FootstepState
 
class  FootstepStateDiscreteCloseList
 FootstepStateDiscreteCloseList is a special clas to use for close list of FootstepState. More...
 
class  FootstepStateDiscreteCloseListLocal
 
class  Graph
 
class  GridAStarSolver
 
class  GridGraph
 
class  GridMap
 
class  GridPathPlanner
 Actionlib server for footstep planning. More...
 
class  GridState
 
class  Line2D
 
class  MarkerArrayPublisher
 
class  Node
 
class  OccupancyGridState
 
class  PerceptionGridMap
 
class  PointCloudModelGenerator
 just a pointcloud generator for sample usage More...
 
class  PosePair
 
class  SimpleNeighboredGraph
 
class  SimpleNeighboredNode
 
class  Solver
 
class  SolverNode
 
class  TransitionLimit
 virtual class to provide limit of transition of footstep. More...
 
class  TransitionLimitRP
 Class to provide limit of transition of footstep about Roll and Pitch. This class is designed for global soundness of footstep. More...
 
class  TransitionLimitXYZRPY
 class to provide limit of transition of footstep with 6 Full parameters. More...
 
class  UnknownPoseName
 

Typedefs

typedef GridGraph< CostedGridStateCostedGridGraph
 
typedef GridMap< CostedGridStateCostedGridMap
 
typedef Eigen::AngleAxisd FootstepAngleAxis
 
typedef Eigen::Quaterniond FootstepQuaternion
 
typedef Eigen::Affine3d FootstepTrans
 
typedef Eigen::Translation3d FootstepTranslation
 
typedef Eigen::Vector3d FootstepVec
 
typedef GridGraph< OccupancyGridStateOccupancyGridGraph
 
typedef GridMap< OccupancyGridStateOccupancyGridMap
 
typedef GridGraph< CostedGridStatePerceptionGridGraph
 
typedef GridGraph< GridStateSimpleGridGraph
 
typedef GridMap< GridStateSimpleGridMap
 

Enumerations

enum  FootstepSupportState { NOT_SUPPORTED, SUPPORTED, CLOSE_TO_SUPPORTED }
 
enum  GridPlanningStatus { NONE, OK, WARNING, ERROR }
 
enum  PlanningStatus { OK, WARNING, ERROR }
 

Functions

void add3Dof2DControl (visualization_msgs::InteractiveMarker &msg, bool fixed)
 
Eigen::Affine3f affineFromXYYaw (double x, double y, double yaw)
 
visualization_msgs::MarkerArray footstepArrayToMarkerArray (const jsk_footstep_msgs::FootstepArray &footstep_array)
 
jsk_footstep_msgs::Footstep footstepFromEigenPose (Eigen::Affine3f pose)
 
jsk_footstep_msgs::Footstep footstepFromEigenPose (Eigen::Affine3d pose)
 
double footstepHeuristicFollowPathLine (SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph)
 
double footstepHeuristicStepCost (SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph, double first_rotation_weight, double second_rotation_weight)
 
double footstepHeuristicStraight (SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph)
 
double footstepHeuristicStraightRotation (SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph)
 
double footstepHeuristicZero (SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph)
 
visualization_msgs::Marker footstepToMarker (const jsk_footstep_msgs::Footstep &footstep, const std_msgs::Header &header)
 
double gridPerceptionHeuristicDistance (SolverNode< PerceptionGridGraph::State, PerceptionGridGraph >::Ptr node, PerceptionGridGraph::Ptr graph)
 
size_t hash_value (const GridState::Ptr &s)
 
size_t hash_value (const FootstepState::Ptr &s)
 
std::string projectStateToString (unsigned int state)
 

Typedef Documentation

Definition at line 151 of file grid_graph.h.

Definition at line 147 of file grid_graph.h.

typedef Eigen::AngleAxisd jsk_footstep_planner::FootstepAngleAxis

Definition at line 72 of file footstep_marker.h.

typedef Eigen::Quaterniond jsk_footstep_planner::FootstepQuaternion

Definition at line 71 of file footstep_marker.h.

typedef Eigen::Affine3d jsk_footstep_planner::FootstepTrans

Definition at line 68 of file footstep_marker.h.

typedef Eigen::Translation3d jsk_footstep_planner::FootstepTranslation

Definition at line 70 of file footstep_marker.h.

typedef Eigen::Vector3d jsk_footstep_planner::FootstepVec

Definition at line 69 of file footstep_marker.h.

Definition at line 150 of file grid_graph.h.

Definition at line 146 of file grid_graph.h.

Definition at line 103 of file grid_perception.h.

Definition at line 149 of file grid_graph.h.

Definition at line 145 of file grid_graph.h.

Enumeration Type Documentation

Enumerator
NOT_SUPPORTED 
SUPPORTED 
CLOSE_TO_SUPPORTED 

Definition at line 73 of file footstep_state.h.

Enumerator
NONE 
OK 
WARNING 
ERROR 

Definition at line 26 of file grid_path_planner.h.

Enumerator
OK 
WARNING 
ERROR 

Definition at line 64 of file footstep_planner.h.

Function Documentation

void jsk_footstep_planner::add3Dof2DControl ( visualization_msgs::InteractiveMarker &  msg,
bool  fixed 
)

Definition at line 72 of file footstep_marker.cpp.

Eigen::Affine3f jsk_footstep_planner::affineFromXYYaw ( double  x,
double  y,
double  yaw 
)
inline

Definition at line 42 of file util.h.

visualization_msgs::MarkerArray jsk_footstep_planner::footstepArrayToMarkerArray ( const jsk_footstep_msgs::FootstepArray &  footstep_array)

Definition at line 72 of file footstep_conversions.cpp.

jsk_footstep_msgs::Footstep jsk_footstep_planner::footstepFromEigenPose ( Eigen::Affine3f  pose)

Definition at line 41 of file footstep_conversions.cpp.

jsk_footstep_msgs::Footstep jsk_footstep_planner::footstepFromEigenPose ( Eigen::Affine3d  pose)

Definition at line 47 of file footstep_conversions.cpp.

double jsk_footstep_planner::footstepHeuristicFollowPathLine ( SolverNode< FootstepState, FootstepGraph >::Ptr  node,
FootstepGraph::Ptr  graph 
)

Definition at line 456 of file footstep_graph.cpp.

double jsk_footstep_planner::footstepHeuristicStepCost ( SolverNode< FootstepState, FootstepGraph >::Ptr  node,
FootstepGraph::Ptr  graph,
double  first_rotation_weight,
double  second_rotation_weight 
)

Definition at line 417 of file footstep_graph.cpp.

double jsk_footstep_planner::footstepHeuristicStraight ( SolverNode< FootstepState, FootstepGraph >::Ptr  node,
FootstepGraph::Ptr  graph 
)

Definition at line 395 of file footstep_graph.cpp.

double jsk_footstep_planner::footstepHeuristicStraightRotation ( SolverNode< FootstepState, FootstepGraph >::Ptr  node,
FootstepGraph::Ptr  graph 
)

Definition at line 406 of file footstep_graph.cpp.

double jsk_footstep_planner::footstepHeuristicZero ( SolverNode< FootstepState, FootstepGraph >::Ptr  node,
FootstepGraph::Ptr  graph 
)

Definition at line 388 of file footstep_graph.cpp.

visualization_msgs::Marker jsk_footstep_planner::footstepToMarker ( const jsk_footstep_msgs::Footstep &  footstep,
const std_msgs::Header header 
)

Definition at line 54 of file footstep_conversions.cpp.

double jsk_footstep_planner::gridPerceptionHeuristicDistance ( SolverNode< PerceptionGridGraph::State, PerceptionGridGraph >::Ptr  node,
PerceptionGridGraph::Ptr  graph 
)

Definition at line 106 of file grid_perception.h.

size_t jsk_footstep_planner::hash_value ( const GridState::Ptr s)
inline

Definition at line 87 of file grid_state.h.

size_t jsk_footstep_planner::hash_value ( const FootstepState::Ptr s)
inline

Definition at line 254 of file footstep_state.h.

std::string jsk_footstep_planner::projectStateToString ( unsigned int  state)

Definition at line 59 of file footstep_state.cpp.



jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Fri May 14 2021 02:51:52