#include "ros/ros.h"#include "visualization_msgs/MarkerArray.h"#include "visualization_msgs/Marker.h"#include "tf/transform_broadcaster.h"#include "tf/transform_listener.h"#include "bipedRobin_msgs/InitialStepsService.h"#include "bipedRobin_msgs/SetModeService.h"#include "bipedRobin_msgs/StepTarget3DService.h"#include "std_srvs/Empty.h"#include "std_msgs/UInt8.h"#include <string.h>
Go to the source code of this file.
| #define DEFAULT_VARIABLE_NUMBER 150 | 
Definition at line 22 of file navigation_master.cpp.
| #define DEFAULT_WORDLENGTH 20 /* multible of 4 and compatible with simulink receiving file */ | 
Definition at line 23 of file navigation_master.cpp.
| void createMap | ( | ) | 
Definition at line 82 of file navigation_master.cpp.
| void dynamicPlanning | ( | ) | 
Definition at line 156 of file navigation_master.cpp.
| bool dynamicPlanningCallback | ( | std_srvs::Empty::Request & | req, | 
| std_srvs::Empty::Request & | res | ||
| ) | 
Definition at line 395 of file navigation_master.cpp.
| void goalCallback | ( | geometry_msgs::PoseStamped | pose | ) | 
Definition at line 442 of file navigation_master.cpp.
| void goalpose | ( | ) | 
Definition at line 88 of file navigation_master.cpp.
| void localize | ( | ) | 
Definition at line 76 of file navigation_master.cpp.
| int main | ( | int | argc, | 
| char ** | argv | ||
| ) | 
Definition at line 454 of file navigation_master.cpp.
| void newStepsArrayCallback | ( | const visualization_msgs::MarkerArray | markerArray | ) | 
Definition at line 412 of file navigation_master.cpp.
| void pub_goal | ( | ) | 
Definition at line 112 of file navigation_master.cpp.
| void replan | ( | ) | 
Definition at line 100 of file navigation_master.cpp.
| bool replanCallback | ( | std_srvs::Empty::Request & | req, | 
| std_srvs::Empty::Request & | res | ||
| ) | 
Definition at line 449 of file navigation_master.cpp.
| void restart | ( | ) | 
Definition at line 94 of file navigation_master.cpp.
| void sendMarker | ( | visualization_msgs::Marker | step, | 
| tf::StampedTransform | map | ||
| ) | 
Definition at line 124 of file navigation_master.cpp.
| void setdynamicInitialSteps | ( | visualization_msgs::Marker | left, | 
| visualization_msgs::Marker | right, | ||
| tf::StampedTransform | map | ||
| ) | 
Definition at line 285 of file navigation_master.cpp.
| void setInitialStep | ( | ) | 
Definition at line 364 of file navigation_master.cpp.
| void setInitialSteps | ( | tf::StampedTransform | left, | 
| tf::StampedTransform | right | ||
| ) | 
Definition at line 335 of file navigation_master.cpp.
| void staticInitialSteps | ( | ) | 
Definition at line 316 of file navigation_master.cpp.
| void staticPlanning | ( | ) | 
| bool staticPlanningCallback | ( | std_srvs::Empty::Request & | req, | 
| std_srvs::Empty::Request & | res | ||
| ) | 
Definition at line 384 of file navigation_master.cpp.
| void stepsLeftCallback | ( | std_msgs::UInt8 | stepsLeft | ) | 
Definition at line 433 of file navigation_master.cpp.
| bool walkCallback | ( | std_srvs::Empty::Request & | req, | 
| std_srvs::Empty::Request & | res | ||
| ) | 
Definition at line 406 of file navigation_master.cpp.
Definition at line 44 of file navigation_master.cpp.
| visualization_msgs::MarkerArray currentFootsteps | 
Definition at line 68 of file navigation_master.cpp.
| geometry_msgs::PoseStamped currentGoalpose | 
Definition at line 69 of file navigation_master.cpp.
| int dynamic_left_right = 1 | 
Definition at line 63 of file navigation_master.cpp.
| int dynamicBufferSize = 0 | 
Definition at line 65 of file navigation_master.cpp.
Definition at line 60 of file navigation_master.cpp.
| bool first_call_flag = true | 
Definition at line 55 of file navigation_master.cpp.
Definition at line 45 of file navigation_master.cpp.
Definition at line 50 of file navigation_master.cpp.
Definition at line 46 of file navigation_master.cpp.
Definition at line 49 of file navigation_master.cpp.
Definition at line 41 of file navigation_master.cpp.
Definition at line 42 of file navigation_master.cpp.
Definition at line 53 of file navigation_master.cpp.
Definition at line 43 of file navigation_master.cpp.
Definition at line 48 of file navigation_master.cpp.
| bool newMarkerArray_flag = false | 
Definition at line 56 of file navigation_master.cpp.
Definition at line 70 of file navigation_master.cpp.
Definition at line 71 of file navigation_master.cpp.
tf::TransformBroadcaster* pBroadcaster = NULL [static] | 
        
Definition at line 74 of file navigation_master.cpp.
Definition at line 58 of file navigation_master.cpp.
tf::TransformListener* pListener = NULL [static] | 
        
Definition at line 73 of file navigation_master.cpp.
| bool random_flag = true | 
Definition at line 61 of file navigation_master.cpp.
Definition at line 47 of file navigation_master.cpp.
| bool sendStep_flag = false | 
Definition at line 54 of file navigation_master.cpp.
| bool staticPlanner_flag = false | 
Definition at line 59 of file navigation_master.cpp.
| int stepBufferSize = 0 | 
Definition at line 66 of file navigation_master.cpp.
| int stepsLeftInBuffer = 0 | 
Definition at line 64 of file navigation_master.cpp.
Definition at line 57 of file navigation_master.cpp.