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 #include <eband_local_planner/EBandPlannerConfig.h>
00047
00048
00049 #include <geometry_msgs/Pose2D.h>
00050 #include <geometry_msgs/Pose.h>
00051 #include <geometry_msgs/PoseStamped.h>
00052 #include <geometry_msgs/Wrench.h>
00053 #include <geometry_msgs/WrenchStamped.h>
00054
00055 #include <visualization_msgs/Marker.h>
00056 #include <visualization_msgs/MarkerArray.h>
00057
00058
00059 #include <angles/angles.h>
00060 #include <tf/tf.h>
00061 #include <tf_conversions/tf_eigen.h>
00062
00063
00064 #include <costmap_2d/costmap_2d_ros.h>
00065
00066
00067 #include <Eigen/Core>
00068 #include <Eigen/Geometry>
00069
00070
00071 namespace eband_local_planner{
00072
00077 class EBandVisualization{
00078
00079 public:
00080
00081
00082 enum Color {blue, red, green};
00083
00084
00085
00086
00090 EBandVisualization();
00091
00095 EBandVisualization(ros::NodeHandle& pn, costmap_2d::Costmap2DROS* costmap_ros);
00096
00100 ~EBandVisualization();
00101
00106 void initialize(ros::NodeHandle& pn, costmap_2d::Costmap2DROS* costmap_ros);
00107
00112 void reconfigure(EBandPlannerConfig& config);
00113
00120 void publishBand(std::string marker_name_space, std::vector<Bubble> band);
00121
00128 void publishBubble(std::string marker_name_space, int marker_id, Bubble bubble);
00129
00137 void publishBubble(std::string marker_name_space, int marker_id, Color marker_color, Bubble bubble);
00138
00146 void publishForceList(std::string marker_name_space, std::vector<geometry_msgs::WrenchStamped> forces, std::vector<Bubble> band);
00147
00154 void publishForce(std::string marker_name_space, int id, Color marker_color, geometry_msgs::WrenchStamped force, Bubble bubble);
00155
00156 private:
00157
00158
00159 costmap_2d::Costmap2DROS* costmap_ros_;
00160
00161
00162 ros::Publisher bubble_pub_;
00163 ros::Publisher one_bubble_pub_;
00164
00165
00166 bool initialized_;
00167
00168
00169 double marker_lifetime_;
00170
00171
00172
00173
00181 void bubbleToMarker(Bubble bubble, visualization_msgs::Marker& marker, std::string marker_name_space, int marker_id, Color marker_color);
00182
00190 void bubbleHeadingToMarker(Bubble bubble, visualization_msgs::Marker& marker, std::string marker_name_space, int marker_id, Color marker_color);
00191
00201 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);
00202
00203 };
00204 };
00205 #endif