Actionlib server for footstep planning.  
 More...
#include <footstep_planner.h>
|  | 
| virtual void | buildGraph () | 
|  | 
| virtual bool | collisionBoundingBoxInfoService (jsk_footstep_planner::CollisionBoundingBoxInfo::Request &req, jsk_footstep_planner::CollisionBoundingBoxInfo::Response &res) | 
|  | 
| virtual void | configCallback (Config &config, uint32_t level) | 
|  | 
| virtual double | followPathLineHeuristic (SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph) | 
|  | 
| virtual void | obstacleCallback (const sensor_msgs::PointCloud2::ConstPtr &msg) | 
|  | 
| virtual void | planCB (const jsk_footstep_msgs::PlanFootstepsGoal::ConstPtr &goal) | 
|  | 
| virtual void | pointcloudCallback (const sensor_msgs::PointCloud2::ConstPtr &msg) | 
|  | 
| virtual void | profile (FootstepAStarSolver< FootstepGraph > &solver, FootstepGraph::Ptr graph) | 
|  | 
| virtual bool | projectFootPrint (const Eigen::Affine3f ¢er_pose, const Eigen::Affine3f &left_pose_trans, const Eigen::Affine3f &right_pose_trans, geometry_msgs::Pose &pose) | 
|  | 
| virtual bool | projectFootPrintService (jsk_interactive_marker::SnapFootPrint::Request &req, jsk_interactive_marker::SnapFootPrint::Response &res) | 
|  | 
| virtual bool | projectFootPrintWithLocalSearchService (jsk_interactive_marker::SnapFootPrint::Request &req, jsk_interactive_marker::SnapFootPrint::Response &res) | 
|  | 
| virtual bool | projectFootstepService (jsk_footstep_planner::ProjectFootstep::Request &req, jsk_footstep_planner::ProjectFootstep::Response &res) | 
|  | 
| virtual void | publishPointCloud (const pcl::PointCloud< pcl::PointNormal > &cloud, ros::Publisher &pub, const std_msgs::Header &header) | 
|  | 
| virtual void | publishText (ros::Publisher &pub, const std::string &text, PlanningStatus status) | 
|  | 
| virtual bool | readSuccessors (ros::NodeHandle &nh) | 
|  | 
| virtual bool | setHeuristicPathService (jsk_footstep_planner::SetHeuristicPath::Request &req, jsk_footstep_planner::SetHeuristicPath::Response &res) | 
|  | 
| virtual double | stepCostHeuristic (SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph) | 
|  | 
| virtual double | straightHeuristic (SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph) | 
|  | 
| virtual double | straightRotationHeuristic (SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph) | 
|  | 
| virtual double | zeroHeuristic (SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph) | 
|  | 
Actionlib server for footstep planning. 
Definition at line 104 of file footstep_planner.h.
◆ Config
◆ Ptr
◆ FootstepPlanner()
      
        
          | jsk_footstep_planner::FootstepPlanner::FootstepPlanner | ( | ros::NodeHandle & | nh | ) |  | 
      
 
 
◆ buildGraph()
  
  | 
        
          | void jsk_footstep_planner::FootstepPlanner::buildGraph | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ collisionBoundingBoxInfoService()
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::collisionBoundingBoxInfoService | ( | jsk_footstep_planner::CollisionBoundingBoxInfo::Request & | req, |  
          |  |  | jsk_footstep_planner::CollisionBoundingBoxInfo::Response & | res |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ configCallback()
  
  | 
        
          | void jsk_footstep_planner::FootstepPlanner::configCallback | ( | Config & | config, |  
          |  |  | uint32_t | level |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ followPathLineHeuristic()
◆ obstacleCallback()
  
  | 
        
          | void jsk_footstep_planner::FootstepPlanner::obstacleCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) |  |  | protectedvirtual | 
 
 
◆ planCB()
  
  | 
        
          | void jsk_footstep_planner::FootstepPlanner::planCB | ( | const jsk_footstep_msgs::PlanFootstepsGoal::ConstPtr & | goal | ) |  |  | protectedvirtual | 
 
 
◆ pointcloudCallback()
  
  | 
        
          | void jsk_footstep_planner::FootstepPlanner::pointcloudCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) |  |  | protectedvirtual | 
 
 
