Public Types | Public Member Functions | Protected Attributes
jsk_footstep_planner::FootstepGraph Class Reference

#include <footstep_graph.h>

Inheritance diagram for jsk_footstep_planner::FootstepGraph:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< FootstepGraph
Ptr

Public Member Functions

 FootstepGraph (const Eigen::Vector3f &resolution, const bool use_pointcloud_model=false, const bool lazy_projection=true, const bool local_movement=false)
virtual FootstepState::Ptr getGoal (int leg)
virtual TransitionLimit::Ptr getTransitionLimit ()
virtual std::string infoString () const
 return string about graph information.
virtual bool isGoal (StatePtr state)
virtual bool lazyProjection () const
virtual std::vector
< FootstepState::Ptr
localMoveFootstepState (FootstepState::Ptr in)
virtual bool localMovement () const
virtual double maxSuccessorDistance ()
virtual double maxSuccessorRotation ()
virtual FootstepState::Ptr projectFootstep (FootstepState::Ptr in)
virtual FootstepState::Ptr projectFootstep (FootstepState::Ptr in, unsigned int &state)
virtual bool projectGoal ()
virtual bool projectStart ()
virtual void setBasicSuccessors (std::vector< Eigen::Affine3f > left_to_right_successors)
virtual void setGoalState (FootstepState::Ptr left, FootstepState::Ptr right)
virtual void setLeftGoalState (FootstepState::Ptr goal)
virtual void setLocalThetaMovement (double x)
virtual void setLocalThetaMovementNum (size_t n)
virtual void setLocalXMovement (double x)
virtual void setLocalXMovementNum (size_t n)
virtual void setLocalYMovement (double x)
virtual void setLocalYMovementNum (size_t n)
virtual void setPlaneEstimationMaxIterations (int n)
virtual void setPlaneEstimationMinInliers (int n)
virtual void setPlaneEstimationOutlierThreshold (double d)
virtual void setPointCloudModel (pcl::PointCloud< pcl::PointNormal >::Ptr model)
virtual void setPositionGoalThreshold (double x)
virtual void setProgressPublisher (ros::NodeHandle &nh, std::string topic)
virtual void setRightGoalState (FootstepState::Ptr goal)
virtual void setRotationGoalThreshold (double x)
virtual void setSupportCheckVertexNeighborThreshold (double d)
virtual void setSupportCheckXSampling (int n)
virtual void setSupportCheckYSampling (int n)
virtual void setTransitionLimit (TransitionLimit::Ptr limit)
virtual std::vector< StatePtrsuccessors (StatePtr target_state)
virtual bool usePointCloudModel () const

Protected Attributes

ANNGrid::Ptr grid_search_
const bool lazy_projection_
FootstepState::Ptr left_goal_state_
double local_move_theta_
size_t local_move_theta_num_
double local_move_x_
size_t local_move_x_num_
double local_move_y_
size_t local_move_y_num_
const bool local_movement_
double max_successor_distance_
double max_successor_rotation_
int plane_estimation_max_iterations_
int plane_estimation_min_inliers_
double plane_estimation_outlier_threshold_
pcl::PointCloud
< pcl::PointNormal >::Ptr 
pointcloud_model_
pcl::PointCloud
< pcl::PointNormal >::Ptr 
pointcloud_model_2d_
double pos_goal_thr_
ros::Publisher pub_progress_
bool publish_progress_
const Eigen::Vector3f resolution_
FootstepState::Ptr right_goal_state_
double rot_goal_thr_
std::vector< Eigen::Affine3f > successors_from_left_to_right_
std::vector< Eigen::Affine3f > successors_from_right_to_left_
double support_check_vertex_neighbor_threshold_
int support_check_x_sampling_
int support_check_y_sampling_
TransitionLimit::Ptr transition_limit_
pcl::KdTreeFLANN
< pcl::PointNormal >::Ptr 
tree_model_
pcl::search::Octree
< pcl::PointNormal >::Ptr 
tree_model_2d_
const bool use_pointcloud_model_

Detailed Description

Definition at line 50 of file footstep_graph.h.


Member Typedef Documentation

Reimplemented from jsk_footstep_planner::Graph< FootstepState >.

Definition at line 53 of file footstep_graph.h.


Constructor & Destructor Documentation

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.


Member Function Documentation

virtual FootstepState::Ptr jsk_footstep_planner::FootstepGraph::getGoal ( int  leg) [inline, virtual]

Definition at line 105 of file footstep_graph.h.

Definition at line 171 of file footstep_graph.h.

return string about graph information.

Definition at line 87 of file footstep_graph.cpp.

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.

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.

Definition at line 201 of file footstep_graph.cpp.

Definition at line 207 of file footstep_graph.cpp.

Definition at line 228 of file footstep_graph.cpp.

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.

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.

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.

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.

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.

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.

Definition at line 170 of file footstep_graph.h.

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.


Member Data Documentation

Definition at line 182 of file footstep_graph.h.

Definition at line 193 of file footstep_graph.h.

Definition at line 185 of file footstep_graph.h.

Definition at line 198 of file footstep_graph.h.

Definition at line 201 of file footstep_graph.h.

Definition at line 196 of file footstep_graph.h.

Definition at line 199 of file footstep_graph.h.

Definition at line 197 of file footstep_graph.h.

Definition at line 200 of file footstep_graph.h.

Definition at line 194 of file footstep_graph.h.

Definition at line 187 of file footstep_graph.h.

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.

Definition at line 208 of file footstep_graph.h.

Definition at line 177 of file footstep_graph.h.

Definition at line 178 of file footstep_graph.h.

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.

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.

Reimplemented from jsk_footstep_planner::Graph< FootstepState >.

Definition at line 190 of file footstep_graph.h.

Definition at line 183 of file footstep_graph.h.

Definition at line 184 of file footstep_graph.h.

Definition at line 211 of file footstep_graph.h.

Definition at line 209 of file footstep_graph.h.

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.

Definition at line 192 of file footstep_graph.h.


The documentation for this class was generated from the following files:


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:37:57