HectorDrawings.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef HECTOR_DRAWINGS_H__
30 #define HECTOR_DRAWINGS_H__
31 
32 #include "util/DrawInterface.h"
33 #include "util/UtilFunctions.h"
34 
35 #include "ros/ros.h"
36 
37 #include <visualization_msgs/MarkerArray.h>
38 
39 #include <Eigen/Dense>
40 
41 
43 {
44 public:
45 
47  {
48  idCounter = 0;
49 
50  ros::NodeHandle nh_;
51 
52  markerPublisher_ = nh_.advertise<visualization_msgs::Marker>("visualization_marker", 1, true);
53  markerArrayPublisher_ = nh_.advertise<visualization_msgs::MarkerArray>("visualization_marker_array", 1, true);
54 
55  tempMarker.header.frame_id = "map";
56  tempMarker.ns = "slam";
57 
58  this->setScale(1.0);
59  this->setColor(1.0, 1.0, 1.0);
60 
61  tempMarker.action = visualization_msgs::Marker::ADD;
62  };
63 
64  virtual void drawPoint(const Eigen::Vector2f& pointWorldFrame)
65  {
66  tempMarker.id = idCounter++;
67 
68  tempMarker.pose.position.x = pointWorldFrame.x();
69  tempMarker.pose.position.y = pointWorldFrame.y();
70 
71  tempMarker.pose.orientation.w = 0.0;
72  tempMarker.pose.orientation.z = 0.0;
73  tempMarker.type = visualization_msgs::Marker::CUBE;
74 
75  //markerPublisher_.publish(tempMarker);
76 
77  markerArray.markers.push_back(tempMarker);
78  }
79 
80  virtual void drawArrow(const Eigen::Vector3f& poseWorld)
81  {
82  tempMarker.id = idCounter++;
83 
84  tempMarker.pose.position.x = poseWorld.x();
85  tempMarker.pose.position.y = poseWorld.y();
86 
87  tempMarker.pose.orientation.w = cos(poseWorld.z()*0.5f);
88  tempMarker.pose.orientation.z = sin(poseWorld.z()*0.5f);
89 
90  tempMarker.type = visualization_msgs::Marker::ARROW;
91 
92  //markerPublisher_.publish(tempMarker);
93 
94  markerArray.markers.push_back(tempMarker);
95 
96  }
97 
98  virtual void drawCovariance(const Eigen::Vector2f& mean, const Eigen::Matrix2f& covMatrix)
99  {
100  tempMarker.pose.position.x = mean[0];
101  tempMarker.pose.position.y = mean[1];
102 
103  Eigen::SelfAdjointEigenSolver<Eigen::Matrix2f> eig(covMatrix);
104 
105  const Eigen::Vector2f& eigValues (eig.eigenvalues());
106  const Eigen::Matrix2f& eigVectors (eig.eigenvectors());
107 
108  float angle = (atan2(eigVectors(1, 0), eigVectors(0, 0)));
109 
110  tempMarker.type = visualization_msgs::Marker::CYLINDER;
111 
112  double lengthMajor = sqrt(eigValues[0]);
113  double lengthMinor = sqrt(eigValues[1]);
114 
115  tempMarker.scale.x = lengthMajor;
116  tempMarker.scale.y = lengthMinor;
117  tempMarker.scale.z = 0.001;
118 
119 
120  tempMarker.pose.orientation.w = cos(angle*0.5);
121  tempMarker.pose.orientation.z = sin(angle*0.5);
122 
123  tempMarker.id = idCounter++;
124  markerArray.markers.push_back(tempMarker);
125 
126  //drawLine(Eigen::Vector3f(0,0,0), Eigen::Vector3f(lengthMajor ,0,0));
127  //drawLine(Eigen::Vector3f(0,0,0), Eigen::Vector3f(0,lengthMinor,0));
128 
129  //glScalef(lengthMajor, lengthMinor, 0);
130  //glCallList(dlCircle);
131  //this->popCS();
132  }
133 
134  virtual void setScale(double scale)
135  {
136  tempMarker.scale.x = scale;
137  tempMarker.scale.y = scale;
138  tempMarker.scale.z = scale;
139  }
140 
141  virtual void setColor(double r, double g, double b, double a = 1.0)
142  {
143  tempMarker.color.r = r;
144  tempMarker.color.g = g;
145  tempMarker.color.b = b;
146  tempMarker.color.a = a;
147  }
148 
149  virtual void sendAndResetData()
150  {
152  markerArray.markers.clear();
153  idCounter = 0;
154  }
155 
156  void setTime(const ros::Time& time)
157  {
158  tempMarker.header.stamp = time;
159  }
160 
161 
164 
165  visualization_msgs::Marker tempMarker;
166  visualization_msgs::MarkerArray markerArray;
167 
169 };
170 
171 #endif
visualization_msgs::MarkerArray markerArray
void publish(const boost::shared_ptr< M > &message) const
virtual void sendAndResetData()
virtual void setScale(double scale)
virtual void drawPoint(const Eigen::Vector2f &pointWorldFrame)
visualization_msgs::Marker tempMarker
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
virtual void drawCovariance(const Eigen::Vector2f &mean, const Eigen::Matrix2f &covMatrix)
virtual void setColor(double r, double g, double b, double a=1.0)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
void setTime(const ros::Time &time)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
ros::Publisher markerArrayPublisher_
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
virtual void drawArrow(const Eigen::Vector3f &poseWorld)
ros::Publisher markerPublisher_


hector_mapping
Author(s): Stefan Kohlbrecher
autogenerated on Sun Nov 3 2019 03:18:33