Class LimitedAccelGenerator

Inheritance Relationships

Base Type

Class Documentation

class LimitedAccelGenerator : public dwb_plugins::StandardTrajectoryGenerator

Limits the acceleration in the generated trajectories to a fraction of the simulated time.

Public Functions

virtual void initialize(const nav2_util::LifecycleNode::SharedPtr &nh, const std::string &plugin_name) override
virtual void startNewIteration(const nav_2d_msgs::msg::Twist2D &current_velocity) override

Protected Functions

virtual 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.

Unlike the StandardTrajectoryGenerator, the velocity remains constant in the LimitedAccelGenerator

Parameters:
  • cmd_vel – Desired velocity

  • start_vel – starting velocity

  • dt – amount of time in seconds

Returns:

cmd_vel

Protected Attributes

double acceleration_time_
std::string plugin_name_