Go to the documentation of this file.00001 #include <vigir_walk_monitor/walk_analyzer_node.h>
00002
00003 namespace vigir_footstep_planning
00004 {
00005 WalkAnalyzerNode::WalkAnalyzerNode(ros::NodeHandle& nh, WalkAnalyzer::Ptr walk_anaylzer)
00006 : walk_analyzer(walk_anaylzer)
00007 {
00008
00009 execute_step_plan_goal_sub = nh.subscribe("execute_step_plan/goal", 0, &WalkAnalyzer::executeStepPlanGoalCallback, walk_analyzer.get());
00010 execute_step_plan_result_sub = nh.subscribe("execute_step_plan/result", 0, &WalkAnalyzer::executeStepPlanResultCallback, walk_analyzer.get());
00011 step_feedback_sub = nh.subscribe("step_feedback", 0, &WalkAnalyzer::stepFeedbackCallback, walk_analyzer.get());
00012 }
00013
00014 WalkAnalyzerNode::WalkAnalyzerNode(ros::NodeHandle& nh)
00015 : WalkAnalyzerNode(nh, WalkAnalyzer::Ptr(new WalkAnalyzer(nh)))
00016 {
00017 }
00018
00019 WalkAnalyzerNode::~WalkAnalyzerNode()
00020 {
00021 }
00022 }
00023
00024 int main (int argc, char **argv)
00025 {
00026 ros::init(argc, argv, "walk_analyzer_node");
00027 ros::NodeHandle nh;
00028 vigir_footstep_planning::WalkAnalyzerNode walk_analyzer_node(nh);
00029 ros::spin();
00030
00031 return 0;
00032 }