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>
31#include <eigen3/Eigen/Eigen>
38namespace backward_local_planner
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;
62 void setPlan(
const nav_msgs::msg::Path & path)
override;
77 const geometry_msgs::msg::PoseStamped & pose,
const geometry_msgs::msg::Twist & velocity,
78 nav2_core::GoalChecker * goal_checker)
override;
83 virtual void setSpeedLimit(
const double & speed_limit,
const bool & percentage)
override;
97 const geometry_msgs::msg::PoseStamped & pose,
double & vetta,
double & gamma,
98 double alpha_error,
double betta_error,
double rho_error);
104 const geometry_msgs::msg::PoseStamped & pose,
double & dist,
double & angular_error);
107 const geometry_msgs::msg::PoseStamped & pose,
double vetta,
double gamma,
double alpha_error,
108 geometry_msgs::msg::Twist & cmd_vel);
111 const geometry_msgs::msg::PoseStamped & tfpose,
const geometry_msgs::msg::Twist & currentTwist,
112 double angle_error,
bool & linearGoalReached, nav2_core::GoalChecker * goalChecker);
124 rclcpp_lifecycle::LifecycleNode::SharedPtr
nh_;
129 std::shared_ptr<tf2_ros::Buffer>
tf_;
131 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>>
133 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>>
planPub_;
172 const Eigen::Vector3f & pos,
const Eigen::Vector3f & vel,
float maxdist,
float maxangle,
173 float maxtime,
float dt, std::vector<Eigen::Vector3f> & outtraj);
176 const Eigen::Vector3f & pos,
const Eigen::Vector3f & vel,
double dt);
bool updateCarrotGoal(const geometry_msgs::msg::PoseStamped &pose)
rad carrot_angular_distance_
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)
meter divergenceDetectionLastCarrotLinearDistance_
void publishGoalMarker(double x, double y, double phi)
double pure_spinning_allowed_betta_error_
void deactivate() override
const double betta_offset_
std::shared_ptr< tf2_ros::Buffer > tf_
rclcpp::Duration waitingTimeout_
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
double yaw_goal_tolerance_
const double alpha_offset_
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)
virtual ~BackwardLocalPlanner()
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
double xy_goal_tolerance_
bool inGoalPureSpinningState_
double max_linear_x_speed_
void computeCurrentEuclideanAndAngularErrorsToCarrotGoal(const geometry_msgs::msg::PoseStamped &pose, double &dist, double &angular_error)
bool enable_obstacle_checking_
double linear_mode_rho_error_threshold_
bool checkCurrentPoseInGoalRange(const geometry_msgs::msg::PoseStamped &tfpose, const geometry_msgs::msg::Twist ¤tTwist, 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
bool straightBackwardsAndPureSpinningMode_
virtual void setSpeedLimit(const double &speed_limit, const bool &percentage) override
double max_angular_z_speed_
double transform_tolerance_
bool initialPureSpinningStage_
rclcpp::Time waitingStamp_
bool resamplePrecisePlan()
int currentCarrotPoseIndex_
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmapRos_
rclcpp_lifecycle::LifecycleNode::SharedPtr nh_
bool resetDivergenceDetection()