planner.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, The Regents of the University of California (Regents).
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
7  * met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  *
12  * 2. Redistributions in binary form must reproduce the above
13  * copyright notice, this list of conditions and the following
14  * disclaimer in the documentation and/or other materials provided
15  * with the distribution.
16  *
17  * 3. Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS AS IS
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * Please contact the author(s) of this library if you have any questions.
34  * Authors: David Fridovich-Keil ( dfk@eecs.berkeley.edu )
35  */
36 
38 //
39 // Base class for all planners. Planners are templated on state and dynamics
40 // types **of the planner** NOT **of the tracker,** as well as the tracking
41 // error bound type and environment. Planners take in start and goal states, and
42 // start time, and output a trajectory of planner states.
43 //
44 // Templated on state (S), environment (E), dynamics (D), dynamics service (SD),
45 // bound (B), and bound service (SB).
46 //
48 
49 #ifndef FASTRACK_PLANNING_PLANNER_H
50 #define FASTRACK_PLANNING_PLANNER_H
51 
54 #include <fastrack/utils/types.h>
55 
56 #include <fastrack_srvs/Replan.h>
57 #include <fastrack_srvs/ReplanRequest.h>
58 #include <fastrack_srvs/ReplanResponse.h>
59 #include <fastrack_msgs/Trajectory.h>
60 
61 #include <ros/ros.h>
62 #include <visualization_msgs/Marker.h>
63 
64 namespace fastrack {
65 namespace planning {
66 
67 using environment::Environment;
68 using trajectory::Trajectory;
69 
70 template<typename S, typename E,
71  typename D, typename SD, typename B, typename SB>
72 class Planner {
73 public:
74  virtual ~Planner() {}
75 
76  // Initialize from a ROS NodeHandle.
77  bool Initialize(const ros::NodeHandle& n);
78 
79 protected:
80  explicit Planner()
81  : initialized_(false) {}
82 
83  // Load parameters and register callbacks. These may be overridden
84  // by derived classes if needed (they should still call these functions
85  // via Planner::LoadParameters and Planner::RegisterCallbacks).
86  virtual bool LoadParameters(const ros::NodeHandle& n);
87  virtual bool RegisterCallbacks(const ros::NodeHandle& n);
88 
89  // Callback to handle replanning requests.
90  inline bool ReplanServer(
91  fastrack_srvs::ReplanRequest& req, fastrack_srvs::ReplanResponse& res) {
92  // Unpack start/stop states.
93  const S start(req.req.start);
94  const S goal(req.req.goal);
95 
96  // Plan.
97  const Trajectory<S> traj = Plan(start, goal, req.req.start_time);
98 
99  // Return whether or not planning was successful.
100  res.traj = traj.ToRos();
101  return traj.Size() > 0;
102  }
103 
104  // Plan a trajectory from the given start to goal states starting
105  // at the given time.
106  virtual Trajectory<S> Plan(
107  const S& start, const S& goal, double start_time=0.0) const = 0;
108 
109  // Keep a copy of the dynamics, tracking bound, and environment.
112  E env_;
113 
114  // Max amount of time for planning to run each time.
115  double max_runtime_;
116 
117  // State space bounds.
118  std::vector<double> state_upper_;
119  std::vector<double> state_lower_;
120 
121  // Replanning server.
122  ros::ServiceServer replan_srv_;
123  std::string replan_srv_name_;
124 
125  // Services for loading dynamics and bound.
126  ros::ServiceClient dynamics_srv_;
127  ros::ServiceClient bound_srv_;
128 
129  std::string dynamics_srv_name_;
130  std::string bound_srv_name_;
131 
132  // Naming and initialization.
133  std::string name_;
135 }; //\class Planner
136 
137 // ----------------------------- IMPLEMENTATION ----------------------------- //
138 
139 // Initialize from a ROS NodeHandle.
140 template<typename S, typename E,
141  typename D, typename SD, typename B, typename SB>
142 bool Planner<S, E, D, SD, B, SB>::Initialize(const ros::NodeHandle& n) {
143  name_ = ros::names::append(n.getNamespace(), "Planner");
144 
145  if (!LoadParameters(n)) {
146  ROS_ERROR("%s: Failed to load parameters.", name_.c_str());
147  return false;
148  }
149 
150  if (!RegisterCallbacks(n)) {
151  ROS_ERROR("%s: Failed to register callbacks.", name_.c_str());
152  return false;
153  }
154 
155  // Initialize environment.
156  if (!env_.Initialize(n)) {
157  ROS_ERROR("%s: Failed to initialize environment.", name_.c_str());
158  return false;
159  }
160 
161  // Set bound by calling service provided by tracker.
162  if (!bound_srv_) {
163  ROS_ERROR("%s: Bound server was disconnected.", name_.c_str());
164  return false;
165  }
166 
167  SB b;
168  if (!bound_srv_.call(b)) {
169  ROS_ERROR("%s: Bound server error.", name_.c_str());
170  return false;
171  }
172 
173  bound_.FromRos(b.response);
174 
175  // Set dynamics by calling service provided by tracker.
176  if (!dynamics_srv_) {
177  ROS_ERROR("%s: Dynamics server was disconnected.", name_.c_str());
178  return false;
179  }
180 
181  SD d;
182  if (!dynamics_srv_.call(d)) {
183  ROS_ERROR("%s: Dynamics server error.", name_.c_str());
184  return false;
185  }
186 
187  dynamics_.FromRos(d.response);
188 
189  // Set configuration space bounds.
190  S::SetBounds(state_lower_, state_upper_);
191 
192  initialized_ = true;
193  return true;
194 }
195 
196 // Load parameters.
197 template<typename S, typename E,
198  typename D, typename SD, typename B, typename SB>
199 bool Planner<S, E, D, SD, B, SB>::LoadParameters(const ros::NodeHandle& n) {
200  ros::NodeHandle nl(n);
201 
202  // Services.
203  if (!nl.getParam("srv/replan", replan_srv_name_)) return false;
204  if (!nl.getParam("srv/dynamics", dynamics_srv_name_)) return false;
205  if (!nl.getParam("srv/bound", bound_srv_name_)) return false;
206 
207  // Max runtime per call.
208  if (!nl.getParam("max_runtime", max_runtime_)) return false;
209 
210  // State space bounds.
211  if (!nl.getParam("state/lower", state_lower_)) return false;
212  if (!nl.getParam("state/upper", state_upper_)) return false;
213 
214  return true;
215 }
216 
217 // Register callbacks.
218 template<typename S, typename E,
219  typename D, typename SD, typename B, typename SB>
220 bool Planner<S, E, D, SD, B, SB>::RegisterCallbacks(const ros::NodeHandle& n) {
221  ros::NodeHandle nl(n);
222 
223  // Services.
224  replan_srv_ = nl.advertiseService(replan_srv_name_.c_str(),
226 
227  ros::service::waitForService(dynamics_srv_name_);
228  dynamics_srv_ = nl.serviceClient<SD>(dynamics_srv_name_.c_str(), true);
229 
230  ros::service::waitForService(bound_srv_name_);
231  bound_srv_ = nl.serviceClient<SB>(bound_srv_name_.c_str(), true);
232 
233  return true;
234 }
235 
236 } //\namespace planning
237 } //\namespace fastrack
238 
239 #endif
ros::ServiceClient bound_srv_
Definition: planner.h:127
std::string replan_srv_name_
Definition: planner.h:123
std::vector< double > state_lower_
Definition: planner.h:119
bool ReplanServer(fastrack_srvs::ReplanRequest &req, fastrack_srvs::ReplanResponse &res)
Definition: planner.h:90
std::string bound_srv_name_
Definition: planner.h:130
Definition: box.h:53
std::vector< double > state_upper_
Definition: planner.h:118
bool Initialize(const ros::NodeHandle &n)
Definition: planner.h:142
virtual Trajectory< S > Plan(const S &start, const S &goal, double start_time=0.0) const =0
ros::ServiceServer replan_srv_
Definition: planner.h:122
virtual bool LoadParameters(const ros::NodeHandle &n)
Definition: planner.h:199
virtual bool RegisterCallbacks(const ros::NodeHandle &n)
Definition: planner.h:220
ros::ServiceClient dynamics_srv_
Definition: planner.h:126
std::string dynamics_srv_name_
Definition: planner.h:129


fastrack
Author(s): David Fridovich-Keil
autogenerated on Mon Aug 3 2020 21:28:37