rsband_local_planner_ros.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2016, George Kouros.
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/or other materials provided
17 * with the distribution.
18 * * Neither the name of the the copyright holder 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 * Author: George Kouros
36 *********************************************************************/
37 
38 #ifndef RSBAND_LOCAL_PLANNER_RSBAND_LOCAL_PLANNER_ROS_H
39 #define RSBAND_LOCAL_PLANNER_RSBAND_LOCAL_PLANNER_ROS_H
40 
41 #include <ros/ros.h>
42 #include <tf/tf.h>
43 #include <nav_msgs/Path.h>
44 
45 #include <nav_core/base_local_planner.h>
46 #include "eband_local_planner/eband_local_planner.h"
49 
50 #include <dynamic_reconfigure/server.h>
51 #include "rsband_local_planner/RSBandPlannerConfig.h"
52 
53 #include <boost/shared_ptr.hpp>
54 #include <boost/bind.hpp>
55 
56 namespace rsband_local_planner
57 {
58 
63  class RSBandPlannerROS : public nav_core::BaseLocalPlanner
64  {
65  public:
66 
71 
76 
83  void initialize(std::string name, tf::TransformListener* tfListener,
84  costmap_2d::Costmap2DROS* costmapROS);
85 
91  bool setPlan(const std::vector<geometry_msgs::PoseStamped>& globalPlan);
92 
98  bool computeVelocityCommands(geometry_msgs::Twist& cmd);
99 
104  bool isGoalReached();
105 
106 
109  {
115  };
116 
117  private:
118 
124  std::vector<geometry_msgs::PoseStamped>& plan);
125 
131  bool updateEBand();
132 
139  bool emergencyPlan(std::vector<geometry_msgs::PoseStamped>& ebandPlan,
140  std::vector<geometry_msgs::PoseStamped>& emergencyPlan);
141 
147  void reconfigureCallback(RSBandPlannerConfig& config, uint32_t level);
148 
149  typedef dynamic_reconfigure::Server<
150  rsband_local_planner::RSBandPlannerConfig> drs;
152  boost::shared_ptr<drs> drs_;
153 
155  tf::TransformListener* tfListener_;
157  costmap_2d::Costmap2DROS* costmapROS_;
158 
160  boost::shared_ptr<eband_local_planner::EBandPlanner> ebandPlanner_;
162  boost::shared_ptr<ReedsSheppPlanner> rsPlanner_;
164  boost::shared_ptr<FuzzyPTC> ptc_;
165 
172 
175 
181  std::vector<geometry_msgs::PoseStamped> emergencyPoses_;
182 
183 
185  ros::Publisher globalPlanPub_;
187  ros::Publisher localPlanPub_;
189  ros::Publisher ebandPlanPub_;
191  ros::Publisher rsPlanPub_;
192 
194  std::vector<geometry_msgs::PoseStamped> globalPlan_;
196  std::vector<geometry_msgs::PoseStamped> transformedPlan_;
197 
199  std::vector<int> planStartEndCounters_;
200 
202  };
203 
204 } // namespace rsband_local_planner
205 
206 #endif // RSBAND_LOCAL_PLANNER_RSBAND_LOCAL_PLANNER_ROS_H
bool isGoalReached()
Checks whether the goal is reached.
ros::Publisher globalPlanPub_
global plan publisher
boost::shared_ptr< eband_local_planner::EBandPlanner > ebandPlanner_
eband planner ptr
double yawGoalTolerance_
angular deviation from goal pose tolerance
void initialize(std::string name, tf::TransformListener *tfListener, costmap_2d::Costmap2DROS *costmapROS)
Initializes planner.
double updateSubGoalDistThreshold_
dist threshold used when updating sub goal
std::vector< geometry_msgs::PoseStamped > transformedPlan_
transformed plan
boost::shared_ptr< drs > drs_
dynamic reconfigure server ptr
void reconfigureCallback(RSBandPlannerConfig &config, uint32_t level)
Reconfigures node parameters.
costmap_2d::Costmap2DROS * costmapROS_
costmap ROS wrapper ptr
boost::shared_ptr< ReedsSheppPlanner > rsPlanner_
reeds shepp planner ptr
bool computeVelocityCommands(geometry_msgs::Twist &cmd)
Computes the velocity command for the robot base.
dynamic_reconfigure::Server< rsband_local_planner::RSBandPlannerConfig > drs
double xyGoalTolerance_
distance to goal tolerance
boost::shared_ptr< FuzzyPTC > ptc_
path tracking controller ptr
std::vector< int > planStartEndCounters_
eband plan start and end indexes regarding global plan
std::vector< geometry_msgs::PoseStamped > globalPlan_
global plan
ros::Publisher ebandPlanPub_
eband plan publisher
A local planner plugin for move_base of ROS, for car like robots.
void interpolateOrientations(std::vector< geometry_msgs::PoseStamped > &plan)
Interpolates pose orientations of the given plan.
ros::Publisher localPlanPub_
local plan publisher
ros::Publisher rsPlanPub_
rs plan publisher
tf::TransformListener * tfListener_
tf transform listener ptr
EbandToRSStrategy ebandToRSStrategy_
eband to reeds shepp band conversion strategy
std::vector< geometry_msgs::PoseStamped > emergencyPoses_
bool emergencyPlan(std::vector< geometry_msgs::PoseStamped > &ebandPlan, std::vector< geometry_msgs::PoseStamped > &emergencyPlan)
Attempts an emergency plan in case actual plan failed.
EbandToRSStrategy
eband to rs planning strategy enum
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &globalPlan)
Sets the global plan to be followed by this planner.


rsband_local_planner
Author(s): George Kouros
autogenerated on Wed Nov 9 2016 19:13:53