Visualizer.h
Go to the documentation of this file.
1 /*
2  * Visualizer.h
3  *
4  * Created on: May 8, 2012
5  * Author: sdries
6  */
7 
8 #ifndef VISUALIZER_H_
9 #define VISUALIZER_H_
10 
11 #include "ros/ros.h"
12 #include <visualization_msgs/Marker.h>
13 #include <visualization_msgs/MarkerArray.h>
14 
15 #include <wire_msgs/Property.h>
16 
17 #include "tf/transform_listener.h"
18 
19 #include "problib/conversions.h"
20 
21 
22 
23 #include <map>
24 
25 // Color struct
26 struct Color {
27  double r;
28  double g;
29  double b;
30 
31  Color() {};
32  Color(double red, double green, double blue) : r(red), g(green), b(blue) {};
33  };
34 
35 
36 class Visualizer {
37 
38 public:
39 
40  Visualizer();
41 
42  virtual ~Visualizer();
43 
44  bool setParameters(ros::NodeHandle& n, const std::string& ns);
45 
46  bool createMarkers(const std_msgs::Header& header, long ID,
47  const std::vector<wire_msgs::Property>& props,
48  std::vector<visualization_msgs::Marker>& markers_out,
49  const std::string& frame_id);
50 
51  void setTFListener(tf::TransformListener* tf_listener);
52 
53 protected:
54 
55  // Structure storing marker information
56  struct MarkerInfo {
57  visualization_msgs::Marker shape_marker;
58  visualization_msgs::Marker text_marker;
59  visualization_msgs::Marker cov_marker;
60  bool show_cov;
61  bool show_text;
62  };
63 
64  // Color mapping
65  std::map<std::string, Color> color_mapping_;
66 
67  // Tf listener
69 
70  // Mapping from object class to marker
71  std::map<std::string, MarkerInfo> object_class_to_marker_map_;
72 
73  // Mapping that defines per attribute if it has to be shown
74  std::map<std::string, bool> attribute_map_;
75 
76  // Get marker parameters
77  bool getMarkerParameters(ros::NodeHandle& n, const std::string& ns);
78 
79  // Get attribute settings
80  bool getAttributeSettings(ros::NodeHandle& n, const std::string& ns);
81 
82  // Get most probable Gaussian from a pdf
83  const pbl::Gaussian* getBestGaussian(const pbl::PDF& pdf, double min_weight = 0);
84 
85  // Set marker type
86  void setMarkerType(XmlRpc::XmlRpcValue& v, MarkerInfo& m);
87 
88  // Overloaded get value function
89  void getStructValue(XmlRpc::XmlRpcValue& s, const std::string& name, float& f, float default_value);
90  void getStructValue(XmlRpc::XmlRpcValue& s, const std::string& name, double& d, double default_value);
91  void getStructValue(XmlRpc::XmlRpcValue& s, const std::string& name, bool& b, bool default_value);
92  void getStructValue(XmlRpc::XmlRpcValue& s, const std::string& name, std::string& str, const std::string& default_value);
93 };
94 
95 #endif /* VISUALIZER_H_ */
tf::TransformListener * tf_listener_
Definition: Visualizer.h:68
std::map< std::string, bool > attribute_map_
Definition: Visualizer.h:74
visualization_msgs::Marker shape_marker
Definition: Visualizer.h:57
double r
Definition: Visualizer.h:27
Color(double red, double green, double blue)
Definition: Visualizer.h:32
std::map< std::string, MarkerInfo > object_class_to_marker_map_
Definition: Visualizer.h:71
visualization_msgs::Marker text_marker
Definition: Visualizer.h:58
double b
Definition: Visualizer.h:29
double g
Definition: Visualizer.h:28
Color()
Definition: Visualizer.h:31
std::map< std::string, Color > color_mapping_
Definition: Visualizer.h:65
visualization_msgs::Marker cov_marker
Definition: Visualizer.h:59


wire_viz
Author(s): Sjoerd van den Dries, Jos Elfring
autogenerated on Fri Apr 16 2021 02:32:41