◆ profile()
◆ projectFootPrint()
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::projectFootPrint | ( | const Eigen::Affine3f & | center_pose, |  
          |  |  | const Eigen::Affine3f & | left_pose_trans, |  
          |  |  | const Eigen::Affine3f & | right_pose_trans, |  
          |  |  | geometry_msgs::Pose & | pose |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ projectFootPrintService()
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::projectFootPrintService | ( | jsk_interactive_marker::SnapFootPrint::Request & | req, |  
          |  |  | jsk_interactive_marker::SnapFootPrint::Response & | res |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ projectFootPrintWithLocalSearchService()
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::projectFootPrintWithLocalSearchService | ( | jsk_interactive_marker::SnapFootPrint::Request & | req, |  
          |  |  | jsk_interactive_marker::SnapFootPrint::Response & | res |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ projectFootstepService()
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::projectFootstepService | ( | jsk_footstep_planner::ProjectFootstep::Request & | req, |  
          |  |  | jsk_footstep_planner::ProjectFootstep::Response & | res |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ publishPointCloud()
◆ publishText()
◆ readSuccessors()
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::readSuccessors | ( | ros::NodeHandle & | nh | ) |  |  | protectedvirtual | 
 
format is successors:
- x: 0 y: 0 theta: 0
- x: 0 y: 0 theta: 0 ... 
Definition at line 828 of file footstep_planner.cpp.
 
 
◆ setHeuristicPathLine()
◆ setHeuristicPathService()
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::setHeuristicPathService | ( | jsk_footstep_planner::SetHeuristicPath::Request & | req, |  
          |  |  | jsk_footstep_planner::SetHeuristicPath::Response & | res |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ stepCostHeuristic()
◆ straightHeuristic()
◆ straightRotationHeuristic()
◆ zeroHeuristic()
◆ as_
◆ close_list_theta_num_
  
  | 
        
          | int jsk_footstep_planner::FootstepPlanner::close_list_theta_num_ |  | protected | 
 
 
◆ close_list_x_num_
  
  | 
        
          | int jsk_footstep_planner::FootstepPlanner::close_list_x_num_ |  | protected | 
 
 
◆ close_list_y_num_
  
  | 
        
          | int jsk_footstep_planner::FootstepPlanner::close_list_y_num_ |  | protected | 
 
 
◆ collision_bbox_offset_
  
  | 
        
          | Eigen::Affine3f jsk_footstep_planner::FootstepPlanner::collision_bbox_offset_ |  | protected | 
 
 
◆ collision_bbox_size_
  
  | 
        
          | Eigen::Vector3f jsk_footstep_planner::FootstepPlanner::collision_bbox_size_ |  | protected | 
 
 
◆ cost_weight_
  
  | 
        
          | double jsk_footstep_planner::FootstepPlanner::cost_weight_ |  | protected | 
 
 
◆ footstep_size_x_
  
  | 
        
          | double jsk_footstep_planner::FootstepPlanner::footstep_size_x_ |  | protected | 
 
 
◆ footstep_size_y_
  
  | 
        
          | double jsk_footstep_planner::FootstepPlanner::footstep_size_y_ |  | protected | 
 
 
◆ graph_
◆ heuristic_
  
  | 
        
          | std::string jsk_footstep_planner::FootstepPlanner::heuristic_ |  | protected | 
 
 
◆ heuristic_first_rotation_weight_
  
  | 
        
          | double jsk_footstep_planner::FootstepPlanner::heuristic_first_rotation_weight_ |  | protected | 
 
 
◆ heuristic_second_rotation_weight_
  
  | 
        
          | double jsk_footstep_planner::FootstepPlanner::heuristic_second_rotation_weight_ |  | protected | 
 
 
◆ heuristic_weight_
  
  | 
        
          | double jsk_footstep_planner::FootstepPlanner::heuristic_weight_ |  | protected | 
 
 
◆ inv_lleg_footstep_offset_
  
  | 
        
          | Eigen::Vector3f jsk_footstep_planner::FootstepPlanner::inv_lleg_footstep_offset_ |  | protected | 
 
 
◆ inv_rleg_footstep_offset_
  
  | 
        
          | Eigen::Vector3f jsk_footstep_planner::FootstepPlanner::inv_rleg_footstep_offset_ |  | protected | 
 
 
◆ latest_header_
◆ mutex_
◆ num_finalize_steps_
  
  | 
        
          | size_t jsk_footstep_planner::FootstepPlanner::num_finalize_steps_ |  | protected | 
 
 
◆ obstacle_model_
  
  | 
        
          | pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_footstep_planner::FootstepPlanner::obstacle_model_ |  | protected | 
 
 
◆ obstacle_model_frame_id_
  
  | 
        
          | std::string jsk_footstep_planner::FootstepPlanner::obstacle_model_frame_id_ |  | protected | 
 
 
◆ parameters_
◆ planning_timeout_
  
  | 
        
          | double jsk_footstep_planner::FootstepPlanner::planning_timeout_ |  | protected | 
 
 
◆ pointcloud_model_
  
  | 
        
          | pcl::PointCloud<pcl::PointNormal>::Ptr jsk_footstep_planner::FootstepPlanner::pointcloud_model_ |  | protected | 
 
 
◆ pointcloud_model_frame_id_
  
  | 
        
          | std::string jsk_footstep_planner::FootstepPlanner::pointcloud_model_frame_id_ |  | protected | 
 
 
◆ profile_period_
  
  | 
        
          | int jsk_footstep_planner::FootstepPlanner::profile_period_ |  | protected | 
 
 
◆ project_goal_state_
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::project_goal_state_ |  | protected | 
 
 
◆ project_start_state_
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::project_start_state_ |  | protected | 
 
 
◆ pub_close_list_
◆ pub_open_list_
◆ pub_text_
◆ resolution_theta_
  
  | 
        
          | double jsk_footstep_planner::FootstepPlanner::resolution_theta_ |  | protected | 
 
 
◆ resolution_x_
  
  | 
        
          | double jsk_footstep_planner::FootstepPlanner::resolution_x_ |  | protected | 
 
 
◆ resolution_y_
  
  | 
        
          | double jsk_footstep_planner::FootstepPlanner::resolution_y_ |  | protected | 
 
 
◆ result_
  
  | 
        
          | jsk_footstep_msgs::PlanFootstepsResult jsk_footstep_planner::FootstepPlanner::result_ |  | protected | 
 
 
◆ rich_profiling_
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::rich_profiling_ |  | protected | 
 
 
◆ srv_
◆ srv_collision_bounding_box_info_
  
  | 
        
          | ros::ServiceServer jsk_footstep_planner::FootstepPlanner::srv_collision_bounding_box_info_ |  | protected | 
 
 
◆ srv_project_footprint_
◆ srv_project_footprint_with_local_search_
  
  | 
        
          | ros::ServiceServer jsk_footstep_planner::FootstepPlanner::srv_project_footprint_with_local_search_ |  | protected | 
 
 
◆ srv_project_footstep_
◆ srv_set_heuristic_path_
◆ sub_obstacle_model_
◆ sub_pointcloud_model_
  
  | 
        
          | ros::Subscriber jsk_footstep_planner::FootstepPlanner::sub_pointcloud_model_ |  | protected | 
 
 
◆ successors_
  
  | 
        
          | std::vector<Eigen::Affine3f> jsk_footstep_planner::FootstepPlanner::successors_ |  | protected | 
 
 
◆ use_lazy_perception_
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::use_lazy_perception_ |  | protected | 
 
 
◆ use_local_movement_
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::use_local_movement_ |  | protected | 
 
 
◆ use_obstacle_model_
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::use_obstacle_model_ |  | protected | 
 
 
◆ use_pointcloud_model_
  
  | 
        
          | bool jsk_footstep_planner::FootstepPlanner::use_pointcloud_model_ |  | protected | 
 
 
The documentation for this class was generated from the following files: