38 #ifndef RSBAND_LOCAL_PLANNER_RSBAND_LOCAL_PLANNER_ROS_H
39 #define RSBAND_LOCAL_PLANNER_RSBAND_LOCAL_PLANNER_ROS_H
43 #include <nav_msgs/Path.h>
45 #include <nav_core/base_local_planner.h>
46 #include "eband_local_planner/eband_local_planner.h"
50 #include <dynamic_reconfigure/server.h>
51 #include "rsband_local_planner/RSBandPlannerConfig.h"
53 #include <boost/shared_ptr.hpp>
54 #include <boost/bind.hpp>
56 namespace rsband_local_planner
83 void initialize(std::string name, tf::TransformListener* tfListener,
84 costmap_2d::Costmap2DROS* costmapROS);
91 bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& globalPlan);
124 std::vector<geometry_msgs::PoseStamped>& plan);
139 bool emergencyPlan(std::vector<geometry_msgs::PoseStamped>& ebandPlan,
149 typedef dynamic_reconfigure::Server<
150 rsband_local_planner::RSBandPlannerConfig>
drs;
164 boost::shared_ptr<FuzzyPTC>
ptc_;
206 #endif // RSBAND_LOCAL_PLANNER_RSBAND_LOCAL_PLANNER_ROS_H
bool isGoalReached()
Checks whether the goal is reached.
ros::Publisher globalPlanPub_
global plan publisher
bool emergencyPlanning_
emergency mode
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
bool updateEBand()
Updates eband.
boost::shared_ptr< ReedsSheppPlanner > rsPlanner_
reeds shepp planner ptr
RSBandPlannerROS()
Constructor.
bool computeVelocityCommands(geometry_msgs::Twist &cmd)
Computes the velocity command for the robot base.
~RSBandPlannerROS()
Destructor.
dynamic_reconfigure::Server< rsband_local_planner::RSBandPlannerConfig > drs
bool emergencyMode_
emergency plan poses
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.