Public Types | Public Member Functions | Protected Attributes | List of all members
vigir_step_control::StepQueue Class Reference

#include <step_queue.h>

Public Types

typedef boost::shared_ptr< const StepQueueConstPtr
 
typedef boost::shared_ptr< StepQueuePtr
 

Public Member Functions

void clearDirtyFlag ()
 Resets dirty flag. More...
 
bool empty () const
 Checks if there are steps in queue. More...
 
int firstStepIndex () const
 Returns next step index enqueued for execution. More...
 
bool getStep (msgs::Step &step, unsigned int step_index=0u)
 Retrieves step of execution queue. More...
 
bool getStepAt (msgs::Step &step, unsigned int position=0u)
 Retrieves step of execution queue. More...
 
std::vector< msgs::Step > getSteps (unsigned int start_index, unsigned int end_index) const
 getSteps Retrieves all steps with index in range of [start_index; end_index] More...
 
bool isDirty () const
 Returns if step queue has been changed. More...
 
int lastStepIndex () const
 Returns last step index enqueued for execution. More...
 
bool popStep (msgs::Step &step)
 Dequeues and returns next step from execution queue. More...
 
bool popStep ()
 
void removeStep (unsigned int step_index)
 Remove steps with specific index from queue. More...
 
void removeSteps (unsigned int from_step_index, int to_step_index=-1)
 Remove steps in the given range [from_step_index, to_step_index]. More...
 
void reset ()
 
size_t size () const
 Returns size of step queue. More...
 
 StepQueue ()
 
bool updateStepPlan (const msgs::StepPlan &step_plan, int min_step_index=0)
 Merges given step plan to the current execution queue of steps. Hereby, two cases have to considered: More...
 
virtual ~StepQueue ()
 

Protected Attributes

bool is_dirty_
 
Mutex queue_mutex_
 
StepPlan step_plan_
 

Detailed Description

Definition at line 51 of file step_queue.h.

Member Typedef Documentation

Definition at line 56 of file step_queue.h.

Definition at line 55 of file step_queue.h.

Constructor & Destructor Documentation

vigir_step_control::StepQueue::StepQueue ( )

Definition at line 7 of file step_queue.cpp.

vigir_step_control::StepQueue::~StepQueue ( )
virtual

Definition at line 11 of file step_queue.cpp.

Member Function Documentation

void vigir_step_control::StepQueue::clearDirtyFlag ( )

Resets dirty flag.

Definition at line 40 of file step_queue.cpp.

bool vigir_step_control::StepQueue::empty ( ) const

Checks if there are steps in queue.

Returns
True if any steps has been enqueued.

Definition at line 22 of file step_queue.cpp.

int vigir_step_control::StepQueue::firstStepIndex ( ) const

Returns next step index enqueued for execution.

Returns
Step index of next step in queue. If queue is empty -1 will be returned.

Definition at line 177 of file step_queue.cpp.

bool vigir_step_control::StepQueue::getStep ( msgs::Step &  step,
unsigned int  step_index = 0u 
)

Retrieves step of execution queue.

Parameters
stepOutgoing variable for retrieved step.
indexPosition of step in queue to be returned. 0 points to the next step to be executed next.
Returns
True If step could been returned.

Definition at line 121 of file step_queue.cpp.

bool vigir_step_control::StepQueue::getStepAt ( msgs::Step &  step,
unsigned int  position = 0u 
)

Retrieves step of execution queue.

Parameters
stepOutgoing variable for retrieved step.
positionPosition of step in queue to be returned. 0 points to the next step to be executed next.
Returns
True If step could been returned.

Definition at line 127 of file step_queue.cpp.

std::vector< msgs::Step > vigir_step_control::StepQueue::getSteps ( unsigned int  start_index,
unsigned int  end_index 
) const

getSteps Retrieves all steps with index in range of [start_index; end_index]

Parameters
start_indexStarting index
end_indexEnding index
Returns
List of all found steps within given range of [start_index; end_index]

Definition at line 133 of file step_queue.cpp.

bool vigir_step_control::StepQueue::isDirty ( ) const

Returns if step queue has been changed.

Returns
true if recent changes have been appleid

Definition at line 34 of file step_queue.cpp.

int vigir_step_control::StepQueue::lastStepIndex ( ) const

Returns last step index enqueued for execution.

Returns
Step index of last step in queue. If queue is empty -1 will be returned.

Definition at line 188 of file step_queue.cpp.

bool vigir_step_control::StepQueue::popStep ( msgs::Step &  step)

Dequeues and returns next step from execution queue.

Parameters
stepOutgoing variable for dequeued step.
Returns
True if step could been dequeued.

Definition at line 163 of file step_queue.cpp.

bool vigir_step_control::StepQueue::popStep ( )

Definition at line 170 of file step_queue.cpp.

void vigir_step_control::StepQueue::removeStep ( unsigned int  step_index)

Remove steps with specific index from queue.

Parameters
step_indexStep to be removed

Definition at line 149 of file step_queue.cpp.

void vigir_step_control::StepQueue::removeSteps ( unsigned int  from_step_index,
int  to_step_index = -1 
)

Remove steps in the given range [from_step_index, to_step_index].

Parameters
from_step_indexstart index
to_step_indexend index; to_step_index < 0 is equal to removing all steps with index >= from_step_index

Definition at line 156 of file step_queue.cpp.

void vigir_step_control::StepQueue::reset ( )

Definition at line 15 of file step_queue.cpp.

size_t vigir_step_control::StepQueue::size ( ) const

Returns size of step queue.

Returns
Size of step queue

Definition at line 28 of file step_queue.cpp.

bool vigir_step_control::StepQueue::updateStepPlan ( const msgs::StepPlan &  step_plan,
int  min_step_index = 0 
)

Merges given step plan to the current execution queue of steps. Hereby, two cases have to considered:

  1. In case of an empty execution queue (robot is standing) the step plan has to begin with step index 0.
  2. In case of an non-empty execution queue (robot is walking) TODO: Stitching rules, new total step plan length
    Parameters
    step_planStep plan to be merged into execution queue.
    min_step_indexOnly steps with index >= min_step_index are considered for merge
    Returns
    True if step plan could be merged.

check for consistency

merge step plan

Definition at line 46 of file step_queue.cpp.

Member Data Documentation

bool vigir_step_control::StepQueue::is_dirty_
protected

Definition at line 157 of file step_queue.h.

Mutex vigir_step_control::StepQueue::queue_mutex_
mutableprotected

Definition at line 160 of file step_queue.h.

StepPlan vigir_step_control::StepQueue::step_plan_
protected

Definition at line 155 of file step_queue.h.


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


vigir_step_control
Author(s): Alexander Stumpf
autogenerated on Mon Jun 10 2019 15:44:47