SMACC
Loading...
Searching...
No Matches
pure_spinning_local_planner.h
Go to the documentation of this file.
1/*****************************************************************************************************************
2 * ReelRobotix Inc. - Software License Agreement Copyright (c) 2018
3 * Authors: Pablo Inigo Blasco, Brett Aldrich
4 *
5 ******************************************************************************************************************/
6#pragma once
7#include <dynamic_reconfigure/server.h>
8#include <geometry_msgs/PoseStamped.h>
9#include <nav_core/base_local_planner.h>
10#include <tf/tf.h>
11#include <tf/transform_listener.h>
12#include <tf2_ros/buffer.h>
13#include <Eigen/Eigen>
14#include <pure_spinning_local_planner/PureSpinningLocalPlannerConfig.h>
15
16typedef double meter;
17typedef double rad;
18typedef double rad_s;
19
20namespace cl_move_base_z
21{
22namespace pure_spinning_local_planner
23{
24class PureSpinningLocalPlanner : public nav_core::BaseLocalPlanner
25{
26public:
28
30
37 virtual bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel) override;
38
43 virtual bool isGoalReached() override;
44
50 virtual bool setPlan(const std::vector<geometry_msgs::PoseStamped> &plan) override;
51
58 void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmapRos);
59
60 void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmapRos);
61
62 void initialize();
63
64private:
65 void reconfigCB(::pure_spinning_local_planner::PureSpinningLocalPlannerConfig &config, uint32_t level);
66
67 void publishGoalMarker(double x, double y, double phi);
68
69 costmap_2d::Costmap2DROS *costmapRos_;
70
71 std::vector<geometry_msgs::PoseStamped> plan_;
72
73 dynamic_reconfigure::Server<::pure_spinning_local_planner::PureSpinningLocalPlannerConfig> paramServer_;
74
75
76 double k_betta_;
82};
83} // namespace pure_spinning_local_planner
84} // namespace cl_move_base_z
double rad
void reconfigCB(::pure_spinning_local_planner::PureSpinningLocalPlannerConfig &config, uint32_t level)
dynamic_reconfigure::Server<::pure_spinning_local_planner::PureSpinningLocalPlannerConfig > paramServer_
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan) override
Set the plan that the local planner is following.
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...