VoronoiSegmentDisplay.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Willow Garage, Inc.
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 VORONOISEGMENTDISPLAY_H
31 #define VORONOISEGMENTDISPLAY_H
32 
33 #include <boost/circular_buffer.hpp>
34 
36 #include <tuw_multi_robot_msgs/Graph.h>
37 
38 
39 #ifndef Q_MOC_RUN
40 #include <boost/circular_buffer.hpp>
41 
43 #include <nav_msgs/Path.h>
45 #endif
46 
47 
49 
50 namespace Ogre
51 {
52 class SceneNode;
53 }
54 
55 namespace rviz
56 {
57 class ColorProperty;
58 class EnumProperty;
59 class FloatProperty;
60 class IntProperty;
61 }
62 
63 // All the source in this plugin is in its own namespace. This is not
64 // required but is good practice.
65 namespace tuw_multi_robot_rviz
66 {
67 
68 class VoronoiSegmentVisual;
69 
70 // BEGIN_TUTORIAL
71 // Here we declare our new subclass of rviz::Display. Every display
72 // which can be listed in the "Displays" panel is a subclass of
73 // rviz::Display.
74 //
75 // ImuDisplay will show a 3D arrow showing the direction and magnitude
76 // of the IMU acceleration vector. The base of the arrow will be at
77 // the frame listed in the header of the Imu message, and the
78 // direction of the arrow will be relative to the orientation of that
79 // frame. It will also optionally show a history of recent
80 // acceleration vectors, which will be stored in a circular buffer.
81 //
82 // The ImuDisplay class itself just implements the circular buffer,
83 // editable parameters, and Display subclass machinery. The visuals
84 // themselves are represented by a separate class, ImuVisual. The
85 // idiom for the visuals is that when the objects exist, they appear
86 // in the scene, and when they are deleted, they disappear.
87 class VoronoiSegmentDisplay: public rviz::MessageFilterDisplay<tuw_multi_robot_msgs::Graph>
88 {
89 Q_OBJECT
90 public:
91  // Constructor. pluginlib::ClassLoader creates instances by calling
92  // the default constructor, so make sure you have one.
94  virtual ~VoronoiSegmentDisplay();
95 
96  // Overrides of protected virtual functions from Display. As much
97  // as possible, when Displays are not enabled, they should not be
98  // subscribed to incoming data and should not show anything in the
99  // 3D view. These functions are where these connections are made
100  // and broken.
101 protected:
102  virtual void onInitialize();
103 
104  // A helper to clear this display back to the initial state.
105  virtual void reset();
106 
107  // These Qt slots get connected to signals indicating changes in the user-editable properties.
108 private Q_SLOTS:
109  void updatePathColor();
110  void updatePathScale();
111 
112  void updateHistoryLength();
113 
114  // Function to handle an incoming ROS message.
115 private:
116  void processMessage( const tuw_multi_robot_msgs::Graph::ConstPtr& msg );
117 
118  // Storage for the list of visuals. It is a circular buffer where
119  // data gets popped from the front (oldest) and pushed to the back (newest)
120  boost::circular_buffer<boost::shared_ptr<VoronoiSegmentVisual> > visuals_;
121 
122 
123  // User-editable property variables.
128 
129  enum LineStyle {
131  BILLBOARDS
132  };
133 };
134 
135 } // end namespace rviz_plugin_tutorials
136 
137 #endif // IMU_DISPLAY_H
138 // %EndTag(FULL_SOURCE)%
boost::circular_buffer< boost::shared_ptr< VoronoiSegmentVisual > > visuals_


tuw_multi_robot_rviz
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:40