Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
Public Types | Public Member Functions | List of all members
dwb_core::TrajectoryGenerator Class Referenceabstract

Interface for iterating through possible velocities and creating trajectories. More...

#include <nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_generator.hpp>

Inheritance diagram for dwb_core::TrajectoryGenerator:
Inheritance graph
[legend]

Public Types

typedef std::shared_ptr< dwb_core::TrajectoryGeneratorPtr
 

Public Member Functions

virtual void initialize (const nav2_util::LifecycleNode::SharedPtr &nh, const std::string &plugin_name)=0
 Initialize parameters as needed. More...
 
virtual void reset ()
 
virtual void startNewIteration (const nav_2d_msgs::msg::Twist2D &current_velocity)=0
 Start a new iteration based on the current velocity. More...
 
virtual bool hasMoreTwists ()=0
 Test to see whether there are more twists to test. More...
 
virtual nav_2d_msgs::msg::Twist2D nextTwist ()=0
 Return the next twist and advance the iteration. More...
 
virtual std::vector< nav_2d_msgs::msg::Twist2D > getTwists (const nav_2d_msgs::msg::Twist2D &current_velocity)
 Get all the twists for an iteration. More...
 
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. More...
 
virtual void setSpeedLimit (const double &speed_limit, const bool &percentage)=0
 Limits the maximum linear speed of the robot. More...
 

Detailed Description

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.

Definition at line 64 of file trajectory_generator.hpp.

Member Function Documentation

◆ generateTrajectory()

virtual dwb_msgs::msg::Trajectory2D dwb_core::TrajectoryGenerator::generateTrajectory ( const geometry_msgs::msg::Pose2D &  start_pose,
const nav_2d_msgs::msg::Twist2D &  start_vel,
const nav_2d_msgs::msg::Twist2D &  cmd_vel 
)
pure virtual

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

Parameters
start_poseCurrent robot location
start_velCurrent robot velocity
cmd_velThe desired command velocity

Implemented in dwb_plugins::StandardTrajectoryGenerator.

◆ getTwists()

virtual std::vector<nav_2d_msgs::msg::Twist2D> dwb_core::TrajectoryGenerator::getTwists ( const nav_2d_msgs::msg::Twist2D &  current_velocity)
inlinevirtual

Get all the twists for an iteration.

Note: Resets the iterator if one is in process

Parameters
current_velocity
Returns
all the twists

Definition at line 105 of file trajectory_generator.hpp.

References hasMoreTwists(), nextTwist(), and startNewIteration().

Here is the call graph for this function:

◆ hasMoreTwists()

virtual bool dwb_core::TrajectoryGenerator::hasMoreTwists ( )
pure virtual

Test to see whether there are more twists to test.

Returns
True if more twists, false otherwise

Implemented in dwb_plugins::StandardTrajectoryGenerator.

Referenced by getTwists().

Here is the caller graph for this function:

◆ initialize()

virtual void dwb_core::TrajectoryGenerator::initialize ( const nav2_util::LifecycleNode::SharedPtr &  nh,
const std::string &  plugin_name 
)
pure virtual

Initialize parameters as needed.

Parameters
nhNodeHandle to read parameters from

Implemented in dwb_plugins::StandardTrajectoryGenerator, and dwb_plugins::LimitedAccelGenerator.

◆ nextTwist()

virtual nav_2d_msgs::msg::Twist2D dwb_core::TrajectoryGenerator::nextTwist ( )
pure virtual

Return the next twist and advance the iteration.

Returns
The Twist!

Implemented in dwb_plugins::StandardTrajectoryGenerator.

Referenced by getTwists().

Here is the caller graph for this function:

◆ setSpeedLimit()

virtual void dwb_core::TrajectoryGenerator::setSpeedLimit ( const double &  speed_limit,
const bool &  percentage 
)
pure virtual

Limits the maximum linear speed of the robot.

Parameters
speed_limitexpressed in absolute value (in m/s) or in percentage from maximum robot speed.
percentageSetting speed limit in percentage if true or in absolute values in false case.

Implemented in dwb_plugins::StandardTrajectoryGenerator.

◆ startNewIteration()

virtual void dwb_core::TrajectoryGenerator::startNewIteration ( const nav_2d_msgs::msg::Twist2D &  current_velocity)
pure virtual

Start a new iteration based on the current velocity.

Parameters
current_velocity

Implemented in dwb_plugins::StandardTrajectoryGenerator, and dwb_plugins::LimitedAccelGenerator.

Referenced by getTwists().

Here is the caller graph for this function:

The documentation for this class was generated from the following file: