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

Actionlib server for footstep planning. More...

#include <footstep_planner.h>

List of all members.

Public Types

typedef FootstepPlannerConfig Config
typedef boost::shared_ptr
< FootstepPlanner
Ptr

Public Member Functions

 FootstepPlanner (ros::NodeHandle &nh)

Protected Member Functions

virtual void buildGraph ()
virtual void configCallback (Config &config, uint32_t level)
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 &center_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 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 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)

Protected Attributes

actionlib::SimpleActionServer
< jsk_footstep_msgs::PlanFootstepsAction > 
as_
int close_list_theta_num_
int close_list_x_num_
int close_list_y_num_
double cost_weight_
double footstep_size_x_
double footstep_size_y_
double goal_pos_thr_
double goal_rot_thr_
FootstepGraph::Ptr graph_
std::string heuristic_
double heuristic_first_rotation_weight_
double heuristic_second_rotation_weight_
double heuristic_weight_
std_msgs::Header latest_header_
double local_move_theta_
int local_move_theta_num_
double local_move_x_
int local_move_x_num_
double local_move_y_
int local_move_y_num_
boost::mutex mutex_
int plane_estimation_max_iterations_
int plane_estimation_min_inliers_
double plane_estimation_outlier_threshold_
pcl::PointCloud
< pcl::PointNormal >::Ptr 
pointcloud_model_
int profile_period_
bool project_goal_state_
bool project_start_state_
ros::Publisher pub_close_list_
ros::Publisher pub_open_list_
ros::Publisher pub_text_
double resolution_theta_
double resolution_x_
double resolution_y_
jsk_footstep_msgs::PlanFootstepsResult result_
bool rich_profiling_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
ros::ServiceServer srv_project_footprint_
ros::ServiceServer srv_project_footprint_with_local_search_
ros::Subscriber sub_pointcloud_model_
std::vector< Eigen::Affine3f > successors_
double support_check_vertex_neighbor_threshold_
int support_check_x_sampling_
int support_check_y_sampling_
double transition_limit_pitch_
double transition_limit_roll_
double transition_limit_x_
double transition_limit_y_
double transition_limit_yaw_
double transition_limit_z_
bool use_lazy_perception_
bool use_local_movement_
bool use_pointcloud_model_
bool use_transition_limit_

Detailed Description

Actionlib server for footstep planning.

Definition at line 69 of file footstep_planner.h.


Member Typedef Documentation

typedef FootstepPlannerConfig jsk_footstep_planner::FootstepPlanner::Config

Definition at line 73 of file footstep_planner.h.

Definition at line 72 of file footstep_planner.h.


Constructor & Destructor Documentation

Definition at line 45 of file footstep_planner.cpp.


Member Function Documentation

Definition at line 619 of file footstep_planner.cpp.

void jsk_footstep_planner::FootstepPlanner::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 549 of file footstep_planner.cpp.

void jsk_footstep_planner::FootstepPlanner::planCB ( const jsk_footstep_msgs::PlanFootstepsGoal::ConstPtr &  goal) [protected, virtual]

Definition at line 264 of file footstep_planner.cpp.

void jsk_footstep_planner::FootstepPlanner::pointcloudCallback ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [protected, virtual]

Definition at line 77 of file footstep_planner.cpp.

Definition at line 455 of file footstep_planner.cpp.

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 
) [protected, virtual]

Definition at line 89 of file footstep_planner.cpp.

bool jsk_footstep_planner::FootstepPlanner::projectFootPrintService ( jsk_interactive_marker::SnapFootPrint::Request &  req,
jsk_interactive_marker::SnapFootPrint::Response &  res 
) [protected, virtual]

Definition at line 189 of file footstep_planner.cpp.

bool jsk_footstep_planner::FootstepPlanner::projectFootPrintWithLocalSearchService ( jsk_interactive_marker::SnapFootPrint::Request &  req,
jsk_interactive_marker::SnapFootPrint::Response &  res 
) [protected, virtual]

Definition at line 129 of file footstep_planner.cpp.

