Interface for iterating through possible velocities and creating trajectories. More...
#include <trajectory_generator.h>
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. | |
virtual std::vector < nav_2d_msgs::Twist2D > | getTwists (const nav_2d_msgs::Twist2D ¤t_velocity) |
Get all the twists for an iteration. | |
virtual bool | hasMoreTwists ()=0 |
Test to see whether there are more twists to test. | |
virtual void | initialize (ros::NodeHandle &nh)=0 |
Initialize parameters as needed. | |
virtual nav_2d_msgs::Twist2D | nextTwist ()=0 |
Return the next twist and advance the iteration. | |
virtual void | reset () |
Reset the state (if any) when the planner gets a new goal. | |
virtual void | startNewIteration (const nav_2d_msgs::Twist2D ¤t_velocity)=0 |
Start a new iteration based on the current velocity. | |
virtual | ~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.
Definition at line 61 of file trajectory_generator.h.
virtual dwb_local_planner::TrajectoryGenerator::~TrajectoryGenerator | ( | ) | [inline, virtual] |
Definition at line 66 of file trajectory_generator.h.
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.
start_pose | Current robot location |
start_vel | Current robot velocity |
cmd_vel | The desired command velocity |
virtual std::vector<nav_2d_msgs::Twist2D> dwb_local_planner::TrajectoryGenerator::getTwists | ( | const nav_2d_msgs::Twist2D & | current_velocity | ) | [inline, virtual] |
Get all the twists for an iteration.
Note: Resets the iterator if one is in process
current_velocity |
Definition at line 105 of file trajectory_generator.h.
virtual bool dwb_local_planner::TrajectoryGenerator::hasMoreTwists | ( | ) | [pure virtual] |
Test to see whether there are more twists to test.
virtual void dwb_local_planner::TrajectoryGenerator::initialize | ( | ros::NodeHandle & | nh | ) | [pure virtual] |
Initialize parameters as needed.
nh | NodeHandle to read parameters from |
virtual nav_2d_msgs::Twist2D dwb_local_planner::TrajectoryGenerator::nextTwist | ( | ) | [pure virtual] |
Return the next twist and advance the iteration.
virtual void dwb_local_planner::TrajectoryGenerator::reset | ( | ) | [inline, virtual] |
Reset the state (if any) when the planner gets a new goal.
Definition at line 77 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.
current_velocity |