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 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 #ifndef EBAND_VISUALIZATION_H_
00039 #define EBAND_VISUALIZATION_H_
00040 
00041 
00042 #include <ros/ros.h>
00043 
00044 
00045 #include <eband_local_planner/conversions_and_types.h>
00046 
00047 
00048 #include <geometry_msgs/Pose2D.h>
00049 #include <geometry_msgs/Pose.h>
00050 #include <geometry_msgs/PoseStamped.h>
00051 #include <geometry_msgs/Wrench.h>
00052 #include <geometry_msgs/WrenchStamped.h>
00053 
00054 #include <visualization_msgs/Marker.h>
00055 #include <visualization_msgs/MarkerArray.h>
00056 
00057 
00058 #include <angles/angles.h>
00059 #include <tf/tf.h>
00060 #include <tf_conversions/tf_eigen.h>
00061 
00062 
00063 #include <costmap_2d/costmap_2d_ros.h>
00064 
00065 
00066 #include <Eigen/Core>
00067 #include <Eigen/Geometry>
00068 
00069 
00070 namespace eband_local_planner{
00071 
00076 class EBandVisualization{
00077 
00078         public:
00079 
00080                 
00081                 enum Color {blue, red, green};
00082 
00083 
00084                 
00085 
00089                 EBandVisualization();
00090 
00094                 EBandVisualization(ros::NodeHandle& pn, costmap_2d::Costmap2DROS* costmap_ros);
00095 
00099                 ~EBandVisualization();
00100 
00105                 void initialize(ros::NodeHandle& pn, costmap_2d::Costmap2DROS* costmap_ros);
00106 
00113                 void publishBand(std::string marker_name_space, std::vector<Bubble> band);
00114 
00121                 void publishBubble(std::string marker_name_space, int marker_id, Bubble bubble);
00122 
00130                 void publishBubble(std::string marker_name_space, int marker_id, Color marker_color, Bubble bubble);
00131 
00139                 void publishForceList(std::string marker_name_space, std::vector<geometry_msgs::WrenchStamped> forces, std::vector<Bubble> band);
00140 
00147                 void publishForce(std::string marker_name_space, int id, Color marker_color, geometry_msgs::WrenchStamped force, Bubble bubble);
00148 
00149         private:
00150                 
00151                 
00152                 costmap_2d::Costmap2DROS* costmap_ros_; 
00153 
00154                 
00155                 ros::Publisher bubble_pub_; 
00156                 ros::Publisher one_bubble_pub_; 
00157 
00158                 
00159                 bool initialized_;
00160 
00161                 
00162                 double marker_lifetime_;
00163 
00164 
00165                 
00166 
00174                 void bubbleToMarker(Bubble bubble, visualization_msgs::Marker& marker, std::string marker_name_space, int marker_id, Color marker_color);
00175 
00183                 void bubbleHeadingToMarker(Bubble bubble, visualization_msgs::Marker& marker, std::string marker_name_space, int marker_id, Color marker_color);
00184 
00194                 void forceToMarker(geometry_msgs::WrenchStamped wrench, geometry_msgs::Pose wrench_origin, visualization_msgs::Marker& marker, std::string marker_name_space, int marker_id, Color marker_color);
00195 
00196 };
00197 };
00198 #endif