MarkerHelper.hpp
Go to the documentation of this file.
1 
20 #ifndef MARKER_HELPER_HPP_
21 #define MARKER_HELPER_HPP_
22 
23 #include <geometry_msgs/Pose.h>
24 #include <visualization_msgs/Marker.h>
25 #include "typedef.hpp"
27 
28 namespace next_best_view {
36  class MarkerHelper {
37  private:
38  MarkerHelper();
39  ~MarkerHelper();
40  public:
47  static visualization_msgs::Marker getBasicMarker(int id, std::string ns = "my_namespace");
48 
59  static visualization_msgs::Marker getBasicMarker(int id, SimpleVector3 position, SimpleQuaternion orientation,
60  SimpleVector3 scale, SimpleVector4 color, std::string ns = "my_namespace");
61 
70  static visualization_msgs::Marker getTextMarker(int id, std::string text, geometry_msgs::Pose pose, std::string ns = "my_namespace");
71 
78  static visualization_msgs::Marker getDeleteMarker(int id, std::string ns = "my_namespace");
79 
89  static visualization_msgs::Marker getMeshMarker(int id, std::string meshResource, SimpleVector3 centroid, SimpleQuaternion quaternion,
90  SimpleVector3 scale = SimpleVector3(0.001, 0.001, 0.001), std::string ns = "my_namespace");
91 
101  static visualization_msgs::Marker getArrowMarker(int id, SimpleVector3 startPoint, SimpleVector3 endPoint,
102  SimpleVector3 scale = SimpleVector3(0.025, 0.05, 0.05),
103  SimpleVector4 color = SimpleVector4(1.0, 0.0, 0.0, 1.0),
104  std::string ns = "my_namespace");
105 
116  static visualization_msgs::Marker getArrowMarker(int id, SimpleVector3 position, SimpleQuaternion orientation,
117  SimpleVector3 scale, SimpleVector4 color, std::string ns = "my_namespace");
118 
129  static visualization_msgs::Marker getCubeMarker(int id, SimpleVector3 position, SimpleQuaternion orientation,
130  SimpleVector3 scale, SimpleVector4 color, std::string ns = "my_namespace");
131 
141  static visualization_msgs::Marker getSphereMarker(int id, SimpleVector3 position, SimpleVector3 scale,
142  SimpleVector4 color, std::string ns = "my_namespace");
143 
153  static visualization_msgs::Marker getLineListMarker(int id, std::vector<SimpleVector3> points, double scale,
154  SimpleVector4 color, std::string ns = "my_namespace");
155 
166  static visualization_msgs::Marker getCylinderMarker(int id, SimpleVector3 position, double w, SimpleVector3 scale,
167  SimpleVector4 color, std::string ns = "my_namespace");
168 
169  static visualization_msgs::Marker getTriangleListMarker(int id, std::vector<SimpleVector3> vertices, std::vector<SimpleVector4> colors,
170  std::string ns = "my_namespace");
171 
177  static void getRainbowColor(visualization_msgs::Marker &marker, double x, double alpha = 1.0);
178  };
179 }
180 
181 
182 #endif /* MARKER_HELPER_HPP_ */
static visualization_msgs::Marker getTriangleListMarker(int id, std::vector< SimpleVector3 > vertices, std::vector< SimpleVector4 > colors, std::string ns="my_namespace")
static visualization_msgs::Marker getDeleteMarker(int id, std::string ns="my_namespace")
returns a marker which will delete the corresponding marker with the same id and namespace ...
static visualization_msgs::Marker getCubeMarker(int id, SimpleVector3 position, SimpleQuaternion orientation, SimpleVector3 scale, SimpleVector4 color, std::string ns="my_namespace")
returns a cube marker with the given settings
Eigen::Matrix< Precision, 3, 1 > SimpleVector3
Definition: typedef.hpp:53
static visualization_msgs::Marker getCylinderMarker(int id, SimpleVector3 position, double w, SimpleVector3 scale, SimpleVector4 color, std::string ns="my_namespace")
returns a cylinder marker with the given settings
Eigen::Matrix< Precision, 4, 1 > SimpleVector4
Definition: typedef.hpp:55
this namespace contains all generally usable classes.
TFSIMD_FORCE_INLINE const tfScalar & x() const
MarkerHelper is a convenience class to reduce the mess created if marker initialization is used by ha...
static visualization_msgs::Marker getBasicMarker(int id, std::string ns="my_namespace")
returns a marker with basic settings
TFSIMD_FORCE_INLINE const tfScalar & w() const
static visualization_msgs::Marker getArrowMarker(int id, SimpleVector3 startPoint, SimpleVector3 endPoint, SimpleVector3 scale=SimpleVector3(0.025, 0.05, 0.05), SimpleVector4 color=SimpleVector4(1.0, 0.0, 0.0, 1.0), std::string ns="my_namespace")
returns an arrow marker with the given settings
static void getRainbowColor(visualization_msgs::Marker &marker, double x, double alpha=1.0)
static visualization_msgs::Marker getLineListMarker(int id, std::vector< SimpleVector3 > points, double scale, SimpleVector4 color, std::string ns="my_namespace")
returns a line list marker with the given settings
Eigen::Quaternion< Precision > SimpleQuaternion
Definition: typedef.hpp:67
static visualization_msgs::Marker getTextMarker(int id, std::string text, geometry_msgs::Pose pose, std::string ns="my_namespace")
returns a text marker with the given settings
static visualization_msgs::Marker getSphereMarker(int id, SimpleVector3 position, SimpleVector3 scale, SimpleVector4 color, std::string ns="my_namespace")
returns a sphere marker with the given settings
static visualization_msgs::Marker getMeshMarker(int id, std::string meshResource, SimpleVector3 centroid, SimpleQuaternion quaternion, SimpleVector3 scale=SimpleVector3(0.001, 0.001, 0.001), std::string ns="my_namespace")
returns a mesh marker with the given settings


asr_next_best_view
Author(s): Aumann Florian, Borella Jocelyn, Heller Florian, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
autogenerated on Thu Jan 9 2020 07:20:18