Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
vigir_footstep_planning::WalkAnalyzer Class Reference

#include <walk_analyzer.h>

List of all members.

Public Types

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

Public Member Functions

void executeStepPlanGoalCallback (const msgs::ExecuteStepPlanActionGoal &execute_goal)
void executeStepPlanResultCallback (const msgs::ExecuteStepPlanActionResult &execute_result)
void reset ()
void stepFeedbackCallback (const msgs::StepPlanFeedback &feedback)
 WalkAnalyzer (ros::NodeHandle &nh)
 ~WalkAnalyzer ()

Protected Member Functions

virtual bool analyze (const msgs::Step &previous, const msgs::Step &current, const msgs::Step &next, std::string &result) const
bool analyzeData (const std::map< int, msgs::Step > &data, std::string &result) const
std::string currentDateTime () const
void writeResult (const std::string &logging_dir, const std::string &data_header)

Protected Attributes

actionlib_msgs::GoalID current_goal_id
msgs::StepPlan current_step_plan
std::string data_header
std::string logging_dir
std::map< int, msgs::Step > step_feedback_map

Detailed Description

Definition at line 50 of file walk_analyzer.h.


Member Typedef Documentation

Definition at line 64 of file walk_analyzer.h.

Definition at line 63 of file walk_analyzer.h.


Constructor & Destructor Documentation

Definition at line 5 of file walk_analyzer.cpp.

Definition at line 13 of file walk_analyzer.cpp.


Member Function Documentation

bool vigir_footstep_planning::WalkAnalyzer::analyze ( const msgs::Step &  previous,
const msgs::Step &  current,
const msgs::Step &  next,
std::string &  result 
) const [protected, virtual]

Definition at line 74 of file walk_analyzer.cpp.

bool vigir_footstep_planning::WalkAnalyzer::analyzeData ( const std::map< int, msgs::Step > &  data,
std::string &  result 
) const [protected]

Definition at line 123 of file walk_analyzer.cpp.

std::string vigir_footstep_planning::WalkAnalyzer::currentDateTime ( ) const [protected]

Definition at line 203 of file walk_analyzer.cpp.

void vigir_footstep_planning::WalkAnalyzer::executeStepPlanGoalCallback ( const msgs::ExecuteStepPlanActionGoal &  execute_goal)

Definition at line 24 of file walk_analyzer.cpp.

void vigir_footstep_planning::WalkAnalyzer::executeStepPlanResultCallback ( const msgs::ExecuteStepPlanActionResult &  execute_result)

Definition at line 55 of file walk_analyzer.cpp.

Definition at line 17 of file walk_analyzer.cpp.

void vigir_footstep_planning::WalkAnalyzer::stepFeedbackCallback ( const msgs::StepPlanFeedback &  feedback)

Definition at line 62 of file walk_analyzer.cpp.

void vigir_footstep_planning::WalkAnalyzer::writeResult ( const std::string &  logging_dir,
const std::string &  data_header 
) [protected]

Definition at line 162 of file walk_analyzer.cpp.


Member Data Documentation

actionlib_msgs::GoalID vigir_footstep_planning::WalkAnalyzer::current_goal_id [protected]

Definition at line 77 of file walk_analyzer.h.

Definition at line 79 of file walk_analyzer.h.

Definition at line 75 of file walk_analyzer.h.

Definition at line 74 of file walk_analyzer.h.

std::map<int, msgs::Step> vigir_footstep_planning::WalkAnalyzer::step_feedback_map [protected]

Definition at line 80 of file walk_analyzer.h.


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


vigir_walk_monitor
Author(s): Alexander Stumpf
autogenerated on Thu Jun 6 2019 18:38:20