35 #ifndef DWB_PLUGINS__LIMITED_ACCEL_GENERATOR_HPP_
36 #define DWB_PLUGINS__LIMITED_ACCEL_GENERATOR_HPP_
41 #include "dwb_plugins/standard_traj_generator.hpp"
42 #include "nav2_util/lifecycle_node.hpp"
54 const nav2_util::LifecycleNode::SharedPtr & nh,
55 const std::string & plugin_name)
override;
56 void startNewIteration(
const nav_2d_msgs::msg::Twist2D & current_velocity)
override;
70 const nav_2d_msgs::msg::Twist2D & cmd_vel,
71 const nav_2d_msgs::msg::Twist2D & start_vel,
72 const double dt)
override;
73 double acceleration_time_;
74 std::string plugin_name_;
Limits the acceleration in the generated trajectories to a fraction of the simulated time.
void startNewIteration(const nav_2d_msgs::msg::Twist2D ¤t_velocity) override
Start a new iteration based on the current velocity.
void initialize(const nav2_util::LifecycleNode::SharedPtr &nh, const std::string &plugin_name) override
Initialize parameters as needed.
nav_2d_msgs::msg::Twist2D computeNewVelocity(const nav_2d_msgs::msg::Twist2D &cmd_vel, const nav_2d_msgs::msg::Twist2D &start_vel, const double dt) override
Calculate the velocity after a set period of time, given the desired velocity and acceleration limits...
Standard DWA-like trajectory generator.