Actionlib server for footstep planning. More...
#include <footstep_planner.h>
Actionlib server for footstep planning.
Definition at line 69 of file footstep_planner.h.
typedef FootstepPlannerConfig jsk_footstep_planner::FootstepPlanner::Config |
Definition at line 73 of file footstep_planner.h.
typedef boost::shared_ptr<FootstepPlanner> jsk_footstep_planner::FootstepPlanner::Ptr |
Definition at line 72 of file footstep_planner.h.
Definition at line 45 of file footstep_planner.cpp.
void jsk_footstep_planner::FootstepPlanner::buildGraph | ( | ) | [protected, virtual] |
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.
void jsk_footstep_planner::FootstepPlanner::profile | ( | FootstepAStarSolver< FootstepGraph > & | solver, |
FootstepGraph::Ptr | graph | ||
) | [protected, virtual] |
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.
bool jsk_footstep_planner::FootstepPlanner::readSuccessors | ( | ros::NodeHandle & | nh | ) | [protected, virtual] |
format is successors:
Definition at line 508 of file footstep_planner.cpp.
double jsk_footstep_planner::FootstepPlanner::stepCostHeuristic | ( | SolverNode< FootstepState, FootstepGraph >::Ptr | node, |
FootstepGraph::Ptr | graph | ||
) | [protected, virtual] |
Definition at line 472 of file footstep_planner.cpp.
double jsk_footstep_planner::FootstepPlanner::straightHeuristic | ( | SolverNode< FootstepState, FootstepGraph >::Ptr | node, |
FootstepGraph::Ptr | graph | ||
) | [protected, virtual] |
Definition at line 485 of file footstep_planner.cpp.
double jsk_footstep_planner::FootstepPlanner::straightRotationHeuristic | ( | SolverNode< FootstepState, FootstepGraph >::Ptr | node, |
FootstepGraph::Ptr | graph | ||
) | [protected, virtual] |
Definition at line 491 of file footstep_planner.cpp.
double jsk_footstep_planner::FootstepPlanner::zeroHeuristic | ( | SolverNode< FootstepState, FootstepGraph >::Ptr | node, |
FootstepGraph::Ptr | graph | ||
) | [protected, virtual] |
Definition at line 479 of file footstep_planner.cpp.
actionlib::SimpleActionServer<jsk_footstep_msgs::PlanFootstepsAction> jsk_footstep_planner::FootstepPlanner::as_ [protected] |
Definition at line 118 of file footstep_planner.h.
int jsk_footstep_planner::FootstepPlanner::close_list_theta_num_ [protected] |
Definition at line 166 of file footstep_planner.h.
int jsk_footstep_planner::FootstepPlanner::close_list_x_num_ [protected] |
Definition at line 164 of file footstep_planner.h.
int jsk_footstep_planner::FootstepPlanner::close_list_y_num_ [protected] |
Definition at line 165 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::cost_weight_ [protected] |
Definition at line 171 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::footstep_size_x_ [protected] |
Definition at line 162 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::footstep_size_y_ [protected] |
Definition at line 163 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::goal_pos_thr_ [protected] |
Definition at line 151 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::goal_rot_thr_ [protected] |
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.
double jsk_footstep_planner::FootstepPlanner::heuristic_first_rotation_weight_ [protected] |
Definition at line 169 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::heuristic_second_rotation_weight_ [protected] |
Definition at line 170 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::heuristic_weight_ [protected] |
Definition at line 172 of file footstep_planner.h.
Definition at line 130 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::local_move_theta_ [protected] |
Definition at line 141 of file footstep_planner.h.
int jsk_footstep_planner::FootstepPlanner::local_move_theta_num_ [protected] |
Definition at line 144 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::local_move_x_ [protected] |
Definition at line 139 of file footstep_planner.h.
int jsk_footstep_planner::FootstepPlanner::local_move_x_num_ [protected] |
Definition at line 142 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::local_move_y_ [protected] |
Definition at line 140 of file footstep_planner.h.
int jsk_footstep_planner::FootstepPlanner::local_move_y_num_ [protected] |
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.
double jsk_footstep_planner::FootstepPlanner::plane_estimation_outlier_threshold_ [protected] |
Definition at line 155 of file footstep_planner.h.
pcl::PointCloud<pcl::PointNormal>::Ptr jsk_footstep_planner::FootstepPlanner::pointcloud_model_ [protected] |
Definition at line 127 of file footstep_planner.h.
int jsk_footstep_planner::FootstepPlanner::profile_period_ [protected] |
Definition at line 167 of file footstep_planner.h.
bool jsk_footstep_planner::FootstepPlanner::project_goal_state_ [protected] |
Definition at line 138 of file footstep_planner.h.
bool jsk_footstep_planner::FootstepPlanner::project_start_state_ [protected] |
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.
double jsk_footstep_planner::FootstepPlanner::resolution_theta_ [protected] |
Definition at line 161 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::resolution_x_ [protected] |
Definition at line 159 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::resolution_y_ [protected] |
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.
bool jsk_footstep_planner::FootstepPlanner::rich_profiling_ [protected] |
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.
ros::ServiceServer jsk_footstep_planner::FootstepPlanner::srv_project_footprint_with_local_search_ [protected] |
Definition at line 126 of file footstep_planner.h.
Definition at line 124 of file footstep_planner.h.
std::vector<Eigen::Affine3f> jsk_footstep_planner::FootstepPlanner::successors_ [protected] |
Definition at line 129 of file footstep_planner.h.
Definition at line 158 of file footstep_planner.h.
int jsk_footstep_planner::FootstepPlanner::support_check_x_sampling_ [protected] |
Definition at line 156 of file footstep_planner.h.
int jsk_footstep_planner::FootstepPlanner::support_check_y_sampling_ [protected] |
Definition at line 157 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::transition_limit_pitch_ [protected] |
Definition at line 149 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::transition_limit_roll_ [protected] |
Definition at line 148 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::transition_limit_x_ [protected] |
Definition at line 145 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::transition_limit_y_ [protected] |
Definition at line 146 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::transition_limit_yaw_ [protected] |
Definition at line 150 of file footstep_planner.h.
double jsk_footstep_planner::FootstepPlanner::transition_limit_z_ [protected] |
Definition at line 147 of file footstep_planner.h.
bool jsk_footstep_planner::FootstepPlanner::use_lazy_perception_ [protected] |
Definition at line 134 of file footstep_planner.h.
bool jsk_footstep_planner::FootstepPlanner::use_local_movement_ [protected] |
Definition at line 135 of file footstep_planner.h.
bool jsk_footstep_planner::FootstepPlanner::use_pointcloud_model_ [protected] |
Definition at line 133 of file footstep_planner.h.
bool jsk_footstep_planner::FootstepPlanner::use_transition_limit_ [protected] |
Definition at line 136 of file footstep_planner.h.