Public Member Functions | Private Attributes | List of all members
dwb_plugins::OneDVelocityIterator Class Reference

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

#include <one_d_velocity_iterator.h>

Public Member Functions

double getVelocity () const
 Get the next velocity available. More...
 
bool isFinished () const
 
 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...
 
OneDVelocityIteratoroperator++ ()
 Increment the iterator. More...
 
void reset ()
 Reset back to the first velocity. More...
 

Private Attributes

double current_
 
double increment_
 
double max_vel_
 
double min_vel_
 
bool return_zero_
 
bool return_zero_now_
 

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 85 of file one_d_velocity_iterator.h.

Constructor & Destructor Documentation

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 98 of file one_d_velocity_iterator.h.

Member Function Documentation

double dwb_plugins::OneDVelocityIterator::getVelocity ( ) const
inline

Get the next velocity available.

Definition at line 127 of file one_d_velocity_iterator.h.

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

If we have returned all the velocities for this iteration

Definition at line 164 of file one_d_velocity_iterator.h.

OneDVelocityIterator& dwb_plugins::OneDVelocityIterator::operator++ ( )
inline

Increment the iterator.

Definition at line 136 of file one_d_velocity_iterator.h.

void dwb_plugins::OneDVelocityIterator::reset ( )
inline

Reset back to the first velocity.

Definition at line 154 of file one_d_velocity_iterator.h.

Member Data Documentation

double dwb_plugins::OneDVelocityIterator::current_
private

Definition at line 172 of file one_d_velocity_iterator.h.

double dwb_plugins::OneDVelocityIterator::increment_
private

Definition at line 173 of file one_d_velocity_iterator.h.

double dwb_plugins::OneDVelocityIterator::max_vel_
private

Definition at line 171 of file one_d_velocity_iterator.h.

double dwb_plugins::OneDVelocityIterator::min_vel_
private

Definition at line 171 of file one_d_velocity_iterator.h.

bool dwb_plugins::OneDVelocityIterator::return_zero_
private

Definition at line 170 of file one_d_velocity_iterator.h.

bool dwb_plugins::OneDVelocityIterator::return_zero_now_
private

Definition at line 170 of file one_d_velocity_iterator.h.


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


dwb_plugins
Author(s):
autogenerated on Wed Jun 26 2019 20:06:16