footstep_planner.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_FOOTSTEP_PLANNER_FOOTSTEP_PLANNER_H_
38 #define JSK_FOOTSTEP_PLANNER_FOOTSTEP_PLANNER_H_
39 
40 #include <ros/ros.h>
42 
43 // ros
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>
50 
51 // footstep planning
56 #include <jsk_footstep_planner/CollisionBoundingBoxInfo.h>
57 #include <jsk_interactive_marker/SnapFootPrint.h>
58 
59 #include "jsk_footstep_planner/ProjectFootstep.h"
60 #include "jsk_footstep_planner/SetHeuristicPath.h"
61 
62 namespace jsk_footstep_planner
63 {
64  enum PlanningStatus
65  {
66  OK, WARNING, ERROR
67  };
72  class FootstepPlanner
73  {
74  public:
76  typedef FootstepPlannerConfig Config;
79 
80  protected:
81 
82  // Initialization
83  virtual bool readSuccessors(ros::NodeHandle& nh);
84 
85  virtual void pointcloudCallback(const sensor_msgs::PointCloud2::ConstPtr& msg);
86  virtual void obstacleCallback(const sensor_msgs::PointCloud2::ConstPtr& msg);
87  virtual void planCB(const jsk_footstep_msgs::PlanFootstepsGoal::ConstPtr& goal);
88 
89  // buildGraph is not thread safe, it is responsible for caller to take care
90  // of mutex
91  virtual void buildGraph();
92 
93  virtual void configCallback(Config &config, uint32_t level);
94 
95  virtual double stepCostHeuristic(
97  virtual double zeroHeuristic(
99  virtual double straightHeuristic(
101  virtual double straightRotationHeuristic(
103  virtual double followPathLineHeuristic(
106  virtual void publishPointCloud(
107  const pcl::PointCloud<pcl::PointNormal>& cloud,
109  const std_msgs::Header& header);
110  virtual bool projectFootPrint(
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);
115 
116  virtual bool projectFootPrintService(
117  jsk_interactive_marker::SnapFootPrint::Request& req,
118  jsk_interactive_marker::SnapFootPrint::Response& res);
119  virtual bool projectFootstepService(
120  jsk_footstep_planner::ProjectFootstep::Request& req,
121  jsk_footstep_planner::ProjectFootstep::Response& res);
122  virtual bool collisionBoundingBoxInfoService(
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);
128  virtual bool setHeuristicPathService(
129  jsk_footstep_planner::SetHeuristicPath::Request& req,
130  jsk_footstep_planner::SetHeuristicPath::Response& res);
131  virtual void publishText(ros::Publisher& pub,
132  const std::string& text,
133  PlanningStatus status);
134 
137  jsk_footstep_msgs::PlanFootstepsResult result_;
149  pcl::PointCloud<pcl::PointNormal>::Ptr pointcloud_model_;
150  pcl::PointCloud<pcl::PointXYZ>::Ptr obstacle_model_;
152  std::vector<Eigen::Affine3f> successors_;
153  Eigen::Vector3f collision_bbox_size_;
154  Eigen::Affine3f collision_bbox_offset_;
155  Eigen::Vector3f inv_lleg_footstep_offset_;
156  Eigen::Vector3f inv_rleg_footstep_offset_;
157  std_msgs::Header latest_header_;
158  // Common Parameters
160 
161  // Parameters
162  bool rich_profiling_;
164  bool project_goal_state_;
178  std::string heuristic_;
181  double cost_weight_;
186 
187  private:
188 
189  };
190 }
191 
192 #endif
jsk_footstep_planner::OK
@ OK
Definition: footstep_planner.h:130
jsk_footstep_planner::FootstepPlanner::heuristic_first_rotation_weight_
double heuristic_first_rotation_weight_
Definition: footstep_planner.h:211
jsk_footstep_planner::FootstepPlanner::profile
virtual void profile(FootstepAStarSolver< FootstepGraph > &solver, FootstepGraph::Ptr graph)
Definition: footstep_planner.cpp:765
jsk_footstep_planner::FootstepPlanner::projectFootPrint
virtual bool projectFootPrint(const Eigen::Affine3f &center_pose, const Eigen::Affine3f &left_pose_trans, const Eigen::Affine3f &right_pose_trans, geometry_msgs::Pose &pose)
Definition: footstep_planner.cpp:168
jsk_footstep_planner::FootstepPlanner::pub_open_list_
ros::Publisher pub_open_list_
Definition: footstep_planner.h:172
jsk_footstep_planner::FootstepPlanner::num_finalize_steps_
size_t num_finalize_steps_
Definition: footstep_planner.h:217
jsk_footstep_planner::FootstepParameters
Definition: footstep_parameters.h:74
ros::Publisher
astar_solver.h
jsk_footstep_planner::FootstepPlanner::successors_
std::vector< Eigen::Affine3f > successors_
Definition: footstep_planner.h:184
jsk_footstep_planner::FootstepPlanner::project_start_state_
bool project_start_state_
Definition: footstep_planner.h:195
jsk_footstep_planner::FootstepPlanner::resolution_y_
double resolution_y_
Definition: footstep_planner.h:202
boost::shared_ptr
footstep_astar_solver.h
jsk_footstep_planner::FootstepPlanner::pointcloud_model_frame_id_
std::string pointcloud_model_frame_id_
Definition: footstep_planner.h:215
footstep_parameters.h
jsk_footstep_planner::FootstepPlanner::use_obstacle_model_
bool use_obstacle_model_
Definition: footstep_planner.h:200
jsk_footstep_planner::FootstepPlanner::Ptr
boost::shared_ptr< FootstepPlanner > Ptr
Definition: footstep_planner.h:107
jsk_footstep_planner::FootstepPlanner::planCB
virtual void planCB(const jsk_footstep_msgs::PlanFootstepsGoal::ConstPtr &goal)
Definition: footstep_planner.cpp:443
ros.h
cloud
pcl::PointCloud< pcl::PointNormal >::Ptr cloud
Definition: footstep_projection_demo.cpp:49
footstep_array_to_bounding_box_array.pub
pub
Definition: footstep_array_to_bounding_box_array.py:24
jsk_footstep_planner::FootstepPlanner::mutex_
boost::mutex mutex_
Definition: footstep_planner.h:167
jsk_footstep_planner::FootstepPlanner::resolution_x_
double resolution_x_
Definition: footstep_planner.h:201
jsk_footstep_planner::FootstepPlanner::pointcloudCallback
virtual void pointcloudCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: footstep_planner.cpp:155
simple_action_server.h
jsk_footstep_planner::FootstepPlanner::straightHeuristic
virtual double straightHeuristic(SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph)
Definition: footstep_planner.cpp:799
jsk_footstep_planner::FootstepPlanner::srv_project_footstep_
ros::ServiceServer srv_project_footstep_
Definition: footstep_planner.h:179
jsk_footstep_planner::ERROR
@ ERROR
Definition: footstep_planner.h:130
jsk_footstep_planner::FootstepPlanner::srv_project_footprint_
ros::ServiceServer srv_project_footprint_
Definition: footstep_planner.h:176
jsk_footstep_planner::FootstepPlanner::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: footstep_planner.cpp:919
jsk_footstep_planner::FootstepPlanner::projectFootPrintService
virtual bool projectFootPrintService(jsk_interactive_marker::SnapFootPrint::Request &req, jsk_interactive_marker::SnapFootPrint::Response &res)
Definition: footstep_planner.cpp:348
jsk_footstep_planner::FootstepPlanner::publishText
virtual void publishText(ros::Publisher &pub, const std::string &text, PlanningStatus status)
Definition: footstep_planner.cpp:402
mutex
boost::mutex mutex
Definition: pointcloud_model_generator_node.cpp:46
jsk_footstep_planner::FootstepPlanner::collision_bbox_size_
Eigen::Vector3f collision_bbox_size_
Definition: footstep_planner.h:185
jsk_footstep_planner::FootstepPlanner::latest_header_
std_msgs::Header latest_header_
Definition: footstep_planner.h:189
jsk_footstep_planner::FootstepPlanner::as_
actionlib::SimpleActionServer< jsk_footstep_msgs::PlanFootstepsAction > as_
Definition: footstep_planner.h:168
ros::ServiceServer
jsk_footstep_planner::FootstepPlanner::obstacle_model_frame_id_
std::string obstacle_model_frame_id_
Definition: footstep_planner.h:215
jsk_footstep_planner::FootstepPlanner::use_pointcloud_model_
bool use_pointcloud_model_
Definition: footstep_planner.h:197
jsk_footstep_planner::FootstepAStarSolver
Definition: footstep_astar_solver.h:80
jsk_footstep_planner::FootstepPlanner::heuristic_
std::string heuristic_
Definition: footstep_planner.h:210
jsk_footstep_planner::FootstepPlanner::close_list_theta_num_
int close_list_theta_num_
Definition: footstep_planner.h:208
jsk_footstep_planner::WARNING
@ WARNING
Definition: footstep_planner.h:130
jsk_footstep_planner
Definition: ann_grid.h:50
jsk_footstep_planner::FootstepPlanner::heuristic_second_rotation_weight_
double heuristic_second_rotation_weight_
Definition: footstep_planner.h:212
jsk_footstep_planner::FootstepPlanner::publishPointCloud
virtual void publishPointCloud(const pcl::PointCloud< pcl::PointNormal > &cloud, ros::Publisher &pub, const std_msgs::Header &header)
Definition: footstep_planner.cpp:754
jsk_footstep_planner::FootstepPlanner::buildGraph
virtual void buildGraph()
Definition: footstep_planner.cpp:1010
jsk_footstep_planner::FootstepPlanner::collisionBoundingBoxInfoService
virtual bool collisionBoundingBoxInfoService(jsk_footstep_planner::CollisionBoundingBoxInfo::Request &req, jsk_footstep_planner::CollisionBoundingBoxInfo::Response &res)
Definition: footstep_planner.cpp:268
jsk_footstep_planner::FootstepPlanner::projectFootstepService
virtual bool projectFootstepService(jsk_footstep_planner::ProjectFootstep::Request &req, jsk_footstep_planner::ProjectFootstep::Response &res)
Definition: footstep_planner.cpp:280
jsk_footstep_planner::FootstepPlanner::project_goal_state_
bool project_goal_state_
Definition: footstep_planner.h:196
jsk_footstep_planner::FootstepPlanner::close_list_x_num_
int close_list_x_num_
Definition: footstep_planner.h:206
graph
FootstepGraph::Ptr graph
Definition: footstep_planning_2d_interactive_demo.cpp:51
jsk_footstep_planner::FootstepPlanner::readSuccessors
virtual bool readSuccessors(ros::NodeHandle &nh)
Definition: footstep_planner.cpp:828
jsk_footstep_planner::FootstepPlanner::setHeuristicPathService
virtual bool setHeuristicPathService(jsk_footstep_planner::SetHeuristicPath::Request &req, jsk_footstep_planner::SetHeuristicPath::Response &res)
Definition: footstep_planner.cpp:381
jsk_footstep_planner::FootstepPlanner::close_list_y_num_
int close_list_y_num_
Definition: footstep_planner.h:207
jsk_footstep_planner::FootstepPlanner::planning_timeout_
double planning_timeout_
Definition: footstep_planner.h:216
jsk_footstep_planner::FootstepPlanner::sub_pointcloud_model_
ros::Subscriber sub_pointcloud_model_
Definition: footstep_planner.h:174
jsk_footstep_planner::FootstepPlanner::sub_obstacle_model_
ros::Subscriber sub_obstacle_model_
Definition: footstep_planner.h:175
jsk_footstep_planner::FootstepPlanner::resolution_theta_
double resolution_theta_
Definition: footstep_planner.h:203
jsk_footstep_planner::FootstepPlanner::heuristic_weight_
double heuristic_weight_
Definition: footstep_planner.h:214
jsk_footstep_planner::FootstepPlanner::footstep_size_x_
double footstep_size_x_
Definition: footstep_planner.h:204
jsk_footstep_planner::FootstepPlanner::pointcloud_model_
pcl::PointCloud< pcl::PointNormal >::Ptr pointcloud_model_
Definition: footstep_planner.h:181
jsk_recognition_utils::PolyLine
jsk_footstep_planner::FootstepPlanner::inv_lleg_footstep_offset_
Eigen::Vector3f inv_lleg_footstep_offset_
Definition: footstep_planner.h:187
jsk_footstep_planner::FootstepPlanner::FootstepPlanner
FootstepPlanner(ros::NodeHandle &nh)
Definition: footstep_planner.cpp:78
jsk_footstep_planner::FootstepPlanner::obstacle_model_
pcl::PointCloud< pcl::PointXYZ >::Ptr obstacle_model_
Definition: footstep_planner.h:182
jsk_footstep_planner::FootstepPlanner::inv_rleg_footstep_offset_
Eigen::Vector3f inv_rleg_footstep_offset_
Definition: footstep_planner.h:188
jsk_footstep_planner::FootstepPlanner::profile_period_
int profile_period_
Definition: footstep_planner.h:209
jsk_footstep_planner::FootstepPlanner::rich_profiling_
bool rich_profiling_
Definition: footstep_planner.h:194
footstep_graph.h
jsk_footstep_planner::FootstepPlanner::Config
FootstepPlannerConfig Config
Definition: footstep_planner.h:108
jsk_footstep_planner::FootstepPlanner::followPathLineHeuristic
virtual double followPathLineHeuristic(SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph)
Definition: footstep_planner.cpp:811
actionlib::SimpleActionServer< jsk_footstep_msgs::PlanFootstepsAction >
jsk_footstep_planner::FootstepPlanner::result_
jsk_footstep_msgs::PlanFootstepsResult result_
Definition: footstep_planner.h:169
jsk_footstep_planner::FootstepPlanner::straightRotationHeuristic
virtual double straightRotationHeuristic(SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph)
Definition: footstep_planner.cpp:805
jsk_footstep_planner::FootstepPlanner::zeroHeuristic
virtual double zeroHeuristic(SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph)
Definition: footstep_planner.cpp:793
jsk_footstep_planner::FootstepPlanner::projectFootPrintWithLocalSearchService
virtual bool projectFootPrintWithLocalSearchService(jsk_interactive_marker::SnapFootPrint::Request &req, jsk_interactive_marker::SnapFootPrint::Response &res)
Definition: footstep_planner.cpp:208
jsk_footstep_planner::FootstepPlanner::collision_bbox_offset_
Eigen::Affine3f collision_bbox_offset_
Definition: footstep_planner.h:186
jsk_footstep_planner::FootstepPlanner::graph_
FootstepGraph::Ptr graph_
Definition: footstep_planner.h:183
jsk_footstep_planner::FootstepPlanner::pub_text_
ros::Publisher pub_text_
Definition: footstep_planner.h:173
jsk_footstep_planner::FootstepPlanner::obstacleCallback
virtual void obstacleCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: footstep_planner.cpp:143
jsk_footstep_planner::FootstepPlanner::use_lazy_perception_
bool use_lazy_perception_
Definition: footstep_planner.h:198
jsk_footstep_planner::FootstepPlanner::cost_weight_
double cost_weight_
Definition: footstep_planner.h:213
jsk_footstep_planner::FootstepPlanner::use_local_movement_
bool use_local_movement_
Definition: footstep_planner.h:199
jsk_footstep_planner::FootstepPlanner::srv_collision_bounding_box_info_
ros::ServiceServer srv_collision_bounding_box_info_
Definition: footstep_planner.h:178
jsk_footstep_planner::FootstepPlanner::setHeuristicPathLine
virtual void setHeuristicPathLine(jsk_recognition_utils::PolyLine &path_line)
Definition: footstep_planner.cpp:1030
jsk_footstep_planner::FootstepPlanner::stepCostHeuristic
virtual double stepCostHeuristic(SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph)
Definition: footstep_planner.cpp:786
jsk_footstep_planner::FootstepPlanner::pub_close_list_
ros::Publisher pub_close_list_
Definition: footstep_planner.h:171
jsk_footstep_planner::FootstepPlanner::footstep_size_y_
double footstep_size_y_
Definition: footstep_planner.h:205
jsk_footstep_planner::FootstepPlanner::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: footstep_planner.h:170
jsk_footstep_planner::PlanningStatus
PlanningStatus
Definition: footstep_planner.h:96
ros::NodeHandle
ros::Subscriber
jsk_footstep_planner::FootstepPlanner::srv_set_heuristic_path_
ros::ServiceServer srv_set_heuristic_path_
Definition: footstep_planner.h:180
jsk_footstep_planner::FootstepPlanner::srv_project_footprint_with_local_search_
ros::ServiceServer srv_project_footprint_with_local_search_
Definition: footstep_planner.h:177
jsk_footstep_planner::FootstepPlanner::parameters_
FootstepParameters parameters_
Definition: footstep_planner.h:191


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Wed Jan 24 2024 04:05:29