Public Types | Public Member Functions | List of all members
dwb_local_planner::TrajectoryGenerator Class Referenceabstract

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

#include <trajectory_generator.h>

Public Types

using Ptr = std::shared_ptr< dwb_local_planner::TrajectoryGenerator >
 

Public Member Functions

virtual dwb_msgs::Trajectory2D generateTrajectory (const geometry_msgs::Pose2D &start_pose, const nav_2d_msgs::Twist2D &start_vel, const nav_2d_msgs::Twist2D &cmd_vel)=0
 Given a cmd_vel in the robot's frame and initial conditions, generate a Trajectory2D. More...
 
virtual std::vector< nav_2d_msgs::Twist2D > getTwists (const nav_2d_msgs::Twist2D &current_velocity)
 Get all the twists for an iteration. More...
 
virtual bool hasMoreTwists ()=0
 Test to see whether there are more twists to test. More...
 
virtual void initialize (ros::NodeHandle &nh)=0
 Initialize parameters as needed. More...
 
virtual nav_2d_msgs::Twist2D nextTwist ()=0
 Return the next twist and advance the iteration. More...
 
virtual void reset ()
 Reset the state (if any) when the planner gets a new goal. More...
 
virtual void startNewIteration (const nav_2d_msgs::Twist2D &current_velocity)=0
 Start a new iteration based on the current velocity. More...
 
virtual ~TrajectoryGenerator ()
 

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 62 of file trajectory_generator.h.

Member Typedef Documentation

Definition at line 65 of file trajectory_generator.h.

Constructor & Destructor Documentation

virtual dwb_local_planner::TrajectoryGenerator::~TrajectoryGenerator ( )
inlinevirtual

Definition at line 67 of file trajectory_generator.h.

Member Function Documentation

virtual dwb_msgs::Trajectory2D dwb_local_planner::TrajectoryGenerator::generateTrajectory ( const geometry_msgs::Pose2D &  start_pose,
const nav_2d_msgs::Twist2D &  start_vel,
const nav_2d_msgs::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
virtual std::vector<nav_2d_msgs::Twist2D> dwb_local_planner::TrajectoryGenerator::getTwists ( const nav_2d_msgs::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 106 of file trajectory_generator.h.

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

Test to see whether there are more twists to test.

Returns
True if more twists, false otherwise
virtual void dwb_local_planner::TrajectoryGenerator::initialize ( ros::NodeHandle nh)
pure virtual

Initialize parameters as needed.

Parameters
nhNodeHandle to read parameters from
virtual nav_2d_msgs::Twist2D dwb_local_planner::TrajectoryGenerator::nextTwist ( )
pure virtual

Return the next twist and advance the iteration.

Returns
The Twist!
virtual void dwb_local_planner::TrajectoryGenerator::reset ( )
inlinevirtual

Reset the state (if any) when the planner gets a new goal.

Definition at line 78 of file trajectory_generator.h.

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

Start a new iteration based on the current velocity.

Parameters
current_velocity

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


dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Sun Jan 10 2021 04:08:34