49 #ifndef FASTRACK_PLANNING_PLANNER_H 50 #define FASTRACK_PLANNING_PLANNER_H 56 #include <fastrack_srvs/Replan.h> 57 #include <fastrack_srvs/ReplanRequest.h> 58 #include <fastrack_srvs/ReplanResponse.h> 59 #include <fastrack_msgs/Trajectory.h> 62 #include <visualization_msgs/Marker.h> 67 using environment::Environment;
68 using trajectory::Trajectory;
70 template<
typename S,
typename E,
71 typename D,
typename SD,
typename B,
typename SB>
91 fastrack_srvs::ReplanRequest& req, fastrack_srvs::ReplanResponse& res) {
93 const S start(req.req.start);
94 const S goal(req.req.goal);
97 const Trajectory<S> traj =
Plan(start, goal, req.req.start_time);
100 res.traj = traj.ToRos();
101 return traj.Size() > 0;
106 virtual Trajectory<S>
Plan(
107 const S& start,
const S& goal,
double start_time=0.0)
const = 0;
140 template<
typename S,
typename E,
141 typename D,
typename SD,
typename B,
typename SB>
143 name_ = ros::names::append(n.getNamespace(),
"Planner");
146 ROS_ERROR(
"%s: Failed to load parameters.",
name_.c_str());
151 ROS_ERROR(
"%s: Failed to register callbacks.",
name_.c_str());
156 if (!
env_.Initialize(n)) {
157 ROS_ERROR(
"%s: Failed to initialize environment.",
name_.c_str());
163 ROS_ERROR(
"%s: Bound server was disconnected.",
name_.c_str());
169 ROS_ERROR(
"%s: Bound server error.",
name_.c_str());
173 bound_.FromRos(b.response);
177 ROS_ERROR(
"%s: Dynamics server was disconnected.",
name_.c_str());
183 ROS_ERROR(
"%s: Dynamics server error.",
name_.c_str());
197 template<
typename S,
typename E,
198 typename D,
typename SD,
typename B,
typename SB>
200 ros::NodeHandle nl(n);
208 if (!nl.getParam(
"max_runtime",
max_runtime_))
return false;
211 if (!nl.getParam(
"state/lower",
state_lower_))
return false;
212 if (!nl.getParam(
"state/upper",
state_upper_))
return false;
218 template<
typename S,
typename E,
219 typename D,
typename SD,
typename B,
typename SB>
221 ros::NodeHandle nl(n);
ros::ServiceClient bound_srv_
std::string replan_srv_name_
std::vector< double > state_lower_
bool ReplanServer(fastrack_srvs::ReplanRequest &req, fastrack_srvs::ReplanResponse &res)
std::string bound_srv_name_
std::vector< double > state_upper_
bool Initialize(const ros::NodeHandle &n)
virtual Trajectory< S > Plan(const S &start, const S &goal, double start_time=0.0) const =0
ros::ServiceServer replan_srv_
virtual bool LoadParameters(const ros::NodeHandle &n)
virtual bool RegisterCallbacks(const ros::NodeHandle &n)
ros::ServiceClient dynamics_srv_
std::string dynamics_srv_name_