Public Member Functions | Protected Member Functions | Protected Attributes
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]

List of all members.

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.
void initialize (ros::NodeHandle &nh) override
void startNewIteration (const nav_2d_msgs::Twist2D &current_velocity) override

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.

Protected Attributes

double acceleration_time_

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

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 
) [override, protected, virtual]

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.

Reimplemented from dwb_plugins::StandardTrajectoryGenerator.

Definition at line 44 of file limited_accel_generator.cpp.

void dwb_plugins::LimitedAccelGenerator::startNewIteration ( const nav_2d_msgs::Twist2D &  current_velocity) [override, virtual]

Reimplemented from dwb_plugins::StandardTrajectoryGenerator.

Definition at line 78 of file limited_accel_generator.cpp.


Member Data Documentation

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 Wed Jun 26 2019 20:09:40