22#include <eigen3/Eigen/Eigen>
25#include <tf2/transform_datatypes.h>
27#include <visualization_msgs/msg/marker_array.hpp>
30#include <nav2_core/controller.hpp>
37namespace forward_local_planner
47 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
48 const std::shared_ptr<tf2_ros::Buffer> tf,
49 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
59 void setPlan(
const nav_msgs::msg::Path & path)
override;
74 const geometry_msgs::msg::PoseStamped & pose,
const geometry_msgs::msg::Twist & velocity,
75 nav2_core::GoalChecker * goal_checker)
override;
80 virtual void setSpeedLimit(
const double & speed_limit,
const bool & percentage)
override;
84 nav2_util::LifecycleNode::SharedPtr
nh_;
90 const Eigen::Vector3f & pos,
const Eigen::Vector3f & vel,
float maxdist,
float maxangle,
91 float maxtime,
float dt, std::vector<Eigen::Vector3f> & outtraj);
93 const Eigen::Vector3f & pos,
const Eigen::Vector3f & vel,
double dt);
98 rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr
122 std::vector<geometry_msgs::msg::PoseStamped>
plan_;
127 std::shared_ptr<tf2_ros::Buffer>
tf_;
std::vector< geometry_msgs::msg::PoseStamped > plan_
rad carrot_angular_distance_
double max_linear_x_speed_
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmapRos_
Eigen::Vector3f computeNewPositions(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt)
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
double transform_tolerance_
std::shared_ptr< tf2_ros::Buffer > tf_
virtual ~ForwardLocalPlanner()
rclcpp::Duration waitingTimeout_
double xy_goal_tolerance_
void generateTrajectory(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, float maxdist, float maxangle, float maxtime, float dt, std::vector< Eigen::Vector3f > &outtraj)
virtual void setSpeedLimit(const double &speed_limit, const bool &percentage) override
nav2_util::LifecycleNode::SharedPtr nh_
rclcpp::Time waitingStamp_
const double alpha_offset_
double max_angular_z_speed_
void publishGoalMarker(double x, double y, double phi)
const double betta_offset_
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_
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
void deactivate() override
rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray >::SharedPtr goalMarkerPublisher_