38 #ifndef EBAND_LOCAL_PLANNER_ROS_H_ 39 #define EBAND_LOCAL_PLANNER_ROS_H_ 47 #include <dynamic_reconfigure/server.h> 54 #include <eband_local_planner/EBandPlannerConfig.h> 60 #include <nav_msgs/Path.h> 61 #include <nav_msgs/Odometry.h> 62 #include <geometry_msgs/PoseStamped.h> 63 #include <visualization_msgs/MarkerArray.h> 64 #include <visualization_msgs/Marker.h> 75 #include <boost/bind.hpp> 76 #include <boost/shared_ptr.hpp> 121 bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
145 typedef dynamic_reconfigure::Server<
146 eband_local_planner::EBandPlannerConfig>
drs;
187 void odomCallback(
const nav_msgs::Odometry::ConstPtr& msg);
boost::shared_ptr< EBandPlanner > eband_
bool isGoalReached()
Check if the goal pose has been achieved.
boost::shared_ptr< EBandTrajectoryCtrl > eband_trj_ctrl_
tf::TransformListener * tf_
pointer to Transform Listener
EBandPlannerROS()
Default constructor for the ros wrapper.
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the controller is following; also reset eband-planner.
double trans_stopped_vel_
lower bound for absolute value of velocity (with respect to stick-slip behaviour) ...
double xy_goal_tolerance_
parameters to define region in which goal is treated as reached
double yaw_goal_tolerance_
Plugin to the ros base_local_planner. Implements a wrapper for the Elastic Band Method.
dynamic_reconfigure::Server< eband_local_planner::EBandPlannerConfig > drs
std::vector< geometry_msgs::PoseStamped > transformed_plan_
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
boost::shared_ptr< EBandVisualization > eband_visual_
ros::Publisher g_plan_pub_
publishes modified global plan
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
Odometry-Callback: function is called whenever a new odometry msg is published on that topic...
~EBandPlannerROS()
Destructor for the wrapper.
std::vector< geometry_msgs::PoseStamped > global_plan_
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the ros wrapper.
std::vector< int > plan_start_end_counter_
void reconfigureCallback(EBandPlannerConfig &config, uint32_t level)
Reconfigures node parameters.
ros::Publisher l_plan_pub_
publishes prediction for local commands
costmap_2d::Costmap2DROS * costmap_ros_
pointer to costmap
ros::Subscriber odom_sub_
subscribes to the odometry topic in global namespace
boost::shared_ptr< drs > drs_
dynamic reconfigure server ptr
nav_msgs::Odometry base_odom_