void jsk_footstep_planner::FootstepPlanner::publishPointCloud ( const pcl::PointCloud< pcl::PointNormal > &  cloud,
ros::Publisher pub,
const std_msgs::Header header 
) [protected, virtual]

Definition at line 444 of file footstep_planner.cpp.

void jsk_footstep_planner::FootstepPlanner::publishText ( ros::Publisher pub,
const std::string text,
PlanningStatus  status 
) [protected, virtual]

Definition at line 223 of file footstep_planner.cpp.

format is successors:

  • x: 0 y: 0 theta: 0
  • x: 0 y: 0 theta: 0 ...

Definition at line 508 of file footstep_planner.cpp.

Definition at line 472 of file footstep_planner.cpp.

Definition at line 485 of file footstep_planner.cpp.

Definition at line 491 of file footstep_planner.cpp.

Definition at line 479 of file footstep_planner.cpp.


Member Data Documentation

actionlib::SimpleActionServer<jsk_footstep_msgs::PlanFootstepsAction> jsk_footstep_planner::FootstepPlanner::as_ [protected]

Definition at line 118 of file footstep_planner.h.

Definition at line 166 of file footstep_planner.h.

Definition at line 164 of file footstep_planner.h.

Definition at line 165 of file footstep_planner.h.

Definition at line 171 of file footstep_planner.h.

Definition at line 162 of file footstep_planner.h.

Definition at line 163 of file footstep_planner.h.

Definition at line 151 of file footstep_planner.h.

Definition at line 152 of file footstep_planner.h.

Definition at line 128 of file footstep_planner.h.

Definition at line 168 of file footstep_planner.h.

Definition at line 169 of file footstep_planner.h.

Definition at line 170 of file footstep_planner.h.

Definition at line 172 of file footstep_planner.h.

Definition at line 130 of file footstep_planner.h.

Definition at line 141 of file footstep_planner.h.

Definition at line 144 of file footstep_planner.h.

Definition at line 139 of file footstep_planner.h.

Definition at line 142 of file footstep_planner.h.

Definition at line 140 of file footstep_planner.h.

Definition at line 143 of file footstep_planner.h.

Definition at line 117 of file footstep_planner.h.

Definition at line 153 of file footstep_planner.h.

Definition at line 154 of file footstep_planner.h.

Definition at line 155 of file footstep_planner.h.

Definition at line 127 of file footstep_planner.h.

Definition at line 167 of file footstep_planner.h.

Definition at line 138 of file footstep_planner.h.

Definition at line 137 of file footstep_planner.h.

Definition at line 121 of file footstep_planner.h.

Definition at line 122 of file footstep_planner.h.

Definition at line 123 of file footstep_planner.h.

Definition at line 161 of file footstep_planner.h.

Definition at line 159 of file footstep_planner.h.

Definition at line 160 of file footstep_planner.h.

jsk_footstep_msgs::PlanFootstepsResult jsk_footstep_planner::FootstepPlanner::result_ [protected]

Definition at line 119 of file footstep_planner.h.

Definition at line 132 of file footstep_planner.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_footstep_planner::FootstepPlanner::srv_ [protected]

Definition at line 120 of file footstep_planner.h.

Definition at line 125 of file footstep_planner.h.

Definition at line 126 of file footstep_planner.h.

Definition at line 124 of file footstep_planner.h.

Definition at line 129 of file footstep_planner.h.

Definition at line 158 of file footstep_planner.h.

Definition at line 156 of file footstep_planner.h.

Definition at line 157 of file footstep_planner.h.

Definition at line 149 of file footstep_planner.h.

Definition at line 148 of file footstep_planner.h.

Definition at line 145 of file footstep_planner.h.

Definition at line 146 of file footstep_planner.h.

Definition at line 150 of file footstep_planner.h.

Definition at line 147 of file footstep_planner.h.

Definition at line 134 of file footstep_planner.h.

Definition at line 135 of file footstep_planner.h.

Definition at line 133 of file footstep_planner.h.

Definition at line 136 of file footstep_planner.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