Limits the acceleration in the generated trajectories to a fraction of the simulated time. More...
#include <limited_accel_generator.h>

| 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 ¤t_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 ¤t_velocity) override | 
|  Public Member Functions inherited from dwb_local_planner::TrajectoryGenerator | |
| virtual std::vector< nav_2d_msgs::Twist2D > | getTwists (const nav_2d_msgs::Twist2D ¤t_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< VelocityIterator > | velocity_iterator_ | 
| Additional Inherited Members | |
|  Public Types inherited from dwb_local_planner::TrajectoryGenerator | |
| typedef std::shared_ptr< dwb_local_planner::TrajectoryGenerator > | Ptr | 
Limits the acceleration in the generated trajectories to a fraction of the simulated time.
Definition at line 46 of file limited_accel_generator.h.
| 
 | 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.
| 
 | 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
| cmd_vel | Desired velocity | 
| start_vel | starting velocity | 
| dt | amount of time in seconds | 
Reimplemented from dwb_plugins::StandardTrajectoryGenerator.
Definition at line 84 of file limited_accel_generator.cpp.
| 
 | overridevirtual | 
Implements dwb_local_planner::TrajectoryGenerator.
Definition at line 44 of file limited_accel_generator.cpp.
| 
 | overridevirtual | 
Implements dwb_local_planner::TrajectoryGenerator.
Definition at line 78 of file limited_accel_generator.cpp.
| 
 | protected | 
Definition at line 65 of file limited_accel_generator.h.