SMACC2
Loading...
Searching...
No Matches
pure_spinning_local_planner.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20#pragma once
21//#include <dynamic_reconfigure/server.h>
22//#include <pure_spinning_local_planner/PureSpinningLocalPlannerConfig.h>
23#include <tf2/transform_datatypes.h>
24#include <tf2_ros/buffer.h>
25
26#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
27#include <Eigen/Eigen>
28#include <geometry_msgs/msg/pose_stamped.hpp>
29#include <geometry_msgs/msg/quaternion.hpp>
30#include <nav2_core/controller.hpp>
31#include <visualization_msgs/msg/marker_array.hpp>
32
33typedef double meter;
34typedef double rad;
35typedef double rad_s;
36
37namespace cl_nav2z
38{
39namespace pure_spinning_local_planner
40{
41class PureSpinningLocalPlanner : public nav2_core::Controller
42{
43public:
45
47
48 void configure(
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;
52
53 void activate() override;
54 void deactivate() override;
55 void cleanup() override;
56
61 void setPlan(const nav_msgs::msg::Path & path) override;
62
75 virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
76 const geometry_msgs::msg::PoseStamped & pose, const geometry_msgs::msg::Twist & velocity,
77 nav2_core::GoalChecker * goal_checker) override;
78
79 /*deprecated in navigation2*/
80 bool isGoalReached();
81
82 virtual void setSpeedLimit(const double & speed_limit, const bool & percentage) override;
83
84private:
85 void updateParameters();
86 nav2_util::LifecycleNode::SharedPtr nh_;
87 std::string name_;
88 void publishGoalMarker(double x, double y, double phi);
89
90 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmapRos_;
91
92 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>>
94
95 std::vector<geometry_msgs::msg::PoseStamped> plan_;
96
97 std::shared_ptr<tf2_ros::Buffer> tf_;
98
99 double k_betta_;
107};
108} // namespace pure_spinning_local_planner
109} // namespace cl_nav2z
double rad
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray > > goalMarkerPublisher_
virtual void setSpeedLimit(const double &speed_limit, const bool &percentage) override
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
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
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan