covariance_visual.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, Ellon Paiva Mendes @ LAAS-CNRS
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  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef COVARIANCE_VISUAL_H
31 #define COVARIANCE_VISUAL_H
32 
33 #include <cmath>
34 
36 
37 #include <boost/scoped_ptr.hpp>
38 
39 #include <geometry_msgs/PoseWithCovariance.h>
40 
41 #include <Eigen/Dense>
42 
43 #include <OgreVector3.h>
44 #include <OgreColourValue.h>
45 
46 namespace Ogre
47 {
48 class SceneManager;
49 class SceneNode;
50 class Any;
51 } // namespace Ogre
52 
53 namespace Eigen
54 {
55 typedef Matrix<double, 6, 6> Matrix6d;
56 }
57 
58 namespace rviz
59 {
60 class Shape;
61 class CovarianceProperty;
62 
69 {
70 public:
72  {
73  kRoll = 0,
74  kPitch = 1,
75  kYaw = 2,
76  kYaw2D = 3,
77  kNumOriShapes
78  };
79 
80 public:
91  CovarianceVisual(Ogre::SceneManager* scene_manager,
92  Ogre::SceneNode* parent_node,
93  bool is_local_rotation,
94  bool is_visible = true,
95  float pos_scale = 1.0f,
96  float ori_scale = 0.1f,
97  float ori_offset = 0.1f);
98  ~CovarianceVisual() override;
99 
106  void setScales(float pos_scale, float ori_scale);
107  void setPositionScale(float pos_scale);
108  void setOrientationOffset(float ori_offset);
109  void setOrientationScale(float ori_scale);
110 
118  virtual void setPositionColor(float r, float g, float b, float a);
119  void setPositionColor(const Ogre::ColourValue& color);
120 
128  virtual void setOrientationColor(float r, float g, float b, float a);
129  void setOrientationColor(const Ogre::ColourValue& color);
130  void setOrientationColorToRGB(float a);
131 
137  virtual void setCovariance(const geometry_msgs::PoseWithCovariance& pose);
138 
139  virtual const Ogre::Vector3& getPositionCovarianceScale();
140  virtual const Ogre::Quaternion& getPositionCovarianceOrientation();
141 
146  Ogre::SceneNode* getPositionSceneNode()
147  {
148  return position_scale_node_;
149  }
150 
155  Ogre::SceneNode* getOrientationSceneNode()
156  {
157  return orientation_root_node_;
158  }
159 
165  {
166  return position_shape_;
167  }
168 
173  rviz::Shape* getOrientationShape(ShapeIndex index);
174 
178  void setUserData(const Ogre::Any& data) override;
179 
185  virtual void setVisible(bool visible);
186 
190  virtual void setPositionVisible(bool visible);
191 
195  virtual void setOrientationVisible(bool visible);
196 
200  void setPosition(const Ogre::Vector3& position) override;
201 
205  void setOrientation(const Ogre::Quaternion& orientation) override;
206 
210  virtual void setRotatingFrame(bool use_rotating_frame);
211 
212 private:
213  void updatePosition(const Eigen::Matrix6d& covariance);
214  void updateOrientation(const Eigen::Matrix6d& covariance, ShapeIndex index);
215  void updateOrientationVisibility();
216 
217  Ogre::SceneNode* root_node_;
218  Ogre::SceneNode* fixed_orientation_node_;
219  Ogre::SceneNode* position_scale_node_;
220  Ogre::SceneNode* position_node_;
221 
222  Ogre::SceneNode* orientation_root_node_;
223  Ogre::SceneNode* orientation_offset_node_[kNumOriShapes];
224 
226  rviz::Shape* orientation_shape_[kNumOriShapes];
227 
229 
230  bool pose_2d_;
231 
233 
234  Ogre::Vector3 current_ori_scale_[kNumOriShapes];
236 
237  const static float max_degrees;
238 
239 private:
240  // Hide Object methods we don't want to expose
241  // NOTE: Apparently we still need to define them...
242  void setScale(const Ogre::Vector3& /*scale*/) override
243  {
244  }
245  void setColor(float /*r*/, float /*g*/, float /*b*/, float /*a*/) override
246  {
247  }
248  const Ogre::Vector3& getPosition() override;
249  const Ogre::Quaternion& getOrientation() override;
250 
251  // Make CovarianceProperty friend class so it create CovarianceVisual objects
252  friend class CovarianceProperty;
253 };
254 
255 } // namespace rviz
256 
257 #endif /* COVARIANCE_VISUAL_H */
CovarianceVisual consisting in a ellipse for position and 2D ellipses along the axis for orientation...
Ogre::SceneNode * position_node_
void setColor(float, float, float, float) override
Set the color of the object. Values are in the range [0, 1].
void setVisible(PanelDockWidget *widget, bool visible)
Definition: display.cpp:293
Ogre::SceneNode * getPositionSceneNode()
Get the root scene node of the position part of this covariance.
Base class for visible objects, providing a minimal generic interface.
Definition: object.h:50
Ogre::SceneNode * orientation_root_node_
Matrix< double, 6, 6 > Matrix6d
Ogre::SceneNode * fixed_orientation_node_
bool orientation_visible_
If the orientation component is visible.
Ogre::SceneNode * position_scale_node_
rviz::Shape * getPositionShape()
Get the shape used to display position covariance.
Property specialized to provide getter for booleans.
void setScale(const Ogre::Vector3 &) override
Set the scale of the object. Always relative to the identity orientation of the object.
rviz::Shape * position_shape_
Ellipse used for the position covariance.
static const float max_degrees
Ogre::SceneNode * root_node_
Ogre::SceneNode * getOrientationSceneNode()
Get the root scene node of the orientation part of this covariance.


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:24