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_VIS_H__
00030 #define VIGIR_FOOTSTEP_PLANNING_VIS_H__
00031
00032 #include <ros/ros.h>
00033 #include <sensor_msgs/PointCloud2.h>
00034 #include <pcl_conversions/pcl_conversions.h>
00035
00036 #include <vigir_footstep_planning_msgs/footstep_planning_msgs.h>
00037 #include <vigir_footstep_planning_msgs/visualization.h>
00038
00039
00040
00041 namespace vigir_footstep_planning
00042 {
00043 namespace vis
00044 {
00045 struct StepMsgVisCompare
00046 {
00047 bool operator() (const msgs::Step& lhs, const msgs::Step& rhs) const
00048 {
00049 double lhs_a[3];
00050 toArray(lhs, lhs_a);
00051 double rhs_a[3];
00052 toArray(rhs, rhs_a);
00053
00054
00055 for (size_t i = 0; i < 3; i++)
00056 {
00057 if (lhs_a[i] < rhs_a[i])
00058 return true;
00059 else if (lhs_a[i] > rhs_a[i])
00060 return false;
00061 }
00062 return false;
00063 }
00064
00065 void toArray(const msgs::Step s, double (&a)[3]) const
00066 {
00067 a[0] = s.foot.pose.position.x;
00068 a[1] = s.foot.pose.position.y;
00069 a[2] = s.foot.pose.position.z;
00070 }
00071 };
00072
00073 void publishFeet(ros::Publisher& pub, const msgs::Feet& feet, const geometry_msgs::Vector3& foot_size, const std_msgs::ColorRGBA& color);
00074 void publishStart(ros::Publisher& pub, const msgs::Feet& feet, const geometry_msgs::Vector3& foot_size);
00075 void publishGoal(ros::Publisher& pub, const msgs::Feet& feet, const geometry_msgs::Vector3& foot_size);
00076
00077 void publishStepPlan(ros::Publisher& pub, const msgs::StepPlan& step_plan, const geometry_msgs::Vector3& foot_size, visualization_msgs::MarkerArray& last_step_plan_vis, bool add_step_index = true);
00078 void publishUpperBody(ros::Publisher& pub, const msgs::StepPlan& step_plan, const geometry_msgs::Vector3& upper_body_size, const geometry_msgs::Vector3& upper_body_origin_shift, visualization_msgs::MarkerArray& last_upper_body_vis, bool add_step_index = true);
00079 void publishPath(ros::Publisher& pub, const msgs::StepPlan& step_plan);
00080
00081 void clearFeet(ros::Publisher& pub, const std_msgs::Header& header);
00082 void clearMarkerArray(ros::Publisher& pub, visualization_msgs::MarkerArray& last_step_plan_vis);
00083 void clearPath(ros::Publisher& pub, const std_msgs::Header& header);
00084
00085 void publishRecentlyVistedSteps(ros::Publisher& pub, const std::vector<msgs::Step>& recently_visited_steps, const std_msgs::Header& header);
00086 void publishVistedSteps(ros::Publisher& pub, const std::vector<msgs::Step>& visited_steps, const std_msgs::Header& header);
00087 void publishVistedSteps(ros::Publisher& pub, const std::set<msgs::Step, StepMsgVisCompare>& visited_steps, const std_msgs::Header& header);
00088 }
00089 }
00090
00091 #endif