Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #ifndef VIGIR_FOOTSTEP_PLANNING_VISUALIZATION_H__
00030 #define VIGIR_FOOTSTEP_PLANNING_VISUALIZATION_H__
00031
00032 #include <ros/ros.h>
00033 #include <tf/tf.h>
00034
00035 #include <nav_msgs/Path.h>
00036 #include <visualization_msgs/MarkerArray.h>
00037
00038 #include <vigir_footstep_planning_msgs/footstep_planning_msgs.h>
00039
00040
00041
00042 namespace vigir_footstep_planning
00043 {
00044 namespace msgs
00045 {
00046 void footToFootMarker(const Foot& foot, const geometry_msgs::Vector3& foot_size, const std_msgs::ColorRGBA& color, visualization_msgs::Marker& marker);
00047 void feetToFootMarkerArray(const Feet& feet, const geometry_msgs::Vector3& foot_size, const std_msgs::ColorRGBA& color, visualization_msgs::MarkerArray& marker_array);
00048 void stepToFootMarker(const Step& step, const geometry_msgs::Vector3& foot_size, const std_msgs::ColorRGBA& color, visualization_msgs::Marker& marker);
00049 void stepPlanToFootMarkerArray(const std::vector<Step>& steps, const geometry_msgs::Vector3& foot_size, visualization_msgs::MarkerArray& marker_array, bool add_step_index = true);
00050 void stepPlanToFootMarkerArray(const StepPlan& step_plan, const geometry_msgs::Vector3& foot_size, visualization_msgs::MarkerArray& marker_array, bool add_step_index = true);
00051
00052 void feetToUpperBodyMarker(const Feet& feet, const geometry_msgs::Vector3& upper_body_size, const geometry_msgs::Vector3& upper_body_origin_shift, const std_msgs::ColorRGBA& color, visualization_msgs::Marker& marker, bool flat = false);
00053 void stepPlanToUpperBodyMarkerArray(const std::vector<Step>& steps, const geometry_msgs::Vector3& upper_body_size, const geometry_msgs::Vector3& upper_body_origin_shift, visualization_msgs::MarkerArray& marker_array, bool add_step_index = true);
00054 void stepPlanToUpperBodyMarkerArray(const StepPlan& step_plan, const geometry_msgs::Vector3& upper_body_size, const geometry_msgs::Vector3& upper_body_origin_shift, visualization_msgs::MarkerArray& marker_array, bool add_step_index = true);
00055
00056 void stepPlanToPath(const StepPlan& step_plan, nav_msgs::Path& path);
00057 }
00058 }
00059
00060 #endif