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 #include "DrawInterface.h"
30 //#include "util/UtilFunctions.h"
31 
32 #include "ros/ros.h"
33 
34 #include <Eigen/Geometry>
35 #include <Eigen/Dense>
36 
37 
38 #include <visualization_msgs/MarkerArray.h>
39 
41 {
42 public:
43 
45  {
46  idCounter = 0;
47  maxId = 0;
48 
49  ros::NodeHandle nh_;
50 
51  markerPublisher_ = nh_.advertise<visualization_msgs::Marker>("visualization_marker", 1, true);
52  markerArrayPublisher_ = nh_.advertise<visualization_msgs::MarkerArray>("visualization_marker_array", 1, true);
53 
54  tempMarker.header.frame_id = "map";
55  tempMarker.ns = "marker";
56 
57  this->setScale(1.0);
58  this->setColor(1.0, 1.0, 1.0);
59 
60  tempMarker.action = visualization_msgs::Marker::ADD;
61  };
62 
63  virtual void setNamespace(const std::string& ns)
64  {
65  tempMarker.ns = ns;
66  }
67 
68  virtual void drawPoint(const Eigen::Vector2f& pointWorldFrame)
69  {
70  tempMarker.id = idCounter++;
71 
72  tempMarker.pose.position.x = pointWorldFrame.x();
73  tempMarker.pose.position.y = pointWorldFrame.y();
74 
75  tempMarker.pose.orientation.w = 0.0;
76  tempMarker.pose.orientation.z = 0.0;
77  tempMarker.type = visualization_msgs::Marker::CUBE;
78 
79  //markerPublisher_.publish(tempMarker);
80 
81  markerArray.markers.push_back(tempMarker);
82  }
83 
84  virtual void drawArrow(const Eigen::Vector3f& poseWorld)
85  {
86  tempMarker.id = idCounter++;
87 
88  tempMarker.pose.position.x = poseWorld.x();
89  tempMarker.pose.position.y = poseWorld.y();
90 
91  tempMarker.pose.orientation.w = cos(poseWorld.z()*0.5f);
92  tempMarker.pose.orientation.z = sin(poseWorld.z()*0.5f);
93 
94  tempMarker.type = visualization_msgs::Marker::ARROW;
95 
96  //markerPublisher_.publish(tempMarker);
97 
98  markerArray.markers.push_back(tempMarker);
99 
100  }
101 
102  virtual void drawCovariance(const Eigen::Vector2f& mean, const Eigen::Matrix2f& covMatrix)
103  {
104 
105  tempMarker.pose.position.x = mean[0];
106  tempMarker.pose.position.y = mean[1];
107 
108  Eigen::SelfAdjointEigenSolver<Eigen::Matrix2f> eig(covMatrix);
109 
110  const Eigen::Vector2f& eigValues (eig.eigenvalues());
111  const Eigen::Matrix2f& eigVectors (eig.eigenvectors());
112 
113  float angle = (atan2(eigVectors(1, 0), eigVectors(0, 0)));
114 
115  tempMarker.type = visualization_msgs::Marker::CYLINDER;
116 
117  double lengthMajor = sqrt(eigValues[0]);
118  double lengthMinor = sqrt(eigValues[1]);
119 
120  tempMarker.scale.x = lengthMajor;
121  tempMarker.scale.y = lengthMinor;
122  tempMarker.scale.z = 0.001;
123 
124 
125  tempMarker.pose.orientation.w = cos(angle*0.5);
126  tempMarker.pose.orientation.z = sin(angle*0.5);
127 
128  tempMarker.id = idCounter++;
129  markerArray.markers.push_back(tempMarker);
130  }
131 
132  virtual void drawCovariance(const Eigen::Vector3f& mean, const Eigen::Matrix3f& covMatrix)
133  {
134  tempMarker.type = visualization_msgs::Marker::SPHERE;
135 
136  tempMarker.color.r = 0.0;
137  tempMarker.color.a = 0.5;
138 
139  tempMarker.pose.position.x = mean[0];
140  tempMarker.pose.position.y = mean[1];
141  tempMarker.pose.position.z = mean[2];
142 
143  Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eig(covMatrix);
144 
145  const Eigen::Vector3f& eigValues (eig.eigenvalues());
146  const Eigen::Matrix3f& eigVectors (eig.eigenvectors());
147 
148 
149  Eigen::Matrix3f eigVectorsFlipped;
150  eigVectorsFlipped.col(0) = eigVectors.col(2);
151  eigVectorsFlipped.col(1) = eigVectors.col(1);
152  eigVectorsFlipped.col(2) = eigVectors.col(0);
153 
154  if (eigVectorsFlipped.determinant() < 0){
155  eigVectorsFlipped.col(2) = -eigVectorsFlipped.col(2);
156  }
157 
158  Eigen::Quaternionf quaternion (eigVectorsFlipped);
159 
160  //std::cout << "\neigVec:\n" << eigVectors << "\n";
161  //std::cout << "\neigVecFlipped:\n" << eigVectorsFlipped << "\n";
162 
163  //std::cout << "\now:" << quaternion.w() << " x:" << quaternion.x() << " y:" << quaternion.y() << " z:" << quaternion.z() << "\n";
164 
165 
166  tempMarker.pose.orientation.w = quaternion.w();
167  tempMarker.pose.orientation.x = quaternion.x();
168  tempMarker.pose.orientation.y = quaternion.y();
169  tempMarker.pose.orientation.z = quaternion.z();
170 
171  tempMarker.scale.x = sqrt(eigValues[2]);
172  tempMarker.scale.y = sqrt(eigValues[1]);
173  tempMarker.scale.z = sqrt(eigValues[0]);
174 
175  tempMarker.id = idCounter++;
176  markerArray.markers.push_back(tempMarker);
177 
178 
179  }
180 
181  virtual void setScale(double scale)
182  {
183  tempMarker.scale.x = scale;
184  tempMarker.scale.y = scale;
185  tempMarker.scale.z = scale;
186  }
187 
188  virtual void setColor(double r, double g, double b, double a = 1.0)
189  {
190  tempMarker.color.r = r;
191  tempMarker.color.g = g;
192  tempMarker.color.b = b;
193  tempMarker.color.a = a;
194  }
195 
196  virtual void addMarker(visualization_msgs::Marker marker) {
197  if (marker.id == 0) marker.id = idCounter++;
198  if (marker.ns.empty()) marker.ns = tempMarker.ns;
199  markerArray.markers.push_back(marker);
200  }
201 
202  virtual void addMarkers(visualization_msgs::MarkerArray markers) {
203  for(visualization_msgs::MarkerArray::_markers_type::iterator it = markers.markers.begin(); it != markers.markers.end(); ++it) {
204  visualization_msgs::Marker &marker = *it;
205  addMarker(marker);
206  }
207  }
208 
209  virtual void sendAndResetData()
210  {
211  allMarkers.markers.insert(allMarkers.markers.end(), markerArray.markers.begin(), markerArray.markers.end());
213  markerArray.markers.clear();
214  if (idCounter > maxId) maxId = idCounter;
215  idCounter = 0;
216  }
217 
218  void setTime(const ros::Time& time)
219  {
220  tempMarker.header.stamp = time;
221  }
222 
223  void reset()
224  {
225  for(visualization_msgs::MarkerArray::_markers_type::iterator it = allMarkers.markers.begin(); it != allMarkers.markers.end(); ++it)
226  {
227  it->action = visualization_msgs::Marker::DELETE;
228  }
230  allMarkers.markers.clear();
231  }
232 
235 
236  visualization_msgs::Marker tempMarker;
237  visualization_msgs::MarkerArray markerArray;
238  visualization_msgs::MarkerArray allMarkers;
239 
241  int maxId;
242 };
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
virtual void drawCovariance(const Eigen::Vector3f &mean, const Eigen::Matrix3f &covMatrix)
virtual void setNamespace(const std::string &ns)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual void addMarker(visualization_msgs::Marker marker)
virtual void drawCovariance(const Eigen::Vector2f &mean, const Eigen::Matrix2f &covMatrix)
virtual void addMarkers(visualization_msgs::MarkerArray markers)
visualization_msgs::MarkerArray allMarkers
virtual void setColor(double r, double g, double b, double a=1.0)
void setTime(const ros::Time &time)
ros::Publisher markerArrayPublisher_
virtual void drawArrow(const Eigen::Vector3f &poseWorld)
ros::Publisher markerPublisher_


hector_marker_drawing
Author(s): Stefan Kohlbrecher
autogenerated on Sun Nov 3 2019 03:18:36