37 #ifndef JSK_FOOTSTEP_PLANNER_FOOTSTEP_PLANNER_H_ 38 #define JSK_FOOTSTEP_PLANNER_FOOTSTEP_PLANNER_H_ 44 #include <jsk_footstep_msgs/FootstepArray.h> 45 #include <jsk_footstep_msgs/PlanFootstepsAction.h> 46 #include <jsk_footstep_planner/FootstepPlannerConfig.h> 47 #include <sensor_msgs/PointCloud2.h> 48 #include <dynamic_reconfigure/server.h> 49 #include <jsk_rviz_plugins/OverlayText.h> 56 #include <jsk_footstep_planner/CollisionBoundingBoxInfo.h> 57 #include <jsk_interactive_marker/SnapFootPrint.h> 59 #include "jsk_footstep_planner/ProjectFootstep.h" 60 #include "jsk_footstep_planner/SetHeuristicPath.h" 76 typedef FootstepPlannerConfig
Config;
86 virtual void obstacleCallback(
const sensor_msgs::PointCloud2::ConstPtr& msg);
87 virtual void planCB(
const jsk_footstep_msgs::PlanFootstepsGoal::ConstPtr& goal);
107 const pcl::PointCloud<pcl::PointNormal>&
cloud,
109 const std_msgs::Header& header);
111 const Eigen::Affine3f& center_pose,
112 const Eigen::Affine3f& left_pose_trans,
113 const Eigen::Affine3f& right_pose_trans,
114 geometry_msgs::Pose& pose);
117 jsk_interactive_marker::SnapFootPrint::Request& req,
118 jsk_interactive_marker::SnapFootPrint::Response& res);
120 jsk_footstep_planner::ProjectFootstep::Request& req,
121 jsk_footstep_planner::ProjectFootstep::Response& res);
123 jsk_footstep_planner::CollisionBoundingBoxInfo::Request& req,
124 jsk_footstep_planner::CollisionBoundingBoxInfo::Response& res);
126 jsk_interactive_marker::SnapFootPrint::Request& req,
127 jsk_interactive_marker::SnapFootPrint::Response& res);
129 jsk_footstep_planner::SetHeuristicPath::Request& req,
130 jsk_footstep_planner::SetHeuristicPath::Response& res);
132 const std::string& text,
137 jsk_footstep_msgs::PlanFootstepsResult
result_;