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

Limits the acceleration in the generated trajectories to a fraction of the simulated time. More...

#include <limited_accel_generator.h>

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

Public Member Functions

void checkUseDwaParam (const ros::NodeHandle &nh) override
 Check if the deprecated use_dwa parameter is set to the functionality that matches this class. More...
 
void initialize (ros::NodeHandle &nh) override
 
void startNewIteration (const nav_2d_msgs::Twist2D &current_velocity) override
 
- Public Member Functions inherited from dwb_plugins::StandardTrajectoryGenerator
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

nav_2d_msgs::Twist2D computeNewVelocity (const nav_2d_msgs::Twist2D &cmd_vel, const nav_2d_msgs::Twist2D &start_vel, const double dt) override
 Calculate the velocity after a set period of time, given the desired velocity and acceleration limits. More...
 
- Protected Member Functions inherited from dwb_plugins::StandardTrajectoryGenerator
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 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 acceleration_time_
 
- Protected Attributes inherited from dwb_plugins::StandardTrajectoryGenerator
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

Limits the acceleration in the generated trajectories to a fraction of the simulated time.

Definition at line 46 of file limited_accel_generator.h.

Member Function Documentation

void dwb_plugins::LimitedAccelGenerator::checkUseDwaParam ( const ros::NodeHandle nh)
overridevirtual

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 from dwb_plugins::StandardTrajectoryGenerator.

Definition at line 67 of file limited_accel_generator.cpp.

nav_2d_msgs::Twist2D dwb_plugins::LimitedAccelGenerator::computeNewVelocity ( const nav_2d_msgs::Twist2D &  cmd_vel,
const nav_2d_msgs::Twist2D &  start_vel,
const double  dt 
)
overrideprotectedvirtual

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

Unlike the StandardTrajectoryGenerator, the velocity remains constant in the LimitedAccelGenerator

Parameters
cmd_velDesired velocity
start_velstarting velocity
dtamount of time in seconds
Returns
cmd_vel

Reimplemented from dwb_plugins::StandardTrajectoryGenerator.

Definition at line 84 of file limited_accel_generator.cpp.

void dwb_plugins::LimitedAccelGenerator::initialize ( ros::NodeHandle nh)
overridevirtual
void dwb_plugins::LimitedAccelGenerator::startNewIteration ( const nav_2d_msgs::Twist2D &  current_velocity)
overridevirtual

Member Data Documentation

double dwb_plugins::LimitedAccelGenerator::acceleration_time_
protected

Definition at line 65 of file limited_accel_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