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< CostedGridState > | CostedGridGraph |
typedef GridMap< CostedGridState > | CostedGridMap |
typedef Eigen::AngleAxisd | FootstepAngleAxis |
typedef Eigen::Quaterniond | FootstepQuaternion |
typedef Eigen::Affine3d | FootstepTrans |
typedef Eigen::Translation3d | FootstepTranslation |
typedef Eigen::Vector3d | FootstepVec |
typedef GridGraph< OccupancyGridState > | OccupancyGridGraph |
typedef GridMap< OccupancyGridState > | OccupancyGridMap |
typedef GridGraph< CostedGridState > | PerceptionGridGraph |
typedef GridGraph< GridState > | SimpleGridGraph |
typedef GridMap< GridState > | SimpleGridMap |
Enumerations | |
enum | FootstepSupportState { NOT_SUPPORTED, SUPPORTED, CLOSE_TO_SUPPORTED } |
enum | GridPlanningStatus { NONE, OK, WARNING, ERROR } |
enum | PlanningStatus { OK, WARNING, ERROR } |
Definition at line 151 of file grid_graph.h.
Definition at line 147 of file grid_graph.h.
Definition at line 104 of file footstep_marker.h.
Definition at line 103 of file footstep_marker.h.
typedef Eigen::Affine3d jsk_footstep_planner::FootstepTrans |
Definition at line 100 of file footstep_marker.h.
Definition at line 102 of file footstep_marker.h.
Definition at line 101 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.
Enumerator | |
---|---|
NOT_SUPPORTED | |
SUPPORTED | |
CLOSE_TO_SUPPORTED |
Definition at line 105 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 96 of file footstep_planner.h.
void jsk_footstep_planner::add3Dof2DControl | ( | visualization_msgs::InteractiveMarker & | msg, |
bool | fixed | ||
) |
Definition at line 72 of file footstep_marker.cpp.
|
inline |
visualization_msgs::MarkerArray jsk_footstep_planner::footstepArrayToMarkerArray | ( | const jsk_footstep_msgs::FootstepArray & | footstep_array | ) |
Definition at line 104 of file footstep_conversions.cpp.
jsk_footstep_msgs::Footstep jsk_footstep_planner::footstepFromEigenPose | ( | Eigen::Affine3d | pose | ) |
Definition at line 79 of file footstep_conversions.cpp.
jsk_footstep_msgs::Footstep jsk_footstep_planner::footstepFromEigenPose | ( | Eigen::Affine3f | pose | ) |
Definition at line 73 of file footstep_conversions.cpp.
double jsk_footstep_planner::footstepHeuristicFollowPathLine | ( | SolverNode< FootstepState, FootstepGraph >::Ptr | node, |
FootstepGraph::Ptr | graph | ||
) |
Definition at line 488 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 449 of file footstep_graph.cpp.
double jsk_footstep_planner::footstepHeuristicStraight | ( | SolverNode< FootstepState, FootstepGraph >::Ptr | node, |
FootstepGraph::Ptr | graph | ||
) |
Definition at line 427 of file footstep_graph.cpp.
double jsk_footstep_planner::footstepHeuristicStraightRotation | ( | SolverNode< FootstepState, FootstepGraph >::Ptr | node, |
FootstepGraph::Ptr | graph | ||
) |
Definition at line 438 of file footstep_graph.cpp.
double jsk_footstep_planner::footstepHeuristicZero | ( | SolverNode< FootstepState, FootstepGraph >::Ptr | node, |
FootstepGraph::Ptr | graph | ||
) |
Definition at line 420 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 86 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.
|
inline |
Definition at line 286 of file footstep_state.h.
|
inline |
Definition at line 87 of file grid_state.h.
std::string jsk_footstep_planner::projectStateToString | ( | unsigned int | state | ) |
Definition at line 59 of file footstep_state.cpp.