Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
Public Member Functions | List of all members
dwb_plugins::OneDVelocityIterator Class Reference

An iterator for generating a number of samples in a range. More...

#include <nav2_dwb_controller/dwb_plugins/include/dwb_plugins/one_d_velocity_iterator.hpp>

Public Member Functions

 OneDVelocityIterator (double current, double min, double max, double acc_limit, double decel_limit, double acc_time, int num_samples)
 Constructor for the velocity iterator. More...
 
double getVelocity () const
 Get the next velocity available.
 
OneDVelocityIteratoroperator++ ()
 Increment the iterator.
 
void reset ()
 Reset back to the first velocity.
 
bool isFinished () const
 

Detailed Description

An iterator for generating a number of samples in a range.

In its simplest usage, this gives us N (num_samples) different velocities that are reachable given our current velocity. However, there is some fancy logic around zero velocities and the min/max velocities

If the current velocity is 2 m/s, and the acceleration limit is 1 m/ss and the acc_time is 1 s, this class would provide velocities between 1 m/s and 3 m/s.

Definition at line 82 of file one_d_velocity_iterator.hpp.

Constructor & Destructor Documentation

◆ OneDVelocityIterator()

dwb_plugins::OneDVelocityIterator::OneDVelocityIterator ( double  current,
double  min,
double  max,
double  acc_limit,
double  decel_limit,
double  acc_time,
int  num_samples 
)
inline

Constructor for the velocity iterator.

Parameters
currentCurrent velocity
minMinimum velocity allowable
maxMaximum velocity allowable
acc_limitAcceleration Limit
decel_limitDeceleration Limit
num_samplesThe number of samples to return

Definition at line 95 of file one_d_velocity_iterator.hpp.

References reset().

Here is the call graph for this function:

Member Function Documentation

◆ isFinished()

bool dwb_plugins::OneDVelocityIterator::isFinished ( ) const
inline

If we have returned all the velocities for this iteration

Definition at line 157 of file one_d_velocity_iterator.hpp.


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