Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
dwb_plugins::StandardTrajectoryGenerator Class Reference

Standard DWA-like trajectory generator. More...

#include <standard_traj_generator.h>

Inheritance diagram for dwb_plugins::StandardTrajectoryGenerator:
Inheritance graph
[legend]

Public Member Functions

dwb_msgs::Trajectory2D generateTrajectory (const geometry_msgs::Pose2D &start_pose, const nav_2d_msgs::Twist2D &start_vel, const nav_2d_msgs::Twist2D &cmd_vel) override
 
bool hasMoreTwists () override
 
void initialize (ros::NodeHandle &nh) override
 
nav_2d_msgs::Twist2D nextTwist () override
 
void startNewIteration (const nav_2d_msgs::Twist2D &current_velocity) override
 
- Public Member Functions inherited from dwb_local_planner::TrajectoryGenerator
virtual std::vector< nav_2d_msgs::Twist2D > getTwists (const nav_2d_msgs::Twist2D &current_velocity)
 
virtual void reset ()
 
virtual ~TrajectoryGenerator ()
 

Protected Member Functions

virtual void checkUseDwaParam (const ros::NodeHandle &nh)
 Check if the deprecated use_dwa parameter is set to the functionality that matches this class. More...
 
virtual geometry_msgs::Pose2D computeNewPosition (const geometry_msgs::Pose2D start_pose, const nav_2d_msgs::Twist2D &vel, const double dt)
 Use the robot's kinematic model to predict new positions for the robot. More...
 
virtual nav_2d_msgs::Twist2D computeNewVelocity (const nav_2d_msgs::Twist2D &cmd_vel, const nav_2d_msgs::Twist2D &start_vel, const double dt)
 Calculate the velocity after a set period of time, given the desired velocity and acceleration limits. More...
 
virtual std::vector< double > getTimeSteps (const nav_2d_msgs::Twist2D &cmd_vel)
 Compute an array of time deltas between the points in the generated trajectory. More...
 
virtual void initializeIterator (ros::NodeHandle &nh)
 Initialize the VelocityIterator pointer. Put in its own function for easy overriding. More...
 

Protected Attributes

double angular_granularity_
 If not discretizing by time, the amount of angular space between points. More...
 
bool discretize_by_time_
 
bool include_last_point_
 
KinematicParameters::Ptr kinematics_
 
double linear_granularity_
 If not discretizing by time, the amount of linear space between points. More...
 
double sim_time_
 
double time_granularity_
 If discretizing by time, the amount of time between each point in the traj. More...
 
std::shared_ptr< VelocityIteratorvelocity_iterator_
 

Additional Inherited Members

- Public Types inherited from dwb_local_planner::TrajectoryGenerator
typedef std::shared_ptr< dwb_local_planner::TrajectoryGeneratorPtr
 

Detailed Description

Standard DWA-like trajectory generator.

Definition at line 52 of file standard_traj_generator.h.

Member Function Documentation

void dwb_plugins::StandardTrajectoryGenerator::checkUseDwaParam ( const ros::NodeHandle nh)
protectedvirtual

Check if the deprecated use_dwa parameter is set to the functionality that matches this class.

The functionality guarded by the use_dwa parameter has been split between this class and the derived LimitedAccelGenerator. If use_dwa was false, this class should be used. If it was true, then LimitedAccelGenerator. If this is NOT the case, this function will throw an exception.

Reimplemented in dwb_plugins::LimitedAccelGenerator.

Definition at line 87 of file standard_traj_generator.cpp.

geometry_msgs::Pose2D dwb_plugins::StandardTrajectoryGenerator::computeNewPosition ( const geometry_msgs::Pose2D  start_pose,
const nav_2d_msgs::Twist2D &  vel,
const double  dt 
)
protectedvirtual

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

Parameters
start_poseStarting pose
velActual robot velocity (assumed to be within acceleration limits)
dtamount of time in seconds
Returns
New pose after dt seconds

Definition at line 190 of file standard_traj_generator.cpp.

nav_2d_msgs::Twist2D dwb_plugins::StandardTrajectoryGenerator::computeNewVelocity ( const nav_2d_msgs::Twist2D &  cmd_vel,
const nav_2d_msgs::Twist2D &  start_vel,
const double  dt 
)
protectedvirtual

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

Parameters
cmd_velDesired velocity
start_velstarting velocity
dtamount of time in seconds
Returns
new velocity after dt seconds

change vel using acceleration limits to converge towards sample_target-vel

Reimplemented in dwb_plugins::LimitedAccelGenerator.

Definition at line 179 of file standard_traj_generator.cpp.

dwb_msgs::Trajectory2D dwb_plugins::StandardTrajectoryGenerator::generateTrajectory ( const geometry_msgs::Pose2D &  start_pose,
const nav_2d_msgs::Twist2D &  start_vel,
const nav_2d_msgs::Twist2D &  cmd_vel 
)
overridevirtual
std::vector< double > dwb_plugins::StandardTrajectoryGenerator::getTimeSteps ( const nav_2d_msgs::Twist2D &  cmd_vel)
protectedvirtual

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

Parameters
cmd_velThe desired command velocity
Returns
vector of the difference between each time step 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

Definition at line 113 of file standard_traj_generator.cpp.

bool dwb_plugins::StandardTrajectoryGenerator::hasMoreTwists ( )
overridevirtual
void dwb_plugins::StandardTrajectoryGenerator::initialize ( ros::NodeHandle nh)
overridevirtual
void dwb_plugins::StandardTrajectoryGenerator::initializeIterator ( ros::NodeHandle nh)
protectedvirtual

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

Definition at line 81 of file standard_traj_generator.cpp.

nav_2d_msgs::Twist2D dwb_plugins::StandardTrajectoryGenerator::nextTwist ( )
overridevirtual
void dwb_plugins::StandardTrajectoryGenerator::startNewIteration ( const nav_2d_msgs::Twist2D &  current_velocity)
overridevirtual

Member Data Documentation

double dwb_plugins::StandardTrajectoryGenerator::angular_granularity_
protected

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

Definition at line 127 of file standard_traj_generator.h.

bool dwb_plugins::StandardTrajectoryGenerator::discretize_by_time_
protected

Definition at line 124 of file standard_traj_generator.h.

bool dwb_plugins::StandardTrajectoryGenerator::include_last_point_
protected

Definition at line 142 of file standard_traj_generator.h.

KinematicParameters::Ptr dwb_plugins::StandardTrajectoryGenerator::kinematics_
protected

Definition at line 118 of file standard_traj_generator.h.

double dwb_plugins::StandardTrajectoryGenerator::linear_granularity_
protected

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

Definition at line 126 of file standard_traj_generator.h.

double dwb_plugins::StandardTrajectoryGenerator::sim_time_
protected

Definition at line 121 of file standard_traj_generator.h.

double dwb_plugins::StandardTrajectoryGenerator::time_granularity_
protected

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

Definition at line 125 of file standard_traj_generator.h.

std::shared_ptr<VelocityIterator> dwb_plugins::StandardTrajectoryGenerator::velocity_iterator_
protected

Definition at line 119 of file standard_traj_generator.h.


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


dwb_plugins
Author(s):
autogenerated on Sun Jan 10 2021 04:08:37