Actionlib server for footstep planning.  
 More...
#include <grid_path_planner.h>
|  | 
| virtual void | buildGraph () | 
|  | 
| virtual bool | collisionBoundingBoxInfoService (jsk_footstep_planner::CollisionBoundingBoxInfo::Request &req, jsk_footstep_planner::CollisionBoundingBoxInfo::Response &res) | 
|  | 
| virtual void | gridToPoint (const int ix, const int iy, Eigen::Vector3f &p) | 
|  | 
| double | heuristicDistance (SolverNode< PerceptionGridGraph::State, PerceptionGridGraph >::Ptr node, PerceptionGridGraph::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 | pointToGrid (const Eigen::Vector3f &p, int &ix, int &iy) | 
|  | 
| virtual void | publishMarker () | 
|  | 
| virtual void | publishPointCloud (const pcl::PointCloud< pcl::PointXYZRGB > &cloud, ros::Publisher &pub, const std_msgs::Header &header) | 
|  | 
| virtual void | publishText (ros::Publisher &pub, const std::string &text, GridPlanningStatus status) | 
|  | 
| virtual bool | updateCost (GridState::Ptr ptr) | 
|  | 
Actionlib server for footstep planning. 
Definition at line 37 of file grid_path_planner.h.
◆ Graph
◆ GridMap
◆ Solver
◆ GridPathPlanner()
      
        
          | jsk_footstep_planner::GridPathPlanner::GridPathPlanner | ( | ros::NodeHandle & | nh | ) |  | 
      
 
 
◆ buildGraph()
  
  | 
        
          | void jsk_footstep_planner::GridPathPlanner::buildGraph | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ collisionBoundingBoxInfoService()
  
  | 
        
          | bool jsk_footstep_planner::GridPathPlanner::collisionBoundingBoxInfoService | ( | jsk_footstep_planner::CollisionBoundingBoxInfo::Request & | req, |  
          |  |  | jsk_footstep_planner::CollisionBoundingBoxInfo::Response & | res |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ gridToPoint()
  
  | 
        
          | virtual void jsk_footstep_planner::GridPathPlanner::gridToPoint | ( | const int | ix, |  
          |  |  | const int | iy, |  
          |  |  | Eigen::Vector3f & | p |  
          |  | ) |  |  |  | inlineprotectedvirtual | 
 
 
◆ heuristicDistance()
◆ obstacleCallback()
  
  | 
        
          | void jsk_footstep_planner::GridPathPlanner::obstacleCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) |  |  | protectedvirtual | 
 
 
◆ planCB()
  
  | 
        
          | void jsk_footstep_planner::GridPathPlanner::planCB | ( | const jsk_footstep_msgs::PlanFootstepsGoal::ConstPtr & | goal | ) |  |  | protectedvirtual | 
 
 
◆ pointcloudCallback()
  
  | 
        
          | void jsk_footstep_planner::GridPathPlanner::pointcloudCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) |  |  | protectedvirtual | 
 
 
◆ pointToGrid()
  
  | 
        
          | virtual void jsk_footstep_planner::GridPathPlanner::pointToGrid | ( | const Eigen::Vector3f & | p, |  
          |  |  | int & | ix, |  
          |  |  | int & | iy |  
          |  | ) |  |  |  | inlineprotectedvirtual | 
 
 
◆ publishMarker()
  
  | 
        
          | void jsk_footstep_planner::GridPathPlanner::publishMarker | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ publishPointCloud()
◆ publishText()
◆ updateCost()
  
  | 
        
          | bool jsk_footstep_planner::GridPathPlanner::updateCost | ( | GridState::Ptr | ptr | ) |  |  | protectedvirtual | 
 
 
◆ as_
◆ collision_bbox_offset_
  
  | 
        
          | Eigen::Affine3f jsk_footstep_planner::GridPathPlanner::collision_bbox_offset_ |  | protected | 
 
 
◆ collision_bbox_size_
  
  | 
        
          | Eigen::Vector3f jsk_footstep_planner::GridPathPlanner::collision_bbox_size_ |  | protected | 
 
 
◆ collision_circle_max_height_
  
  | 
        
          | double jsk_footstep_planner::GridPathPlanner::collision_circle_max_height_ |  | protected | 
 
 
◆ collision_circle_min_height_
  
  | 
        
          | double jsk_footstep_planner::GridPathPlanner::collision_circle_min_height_ |  | protected | 
 
 
◆ collision_circle_radius_
  
  | 
        
          | double jsk_footstep_planner::GridPathPlanner::collision_circle_radius_ |  | protected | 
 
 
◆ graph_
◆ gridmap_
◆ map_offset_
  
  | 
        
          | Eigen::Vector3f jsk_footstep_planner::GridPathPlanner::map_offset_ |  | protected | 
 
 
◆ map_resolution_
  
  | 
        
          | double jsk_footstep_planner::GridPathPlanner::map_resolution_ |  | protected | 
 
 
◆ mutex_
◆ obstacle_points_
  
  | 
        
          | pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_footstep_planner::GridPathPlanner::obstacle_points_ |  | protected | 
 
 
◆ obstacle_points_frame_id_
  
  | 
        
          | std::string jsk_footstep_planner::GridPathPlanner::obstacle_points_frame_id_ |  | protected | 
 
 
◆ obstacle_tree_
  
  | 
        
          | pcl::KdTreeFLANN<pcl::PointXYZ>::Ptr jsk_footstep_planner::GridPathPlanner::obstacle_tree_ |  | protected | 
 
 
◆ plane_points_
  
  | 
        
          | pcl::PointCloud<pcl::PointNormal>::Ptr jsk_footstep_planner::GridPathPlanner::plane_points_ |  | protected | 
 
 
◆ plane_points_frame_id_
  
  | 
        
          | std::string jsk_footstep_planner::GridPathPlanner::plane_points_frame_id_ |  | protected | 
 
 
◆ plane_tree_
  
  | 
        
          | pcl::KdTreeFLANN<pcl::PointNormal>::Ptr jsk_footstep_planner::GridPathPlanner::plane_tree_ |  | protected | 
 
 
◆ pub_close_list_
◆ pub_marker_
◆ pub_open_list_
◆ pub_text_
◆ result_
  
  | 
        
          | jsk_footstep_msgs::PlanFootstepsResult jsk_footstep_planner::GridPathPlanner::result_ |  | protected | 
 
 
◆ srv_collision_bounding_box_info_
  
  | 
        
          | ros::ServiceServer jsk_footstep_planner::GridPathPlanner::srv_collision_bounding_box_info_ |  | protected | 
 
 
◆ sub_obstacle_points_
  
  | 
        
          | ros::Subscriber jsk_footstep_planner::GridPathPlanner::sub_obstacle_points_ |  | protected | 
 
 
◆ sub_plane_points_
◆ use_obstacle_points_
  
  | 
        
          | bool jsk_footstep_planner::GridPathPlanner::use_obstacle_points_ |  | protected | 
 
 
◆ use_plane_points_
  
  | 
        
          | bool jsk_footstep_planner::GridPathPlanner::use_plane_points_ |  | protected | 
 
 
The documentation for this class was generated from the following files: