Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes
vigir_footstep_planning::StepPlan Class Reference

#include <step_plan.h>

List of all members.

Public Types

typedef boost::shared_ptr
< const StepPlan
ConstPtr
typedef boost::shared_ptr
< StepPlan
Ptr

Public Member Functions

msgs::ErrorStatus appendStepPlan (const msgs::StepPlan &step_plan)
 Appends a step plan to current step plan. No transformation will be done!
void clear ()
bool empty () const
msgs::ErrorStatus fromMsg (const msgs::StepPlan &step_plan)
bool getfirstStep (msgs::Step &step) const
int getFirstStepIndex () const
bool getLastStep (msgs::Step &step) const
int getLastStepIndex () const
bool getStep (msgs::Step &step, unsigned int step_index) const
bool getStepAt (msgs::Step &step, unsigned int position) const
bool hasStep (unsigned int step_index) const
msgs::ErrorStatus insertStep (const msgs::Step &step)
StepPlanoperator+ (const msgs::StepPlan &step_plan)
StepPlanoperator+ (const msgs::Step &step)
StepPlanoperator- (const msgs::Step &step)
StepPlanoperator= (const msgs::StepPlan &step_plan)
StepPlanoperator| (const msgs::StepPlan &step_plan)
StepPlanoperator| (const msgs::Step &step)
bool popStep (msgs::Step &step)
bool popStep ()
void removeStep (unsigned int step_index)
void removeStepAt (unsigned int position)
void removeSteps (unsigned int from_step_index, int to_step_index=-1)
size_t size () const
 StepPlan (const msgs::StepPlan &step_plan)
 StepPlan ()
msgs::ErrorStatus stitchStepPlan (const msgs::StepPlan &step_plan, int step_index=0)
 Stitches the given step plan into the current step plan starting at step_index. Hereby the all in range [0, step_index] are kept and all steps in range (step_index, inf] are taken from input step plan. The steps at step_index from both step plans are taken as reference points (= both are representing the equal position in world frame) to transform the input step plan towards each other. Finally, all steps are stitched to the current step plan based on the determined transformation.
msgs::ErrorStatus toMsg (msgs::StepPlan &step_plan) const
msgs::ErrorStatus updateStep (const msgs::Step &step)
msgs::ErrorStatus updateStepPlan (const msgs::StepPlan &step_plan)
 Merges the given step plan to current step plan. Already exisiting steps *will* be tagged as modified. No transformation will be done!

Static Public Member Functions

static bool getStep (msgs::Step &step, const msgs::StepPlan &step_plan, unsigned int step_index)
static tf::Transform getTransform (const geometry_msgs::Pose &current, const geometry_msgs::Pose &target)
 Determines transformation T from current to target coordinate system represented by the given poses in a commom coordinate system W so target_W = T * current_W holds.
static void transformStepPlan (msgs::StepPlan &step_plan, const tf::Transform &transform)

Protected Member Functions

msgs::ErrorStatus _appendStepPlan (const msgs::StepPlan &step_plan)
 Appends a step plan to current step plan. No transformation will be done!
void _clear ()
bool _empty () const
bool _getStep (msgs::Step &step, unsigned int step_index) const
bool _hasStep (unsigned int step_index) const
msgs::ErrorStatus _insertStep (const msgs::Step &step)
 Inserts step into step plan. If the step does already exists it will be overwritten and *not tagged* as modified.
size_t _size () const
msgs::ErrorStatus _stitchStepPlan (const msgs::StepPlan &step_plan, int step_index=0)
 Stitches the given step plan into the current step plan starting at step_index. Hereby the all in range [0, step_index] are kept and all steps in range (step_index, inf] are taken from input step plan. The steps at step_index from both step plans are taken as reference points (= both are representing the equal position in world frame) to transform the input step plan towards each other. Finally, all steps are stitched to the current step plan based on the determined transformation.
msgs::ErrorStatus _updateStep (const msgs::Step &step)
 Inserts step into step plan. If the step does already exists it will be overwritten and *tagged* as modified.
msgs::ErrorStatus _updateStepPlan (const msgs::StepPlan &step_plan)
 Merges the given step plan to current step plan. Already exisiting steps *will* be tagged as modified. No transformation will be done!

Protected Attributes

std::vector< uint8_t > data
msgs::Feet goal
std_msgs::Header header
uint8_t mode
msgs::Feet start
boost::shared_mutex step_plan_mutex
std::map< unsigned int,
msgs::Step > 
steps

Detailed Description

Wrapper class for vigir_footstep_planning_msgs::StepPlan to provide advanced operations.

Definition at line 48 of file step_plan.h.


Member Typedef Documentation

typedef boost::shared_ptr<const StepPlan> vigir_footstep_planning::StepPlan::ConstPtr

Definition at line 152 of file step_plan.h.

Definition at line 151 of file step_plan.h.


Constructor & Destructor Documentation

vigir_footstep_planning::StepPlan::StepPlan ( const msgs::StepPlan &  step_plan)

Definition at line 7 of file step_plan.cpp.

Definition at line 12 of file step_plan.cpp.


Member Function Documentation

msgs::ErrorStatus vigir_footstep_planning::StepPlan::_appendStepPlan ( const msgs::StepPlan &  step_plan) [protected]

Appends a step plan to current step plan. No transformation will be done!

Parameters:
step_planStep plan to be merged into current step plan.
Returns:
error status

Definition at line 370 of file step_plan.cpp.

mutex free versions

Definition at line 302 of file step_plan.cpp.

bool vigir_footstep_planning::StepPlan::_empty ( ) const [protected]

Definition at line 312 of file step_plan.cpp.

bool vigir_footstep_planning::StepPlan::_getStep ( msgs::Step &  step,
unsigned int  step_index 
) const [protected]

Definition at line 327 of file step_plan.cpp.

bool vigir_footstep_planning::StepPlan::_hasStep ( unsigned int  step_index) const [protected]

Definition at line 322 of file step_plan.cpp.

msgs::ErrorStatus vigir_footstep_planning::StepPlan::_insertStep ( const msgs::Step &  step) [protected]

Inserts step into step plan. If the step does already exists it will be overwritten and *not tagged* as modified.

Parameters:
stepStep to be inserted
Returns:
error status

Definition at line 338 of file step_plan.cpp.

size_t vigir_footstep_planning::StepPlan::_size ( ) const [protected]

Definition at line 317 of file step_plan.cpp.

msgs::ErrorStatus vigir_footstep_planning::StepPlan::_stitchStepPlan ( const msgs::StepPlan &  step_plan,
int  step_index = 0 
) [protected]

Stitches the given step plan into the current step plan starting at step_index. Hereby the all in range [0, step_index] are kept and all steps in range (step_index, inf] are taken from input step plan. The steps at step_index from both step plans are taken as reference points (= both are representing the equal position in world frame) to transform the input step plan towards each other. Finally, all steps are stitched to the current step plan based on the determined transformation.

Parameters:
step_planStep plan to be merged into current step plan.
Returns:
error status

Definition at line 421 of file step_plan.cpp.

msgs::ErrorStatus vigir_footstep_planning::StepPlan::_updateStep ( const msgs::Step &  step) [protected]

Inserts step into step plan. If the step does already exists it will be overwritten and *tagged* as modified.

Parameters:
stepStep to be inserted
Returns:
error status

Definition at line 352 of file step_plan.cpp.

msgs::ErrorStatus vigir_footstep_planning::StepPlan::_updateStepPlan ( const msgs::StepPlan &  step_plan) [protected]

Merges the given step plan to current step plan. Already exisiting steps *will* be tagged as modified. No transformation will be done!

Parameters:
step_planStep plan to be merged into current step plan.
Returns:
error status

Definition at line 398 of file step_plan.cpp.

msgs::ErrorStatus vigir_footstep_planning::StepPlan::appendStepPlan ( const msgs::StepPlan &  step_plan)

Appends a step plan to current step plan. No transformation will be done!

Parameters:
step_planStep plan to be merged into current step plan.
Returns:
error status

Definition at line 188 of file step_plan.cpp.

Definition at line 62 of file step_plan.h.

Definition at line 67 of file step_plan.h.

msgs::ErrorStatus vigir_footstep_planning::StepPlan::fromMsg ( const msgs::StepPlan &  step_plan)

Definition at line 478 of file step_plan.cpp.

bool vigir_footstep_planning::StepPlan::getfirstStep ( msgs::Step &  step) const

Definition at line 114 of file step_plan.cpp.

Definition at line 53 of file step_plan.cpp.

bool vigir_footstep_planning::StepPlan::getLastStep ( msgs::Step &  step) const

Definition at line 127 of file step_plan.cpp.

Definition at line 63 of file step_plan.cpp.

bool vigir_footstep_planning::StepPlan::getStep ( msgs::Step &  step,
const msgs::StepPlan &  step_plan,
unsigned int  step_index 
) [static]

Definition at line 85 of file step_plan.cpp.

bool vigir_footstep_planning::StepPlan::getStep ( msgs::Step &  step,
unsigned int  step_index 
) const [inline]

Definition at line 91 of file step_plan.h.

bool vigir_footstep_planning::StepPlan::getStepAt ( msgs::Step &  step,
unsigned int  position 
) const

Definition at line 99 of file step_plan.cpp.

Determines transformation T from current to target coordinate system represented by the given poses in a commom coordinate system W so target_W = T * current_W holds.

