Class StandardTrajectoryGenerator

Inheritance Relationships

Base Type

  • public dwb_core::TrajectoryGenerator

Derived Type

Class Documentation

class StandardTrajectoryGenerator : public dwb_core::TrajectoryGenerator

Standard DWA-like trajectory generator.

Subclassed by dwb_plugins::LimitedAccelGenerator

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
virtual bool hasMoreTwists() override
virtual nav_2d_msgs::msg::Twist2D nextTwist() override
virtual dwb_msgs::msg::Trajectory2D generateTrajectory(const geometry_msgs::msg::Pose2D &start_pose, const nav_2d_msgs::msg::Twist2D &start_vel, const nav_2d_msgs::msg::Twist2D &cmd_vel) override
inline virtual void setSpeedLimit(const double &speed_limit, const bool &percentage) override

Limits the maximum linear speed of the robot.

Parameters:
  • speed_limit – expressed in absolute value (in m/s) or in percentage from maximum robot speed.

  • percentage – Setting speed limit in percentage if true or in absolute values in false case.

Protected Functions

virtual void initializeIterator(const nav2_util::LifecycleNode::SharedPtr &nh)

Initialize the VelocityIterator pointer. Put in its own function for easy overriding.

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)

Calculate the velocity after a set period of time, given the desired velocity and acceleration limits.

Parameters:
  • cmd_vel – Desired velocity

  • start_vel – starting velocity

  • dt – amount of time in seconds

Returns:

new velocity after dt seconds

virtual geometry_msgs::msg::Pose2D computeNewPosition(const geometry_msgs::msg::Pose2D start_pose, const nav_2d_msgs::msg::Twist2D &vel, const double dt)

Use the robot’s kinematic model to predict new positions for the robot.

Parameters:
  • start_pose – Starting pose

  • vel – Actual robot velocity (assumed to be within acceleration limits)

  • dt – amount of time in seconds

Returns:

New pose after dt seconds

virtual std::vector<double> getTimeSteps(const nav_2d_msgs::msg::Twist2D &cmd_vel)

Compute an array of time deltas between the points in the generated trajectory.

If we are discretizing by time, the returned vector will be the same constant time_granularity for all cmd_vels. Otherwise, you will get times based on the linear/angular granularity.

Right now the vector contains a single value repeated many times, but this method could be overridden to allow for dynamic spacing

Parameters:

cmd_vel – The desired command velocity

Returns:

vector of the difference between each time step in the generated trajectory

Protected Attributes

KinematicsHandler::Ptr kinematics_handler_
std::shared_ptr<VelocityIterator> velocity_iterator_
double sim_time_
bool discretize_by_time_
double time_granularity_

If discretizing by time, the amount of time between each point in the traj.

double linear_granularity_

If not discretizing by time, the amount of linear space between points.

double angular_granularity_

If not discretizing by time, the amount of angular space between points.

std::string plugin_name_

the name of the overlying plugin ID

bool include_last_point_