#include <footstep_graph.h>
Definition at line 50 of file footstep_graph.h.
typedef boost::shared_ptr<FootstepGraph> jsk_footstep_planner::FootstepGraph::Ptr |
Reimplemented from jsk_footstep_planner::Graph< FootstepState >.
Definition at line 53 of file footstep_graph.h.
jsk_footstep_planner::FootstepGraph::FootstepGraph | ( | const Eigen::Vector3f & | resolution, |
const bool | use_pointcloud_model = false , |
||
const bool | lazy_projection = true , |
||
const bool | local_movement = false |
||
) | [inline] |
Definition at line 54 of file footstep_graph.h.
virtual FootstepState::Ptr jsk_footstep_planner::FootstepGraph::getGoal | ( | int | leg | ) | [inline, virtual] |
Definition at line 105 of file footstep_graph.h.
virtual TransitionLimit::Ptr jsk_footstep_planner::FootstepGraph::getTransitionLimit | ( | ) | [inline, virtual] |
Definition at line 171 of file footstep_graph.h.
std::string jsk_footstep_planner::FootstepGraph::infoString | ( | ) | const [virtual] |
return string about graph information.
Definition at line 87 of file footstep_graph.cpp.
bool jsk_footstep_planner::FootstepGraph::isGoal | ( | StatePtr | state | ) | [virtual] |
Implements jsk_footstep_planner::Graph< FootstepState >.
Definition at line 70 of file footstep_graph.cpp.
virtual bool jsk_footstep_planner::FootstepGraph::lazyProjection | ( | ) | const [inline, virtual] |
Definition at line 154 of file footstep_graph.h.
std::vector< FootstepState::Ptr > jsk_footstep_planner::FootstepGraph::localMoveFootstepState | ( | FootstepState::Ptr | in | ) | [virtual] |
Definition at line 119 of file footstep_graph.cpp.
virtual bool jsk_footstep_planner::FootstepGraph::localMovement | ( | ) | const [inline, virtual] |
Definition at line 155 of file footstep_graph.h.
virtual double jsk_footstep_planner::FootstepGraph::maxSuccessorDistance | ( | ) | [inline, virtual] |
Definition at line 118 of file footstep_graph.h.
virtual double jsk_footstep_planner::FootstepGraph::maxSuccessorRotation | ( | ) | [inline, virtual] |
Definition at line 122 of file footstep_graph.h.
FootstepState::Ptr jsk_footstep_planner::FootstepGraph::projectFootstep | ( | FootstepState::Ptr | in | ) | [virtual] |
Definition at line 201 of file footstep_graph.cpp.
FootstepState::Ptr jsk_footstep_planner::FootstepGraph::projectFootstep | ( | FootstepState::Ptr | in, |
unsigned int & | state | ||
) | [virtual] |
Definition at line 207 of file footstep_graph.cpp.
bool jsk_footstep_planner::FootstepGraph::projectGoal | ( | ) | [virtual] |
Definition at line 228 of file footstep_graph.cpp.
bool jsk_footstep_planner::FootstepGraph::projectStart | ( | ) | [virtual] |
Definition at line 243 of file footstep_graph.cpp.
void jsk_footstep_planner::FootstepGraph::setBasicSuccessors | ( | std::vector< Eigen::Affine3f > | left_to_right_successors | ) | [virtual] |
Definition at line 41 of file footstep_graph.cpp.
virtual void jsk_footstep_planner::FootstepGraph::setGoalState | ( | FootstepState::Ptr | left, |
FootstepState::Ptr | right | ||
) | [inline, virtual] |
Definition at line 82 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setLeftGoalState | ( | FootstepState::Ptr | goal | ) | [inline, virtual] |
Definition at line 89 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setLocalThetaMovement | ( | double | x | ) | [inline, virtual] |
Definition at line 160 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setLocalThetaMovementNum | ( | size_t | n | ) | [inline, virtual] |
Definition at line 163 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setLocalXMovement | ( | double | x | ) | [inline, virtual] |
Definition at line 158 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setLocalXMovementNum | ( | size_t | n | ) | [inline, virtual] |
Definition at line 161 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setLocalYMovement | ( | double | x | ) | [inline, virtual] |
Definition at line 159 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setLocalYMovementNum | ( | size_t | n | ) | [inline, virtual] |
Definition at line 162 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setPlaneEstimationMaxIterations | ( | int | n | ) | [inline, virtual] |
Definition at line 164 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setPlaneEstimationMinInliers | ( | int | n | ) | [inline, virtual] |
Definition at line 165 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setPlaneEstimationOutlierThreshold | ( | double | d | ) | [inline, virtual] |
Definition at line 166 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setPointCloudModel | ( | pcl::PointCloud< pcl::PointNormal >::Ptr | model | ) | [inline, virtual] |
Definition at line 133 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setPositionGoalThreshold | ( | double | x | ) | [inline, virtual] |
Definition at line 156 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setProgressPublisher | ( | ros::NodeHandle & | nh, |
std::string | topic | ||
) | [inline, virtual] |
Definition at line 127 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setRightGoalState | ( | FootstepState::Ptr | goal | ) | [inline, virtual] |
Definition at line 94 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setRotationGoalThreshold | ( | double | x | ) | [inline, virtual] |
Definition at line 157 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setSupportCheckVertexNeighborThreshold | ( | double | d | ) | [inline, virtual] |
Definition at line 169 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setSupportCheckXSampling | ( | int | n | ) | [inline, virtual] |
Definition at line 167 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setSupportCheckYSampling | ( | int | n | ) | [inline, virtual] |
Definition at line 168 of file footstep_graph.h.
virtual void jsk_footstep_planner::FootstepGraph::setTransitionLimit | ( | TransitionLimit::Ptr | limit | ) | [inline, virtual] |
Definition at line 170 of file footstep_graph.h.
std::vector< FootstepGraph::StatePtr > jsk_footstep_planner::FootstepGraph::successors | ( | StatePtr | target_state | ) | [virtual] |
Implements jsk_footstep_planner::Graph< FootstepState >.
Definition at line 143 of file footstep_graph.cpp.
virtual bool jsk_footstep_planner::FootstepGraph::usePointCloudModel | ( | ) | const [inline, virtual] |
Definition at line 153 of file footstep_graph.h.
Definition at line 182 of file footstep_graph.h.
const bool jsk_footstep_planner::FootstepGraph::lazy_projection_ [protected] |
Definition at line 193 of file footstep_graph.h.
Definition at line 185 of file footstep_graph.h.
double jsk_footstep_planner::FootstepGraph::local_move_theta_ [protected] |
Definition at line 198 of file footstep_graph.h.
size_t jsk_footstep_planner::FootstepGraph::local_move_theta_num_ [protected] |
Definition at line 201 of file footstep_graph.h.
double jsk_footstep_planner::FootstepGraph::local_move_x_ [protected] |
Definition at line 196 of file footstep_graph.h.
size_t jsk_footstep_planner::FootstepGraph::local_move_x_num_ [protected] |
Definition at line 199 of file footstep_graph.h.
double jsk_footstep_planner::FootstepGraph::local_move_y_ [protected] |
Definition at line 197 of file footstep_graph.h.
size_t jsk_footstep_planner::FootstepGraph::local_move_y_num_ [protected] |
Definition at line 200 of file footstep_graph.h.
const bool jsk_footstep_planner::FootstepGraph::local_movement_ [protected] |
Definition at line 194 of file footstep_graph.h.
double jsk_footstep_planner::FootstepGraph::max_successor_distance_ [protected] |
Definition at line 187 of file footstep_graph.h.
double jsk_footstep_planner::FootstepGraph::max_successor_rotation_ [protected] |
Definition at line 188 of file footstep_graph.h.
Definition at line 206 of file footstep_graph.h.
Definition at line 207 of file footstep_graph.h.
double jsk_footstep_planner::FootstepGraph::plane_estimation_outlier_threshold_ [protected] |
Definition at line 208 of file footstep_graph.h.
pcl::PointCloud<pcl::PointNormal>::Ptr jsk_footstep_planner::FootstepGraph::pointcloud_model_ [protected] |
Definition at line 177 of file footstep_graph.h.
pcl::PointCloud<pcl::PointNormal>::Ptr jsk_footstep_planner::FootstepGraph::pointcloud_model_2d_ [protected] |
Definition at line 178 of file footstep_graph.h.
double jsk_footstep_planner::FootstepGraph::pos_goal_thr_ [protected] |
Reimplemented from jsk_footstep_planner::Graph< FootstepState >.
Definition at line 189 of file footstep_graph.h.
Definition at line 203 of file footstep_graph.h.
bool jsk_footstep_planner::FootstepGraph::publish_progress_ [protected] |
Definition at line 191 of file footstep_graph.h.
const Eigen::Vector3f jsk_footstep_planner::FootstepGraph::resolution_ [protected] |
Definition at line 204 of file footstep_graph.h.
Definition at line 186 of file footstep_graph.h.
double jsk_footstep_planner::FootstepGraph::rot_goal_thr_ [protected] |
Reimplemented from jsk_footstep_planner::Graph< FootstepState >.
Definition at line 190 of file footstep_graph.h.
std::vector<Eigen::Affine3f> jsk_footstep_planner::FootstepGraph::successors_from_left_to_right_ [protected] |
Definition at line 183 of file footstep_graph.h.
std::vector<Eigen::Affine3f> jsk_footstep_planner::FootstepGraph::successors_from_right_to_left_ [protected] |
Definition at line 184 of file footstep_graph.h.
Definition at line 211 of file footstep_graph.h.
int jsk_footstep_planner::FootstepGraph::support_check_x_sampling_ [protected] |
Definition at line 209 of file footstep_graph.h.
int jsk_footstep_planner::FootstepGraph::support_check_y_sampling_ [protected] |
Definition at line 210 of file footstep_graph.h.
Definition at line 195 of file footstep_graph.h.
pcl::KdTreeFLANN<pcl::PointNormal>::Ptr jsk_footstep_planner::FootstepGraph::tree_model_ [protected] |
Definition at line 179 of file footstep_graph.h.
pcl::search::Octree<pcl::PointNormal>::Ptr jsk_footstep_planner::FootstepGraph::tree_model_2d_ [protected] |
Definition at line 181 of file footstep_graph.h.
const bool jsk_footstep_planner::FootstepGraph::use_pointcloud_model_ [protected] |
Definition at line 192 of file footstep_graph.h.