23#include <tf2/transform_datatypes.h>
24#include <tf2_ros/buffer.h>
27#include <geometry_msgs/msg/pose_stamped.hpp>
28#include <geometry_msgs/msg/quaternion.hpp>
29#include <nav2_core/controller.hpp>
30#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
31#include <visualization_msgs/msg/marker_array.hpp>
39namespace pure_spinning_local_planner
49 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
50 const std::shared_ptr<tf2_ros::Buffer> & tf,
51 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros)
override;
61 void setPlan(
const nav_msgs::msg::Path & path)
override;
76 const geometry_msgs::msg::PoseStamped & pose,
const geometry_msgs::msg::Twist & velocity,
77 nav2_core::GoalChecker * goal_checker)
override;
82 virtual void setSpeedLimit(
const double & speed_limit,
const bool & percentage)
override;
86 nav2_util::LifecycleNode::SharedPtr
nh_;
92 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>>
95 std::vector<geometry_msgs::msg::PoseStamped>
plan_;
97 std::shared_ptr<tf2_ros::Buffer>
tf_;
rad intermediate_goal_yaw_tolerance_
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray > > goalMarkerPublisher_
PureSpinningLocalPlanner()
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmapRos_
void publishGoalMarker(double x, double y, double phi)
rad_s max_angular_z_speed_
virtual void setSpeedLimit(const double &speed_limit, const bool &percentage) override
virtual ~PureSpinningLocalPlanner()
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, const std::shared_ptr< tf2_ros::Buffer > &tf, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > &costmap_ros) override
void deactivate() override
std::vector< geometry_msgs::msg::PoseStamped > plan_
virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *goal_checker) override
nav2_core computeVelocityCommands - calculates the best command given the current pose and velocity
std::shared_ptr< tf2_ros::Buffer > tf_
nav2_util::LifecycleNode::SharedPtr nh_
bool use_shortest_angular_distance_
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
double transform_tolerance_