7#include <dynamic_reconfigure/server.h>
8#include <geometry_msgs/PoseStamped.h>
9#include <nav_core/base_local_planner.h>
11#include <tf/transform_listener.h>
12#include <tf2_ros/buffer.h>
14#include <pure_spinning_local_planner/PureSpinningLocalPlannerConfig.h>
22namespace pure_spinning_local_planner
50 virtual bool setPlan(
const std::vector<geometry_msgs::PoseStamped> &plan)
override;
58 void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmapRos);
60 void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmapRos);
65 void reconfigCB(::pure_spinning_local_planner::PureSpinningLocalPlannerConfig &config, uint32_t level);
71 std::vector<geometry_msgs::PoseStamped>
plan_;
73 dynamic_reconfigure::Server<::pure_spinning_local_planner::PureSpinningLocalPlannerConfig>
paramServer_;
void reconfigCB(::pure_spinning_local_planner::PureSpinningLocalPlannerConfig &config, uint32_t level)
rad_s max_angular_z_speed_
rad intermediate_goal_yaw_tolerance_
std::vector< geometry_msgs::PoseStamped > plan_
PureSpinningLocalPlanner()
dynamic_reconfigure::Server<::pure_spinning_local_planner::PureSpinningLocalPlannerConfig > paramServer_
costmap_2d::Costmap2DROS * costmapRos_
virtual ~PureSpinningLocalPlanner()
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan) override
Set the plan that the local planner is following.
void publishGoalMarker(double x, double y, double phi)
virtual bool isGoalReached() override
Check if the goal pose has been achieved by the local planner.
virtual bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel) override
Given the current position, orientation, and velocity of the robot: compute velocity commands to send...