Class TrajectoryGenerator

Class Documentation

class TrajectoryGenerator

Interface for iterating through possible velocities and creating trajectories.

This class defines the plugin interface for two separate but related components.

First, this class provides an iterator interface for exploring all of the velocities to search, given the current velocity.

Second, the class gives an independent interface for creating a trajectory from a twist, i.e. projecting it out in time and space.

Both components rely heavily on the robot’s kinematic model, and can share many parameters, which is why they are grouped into a singular class.

Public Types

typedef std::shared_ptr<dwb_core::TrajectoryGenerator> Ptr

Public Functions

inline virtual ~TrajectoryGenerator()
virtual void initialize(const nav2_util::LifecycleNode::SharedPtr &nh, const std::string &plugin_name) = 0

Initialize parameters as needed.

Parameters:

nh – NodeHandle to read parameters from

inline virtual void reset()
virtual void startNewIteration(const nav_2d_msgs::msg::Twist2D &current_velocity) = 0

Start a new iteration based on the current velocity.

Parameters:

current_velocity

virtual bool hasMoreTwists() = 0

Test to see whether there are more twists to test.

Returns:

True if more twists, false otherwise

virtual nav_2d_msgs::msg::Twist2D nextTwist() = 0

Return the next twist and advance the iteration.

Returns:

The Twist!

inline virtual std::vector<nav_2d_msgs::msg::Twist2D> getTwists(const nav_2d_msgs::msg::Twist2D &current_velocity)

Get all the twists for an iteration.

Note: Resets the iterator if one is in process

Parameters:

current_velocity

Returns:

all the twists

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) = 0

Given a cmd_vel in the robot’s frame and initial conditions, generate a Trajectory2D.

Parameters:
  • start_pose – Current robot location

  • start_vel – Current robot velocity

  • cmd_vel – The desired command velocity

virtual void setSpeedLimit(const double &speed_limit, const bool &percentage) = 0

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.