Parameters:
currentcenter of current coordinate system in common system W
targetcenter of target coordinate system in common system W
Returns:
transformation between both poses

Definition at line 256 of file step_plan.cpp.

bool vigir_footstep_planning::StepPlan::hasStep ( unsigned int  step_index) const [inline]

Definition at line 84 of file step_plan.h.

msgs::ErrorStatus vigir_footstep_planning::StepPlan::insertStep ( const msgs::Step &  step)

Definition at line 73 of file step_plan.cpp.

StepPlan & vigir_footstep_planning::StepPlan::operator+ ( const msgs::StepPlan &  step_plan)

Definition at line 23 of file step_plan.cpp.

StepPlan & vigir_footstep_planning::StepPlan::operator+ ( const msgs::Step &  step)

Definition at line 35 of file step_plan.cpp.

StepPlan & vigir_footstep_planning::StepPlan::operator- ( const msgs::Step &  step)

Definition at line 47 of file step_plan.cpp.

StepPlan & vigir_footstep_planning::StepPlan::operator= ( const msgs::StepPlan &  step_plan)

Definition at line 17 of file step_plan.cpp.

StepPlan & vigir_footstep_planning::StepPlan::operator| ( const msgs::StepPlan &  step_plan)

Definition at line 29 of file step_plan.cpp.

StepPlan & vigir_footstep_planning::StepPlan::operator| ( const msgs::Step &  step)

Definition at line 41 of file step_plan.cpp.

bool vigir_footstep_planning::StepPlan::popStep ( msgs::Step &  step)

Definition at line 140 of file step_plan.cpp.

Definition at line 154 of file step_plan.cpp.

void vigir_footstep_planning::StepPlan::removeStep ( unsigned int  step_index)

Definition at line 160 of file step_plan.cpp.

void vigir_footstep_planning::StepPlan::removeStepAt ( unsigned int  position)

Definition at line 166 of file step_plan.cpp.

void vigir_footstep_planning::StepPlan::removeSteps ( unsigned int  from_step_index,
int  to_step_index = -1 
)

Definition at line 172 of file step_plan.cpp.

size_t vigir_footstep_planning::StepPlan::size ( ) const [inline]

Definition at line 72 of file step_plan.h.

msgs::ErrorStatus vigir_footstep_planning::StepPlan::stitchStepPlan ( const msgs::StepPlan &  step_plan,
int  step_index = 0 
)

Stitches the given step plan into the current step plan starting at step_index. Hereby the all in range [0, step_index] are kept and all steps in range (step_index, inf] are taken from input step plan. The steps at step_index from both step plans are taken as reference points (= both are representing the equal position in world frame) to transform the input step plan towards each other. Finally, all steps are stitched to the current step plan based on the determined transformation.

Parameters:
step_planStep plan to be merged into current step plan.
step_indexStitching point where the input step plan will be stitched to the current step plan.
Returns:
error status

TODO: Check if stiching would result in consistent step plan

Definition at line 230 of file step_plan.cpp.

msgs::ErrorStatus vigir_footstep_planning::StepPlan::toMsg ( msgs::StepPlan &  step_plan) const

Definition at line 511 of file step_plan.cpp.

void vigir_footstep_planning::StepPlan::transformStepPlan ( msgs::StepPlan &  step_plan,
const tf::Transform transform 
) [static]

Definition at line 269 of file step_plan.cpp.

msgs::ErrorStatus vigir_footstep_planning::StepPlan::updateStep ( const msgs::Step &  step)

Definition at line 79 of file step_plan.cpp.

msgs::ErrorStatus vigir_footstep_planning::StepPlan::updateStepPlan ( const msgs::StepPlan &  step_plan)

Merges the given step plan to current step plan. Already exisiting steps *will* be tagged as modified. No transformation will be done!

Parameters:
step_planStep plan to be merged into current step plan.
Returns:
error status

Definition at line 210 of file step_plan.cpp.


Member Data Documentation

std::vector<uint8_t> vigir_footstep_planning::StepPlan::data [protected]

Definition at line 214 of file step_plan.h.

Definition at line 211 of file step_plan.h.

Definition at line 209 of file step_plan.h.

Definition at line 213 of file step_plan.h.

Definition at line 210 of file step_plan.h.

boost::shared_mutex vigir_footstep_planning::StepPlan::step_plan_mutex [mutable, protected]

Definition at line 207 of file step_plan.h.

std::map<unsigned int, msgs::Step> vigir_footstep_planning::StepPlan::steps [protected]

Definition at line 212 of file step_plan.h.


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


vigir_footstep_planning_msgs
Author(s): Alexander Stumpf
autogenerated on Sat Jul 8 2017 02:21:30