footstep_planner_node.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2018, Alexander Stumpf, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef FOOTSTEP_PLANNER_NODE_H__
30 #define FOOTSTEP_PLANNER_NODE_H__
31 
32 #include <ros/ros.h>
33 
34 #include <boost/thread/mutex.hpp>
35 #include <boost/bind.hpp>
36 
37 #include <geometry_msgs/PoseStamped.h>
38 #include <geometry_msgs/PoseWithCovarianceStamped.h>
39 
40 #include <vigir_footstep_planning_msgs/footstep_planning_msgs.h>
41 #include <vigir_footstep_planning_msgs/visualization.h>
42 
44 
45 
46 
48 {
54 {
55 public:
57  virtual ~FootstepPlannerNode();
58 
59  virtual void initPlugins(ros::NodeHandle& nh);
60  virtual void initialize(ros::NodeHandle& nh);
61 
62 protected:
63  // callbacks
64  void planningResultCallback(const msgs::StepPlanRequestService::Response& resp);
65  void planningResultActionCallback(const msgs::StepPlanRequestService::Response& resp, SimpleActionServer<msgs::StepPlanRequestAction>::Ptr& as);
66 
67  void planningFeedbackCallback(const msgs::PlanningFeedback& feedback);
68  void planningFeedbackActionCallback(const msgs::PlanningFeedback& feedback, SimpleActionServer<msgs::StepPlanRequestAction>::Ptr& as);
69 
70  void planningPreemptionActionCallback(SimpleActionServer<msgs::StepPlanRequestAction>::Ptr& as);
71 
72  // subscriber
73  void setParams(const std_msgs::StringConstPtr& params_name);
74  void stepPlanRequest(const msgs::StepPlanRequestConstPtr& plan_request);
75  void goalPoseCallback(const geometry_msgs::PoseStampedConstPtr& goal_pose);
76 
77  // service calls
78  bool stepPlanRequestService(msgs::StepPlanRequestService::Request& req, msgs::StepPlanRequestService::Response& resp);
79  bool updateFootService(msgs::UpdateFootService::Request& req, msgs::UpdateFootService::Response& resp);
80  bool updateFeetService(msgs::UpdateFeetService::Request& req, msgs::UpdateFeetService::Response& resp);
81  bool updateStepPlanService(msgs::UpdateStepPlanService::Request& req, msgs::UpdateStepPlanService::Response& resp);
82 
83  // action server calls
84  void stepPlanRequestAction(SimpleActionServer<msgs::StepPlanRequestAction>::Ptr& as);
85  void stepPlanRequestPreempt(SimpleActionServer<msgs::StepPlanRequestAction>::Ptr& as);
86  void updateFootAction(SimpleActionServer<msgs::UpdateFootAction>::Ptr& as);
87  void updateFeetAction(SimpleActionServer<msgs::UpdateFeetAction>::Ptr& as);
88  void updateStepPlanAction(SimpleActionServer<msgs::UpdateStepPlanAction>::Ptr& as);
89 
90  // subscribers
94 
95  // publisher
102 
103  // service clients
105 
106  // service servers
111 
112  // action servers
113  SimpleActionServer<msgs::StepPlanRequestAction>::Ptr step_plan_request_as;
114  SimpleActionServer<msgs::UpdateFootAction>::Ptr update_foot_as;
115  SimpleActionServer<msgs::UpdateFeetAction>::Ptr update_feet_as;
116  SimpleActionServer<msgs::UpdateStepPlanAction>::Ptr update_step_plan_as;
117 
118  mutable boost::recursive_mutex step_plan_request_as_mutex;
119 
121  geometry_msgs::Vector3 foot_size;
122 };
123 }
124 #endif
void planningResultActionCallback(const msgs::StepPlanRequestService::Response &resp, SimpleActionServer< msgs::StepPlanRequestAction >::Ptr &as)
void setParams(const std_msgs::StringConstPtr &params_name)
virtual void initPlugins(ros::NodeHandle &nh)
void updateFeetAction(SimpleActionServer< msgs::UpdateFeetAction >::Ptr &as)
void planningResultCallback(const msgs::StepPlanRequestService::Response &resp)
Wrapper class for FootstepPlanner, providing callbacks for the node functionality.
void updateFootAction(SimpleActionServer< msgs::UpdateFootAction >::Ptr &as)
void stepPlanRequest(const msgs::StepPlanRequestConstPtr &plan_request)
void planningFeedbackCallback(const msgs::PlanningFeedback &feedback)
void stepPlanRequestAction(SimpleActionServer< msgs::StepPlanRequestAction >::Ptr &as)
void updateStepPlanAction(SimpleActionServer< msgs::UpdateStepPlanAction >::Ptr &as)
bool updateStepPlanService(msgs::UpdateStepPlanService::Request &req, msgs::UpdateStepPlanService::Response &resp)
void planningFeedbackActionCallback(const msgs::PlanningFeedback &feedback, SimpleActionServer< msgs::StepPlanRequestAction >::Ptr &as)
void stepPlanRequestPreempt(SimpleActionServer< msgs::StepPlanRequestAction >::Ptr &as)
SimpleActionServer< msgs::UpdateStepPlanAction >::Ptr update_step_plan_as
bool updateFootService(msgs::UpdateFootService::Request &req, msgs::UpdateFootService::Response &resp)
bool updateFeetService(msgs::UpdateFeetService::Request &req, msgs::UpdateFeetService::Response &resp)
void planningPreemptionActionCallback(SimpleActionServer< msgs::StepPlanRequestAction >::Ptr &as)
bool stepPlanRequestService(msgs::StepPlanRequestService::Request &req, msgs::StepPlanRequestService::Response &resp)
void goalPoseCallback(const geometry_msgs::PoseStampedConstPtr &goal_pose)
SimpleActionServer< msgs::StepPlanRequestAction >::Ptr step_plan_request_as
SimpleActionServer< msgs::UpdateFootAction >::Ptr update_foot_as
SimpleActionServer< msgs::UpdateFeetAction >::Ptr update_feet_as
virtual void initialize(ros::NodeHandle &nh)


vigir_footstep_planner
Author(s): Alexander Stumpf
autogenerated on Sun Nov 17 2019 03:29:59