SMACC2
Loading...
Searching...
No Matches
backward_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 <backward_local_planner/BackwardLocalPlannerConfig.h>
23#include <tf2/transform_datatypes.h>
24#include <tf2_ros/buffer.h>
25#include <geometry_msgs/msg/pose_stamped.hpp>
26#include <nav2_core/controller.hpp>
27#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
28#include <visualization_msgs/msg/marker_array.hpp>
29
30#include <tf2/utils.h>
31#include <eigen3/Eigen/Eigen>
32
33typedef double meter;
34typedef double rad;
35
36namespace cl_nav2z
37{
38namespace backward_local_planner
39{
40class BackwardLocalPlanner : public nav2_core::Controller
41{
42public:
44
45 virtual ~BackwardLocalPlanner();
46
47 void configure(
48 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
49 const std::shared_ptr<tf2_ros::Buffer> tf,
50 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
51
52 void activate() override;
53
54 void deactivate() override;
55
56 void cleanup() override;
57
62 void setPlan(const nav_msgs::msg::Path & path) override;
63
76 virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
77 const geometry_msgs::msg::PoseStamped & pose, const geometry_msgs::msg::Twist & velocity,
78 nav2_core::GoalChecker * goal_checker) override;
79
80 /*deprecated in navigation2*/
81 bool isGoalReached();
82
83 virtual void setSpeedLimit(const double & speed_limit, const bool & percentage) override;
84
85private:
86 void updateParameters();
87
88 // returns true if found
89 bool findInitialCarrotGoal(geometry_msgs::msg::PoseStamped & pose);
90
91 // returns true for a pure spining motion request
92 bool updateCarrotGoal(const geometry_msgs::msg::PoseStamped & pose);
93
95
97 const geometry_msgs::msg::PoseStamped & pose, double & vetta, double & gamma,
98 double alpha_error, double betta_error, double rho_error);
99
100 void clearMarkers();
101 void publishGoalMarker(double x, double y, double phi);
102
104 const geometry_msgs::msg::PoseStamped & pose, double & dist, double & angular_error);
105
107 const geometry_msgs::msg::PoseStamped & pose, double vetta, double gamma, double alpha_error,
108 geometry_msgs::msg::Twist & cmd_vel);
109
111 const geometry_msgs::msg::PoseStamped & tfpose, const geometry_msgs::msg::Twist & currentTwist,
112 double angle_error, bool & linearGoalReached, nav2_core::GoalChecker * goalChecker);
113
115
116 bool divergenceDetectionUpdate(const geometry_msgs::msg::PoseStamped & pose);
117
118 bool checkCarrotHalfPlainConstraint(const geometry_msgs::msg::PoseStamped & pose);
119
120 // void reconfigCB(::backward_local_planner::BackwardLocalPlannerConfig &config, uint32_t level);
121 // dynamic_reconfigure::Server<::backward_local_planner::BackwardLocalPlannerConfig> paramServer_;
122 // dynamic_reconfigure::Server<::backward_local_planner::BackwardLocalPlannerConfig>::CallbackType f;
123
124 rclcpp_lifecycle::LifecycleNode::SharedPtr nh_;
125 std::string name_;
126
127 std::vector<geometry_msgs::msg::PoseStamped> backwardsPlanPath_;
128 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmapRos_;
129 std::shared_ptr<tf2_ros::Buffer> tf_;
130
131 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>>
133 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> planPub_;
134
135 // --- control parameters ---
136 double k_rho_;
137 double k_alpha_;
138 double k_betta_;
141
142 const double alpha_offset_ = M_PI;
143 const double betta_offset_ = 0;
144
145 double max_linear_x_speed_; // meters/sec
146 double max_angular_z_speed_; // rads/sec
147
148 double yaw_goal_tolerance_; // radians
149 double xy_goal_tolerance_; // meters
150
154
156
157 rclcpp::Duration waitingTimeout_;
158 rclcpp::Time waitingStamp_;
159
160 // --- controller state ---
167
168 // references the current point inside the backwardsPlanPath were the robot is located
170
172 const Eigen::Vector3f & pos, const Eigen::Vector3f & vel, float maxdist, float maxangle,
173 float maxtime, float dt, std::vector<Eigen::Vector3f> & outtraj);
174
175 Eigen::Vector3f computeNewPositions(
176 const Eigen::Vector3f & pos, const Eigen::Vector3f & vel, double dt);
177};
178} // namespace backward_local_planner
179} // namespace cl_nav2z
double meter
bool updateCarrotGoal(const geometry_msgs::msg::PoseStamped &pose)
bool checkCarrotHalfPlainConstraint(const geometry_msgs::msg::PoseStamped &pose)
Eigen::Vector3f computeNewPositions(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt)
bool checkGoalReached(const geometry_msgs::msg::PoseStamped &pose, double vetta, double gamma, double alpha_error, geometry_msgs::msg::Twist &cmd_vel)
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 straightBackwardsAndPureSpinCmd(const geometry_msgs::msg::PoseStamped &pose, double &vetta, double &gamma, double alpha_error, double betta_error, double rho_error)
std::vector< geometry_msgs::msg::PoseStamped > backwardsPlanPath_
void generateTrajectory(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, float maxdist, float maxangle, float maxtime, float dt, std::vector< Eigen::Vector3f > &outtraj)
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray > > goalMarkerPublisher_
bool findInitialCarrotGoal(geometry_msgs::msg::PoseStamped &pose)
bool divergenceDetectionUpdate(const geometry_msgs::msg::PoseStamped &pose)
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
void computeCurrentEuclideanAndAngularErrorsToCarrotGoal(const geometry_msgs::msg::PoseStamped &pose, double &dist, double &angular_error)
bool checkCurrentPoseInGoalRange(const geometry_msgs::msg::PoseStamped &tfpose, const geometry_msgs::msg::Twist &currentTwist, double angle_error, bool &linearGoalReached, nav2_core::GoalChecker *goalChecker)
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path > > planPub_
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 void setSpeedLimit(const double &speed_limit, const bool &percentage) override
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmapRos_