point_display.h
Go to the documentation of this file.
1 #ifndef POINT_DISPLAY_H
2 #define POINT_DISPLAY_H
3 
4 #ifndef Q_MOC_RUN
5 #include <boost/circular_buffer.hpp>
6 #endif
7 
8 #include <geometry_msgs/PointStamped.h>
10 
11 
12 namespace Ogre
13 {
14 class SceneNode;
15 }
16 
17 namespace rviz
18 {
19 class ColorProperty;
20 class FloatProperty;
21 class IntProperty;
22 } // namespace rviz
23 
24 namespace rviz
25 {
26 class PointStampedVisual;
27 
28 class PointStampedDisplay : public rviz::MessageFilterDisplay<geometry_msgs::PointStamped>
29 {
30  Q_OBJECT
31 public:
32  // Constructor. pluginlib::ClassLoader creates instances by calling
33  // the default constructor, so make sure you have one.
35  ~PointStampedDisplay() override;
36 
37 protected:
38  // Overrides of public virtual functions from the Display class.
39  void onInitialize() override;
40  void reset() override;
41 
42 private Q_SLOTS:
43  // Helper function to apply color and alpha to all visuals.
44  void updateColorAndAlpha();
45  void updateHistoryLength();
46 
47  // Function to handle an incoming ROS message.
48 private:
49  void processMessage(const geometry_msgs::PointStamped::ConstPtr& msg) override;
50 
51  // Storage for the list of visuals. It is a circular buffer where
52  // data gets popped from the front (oldest) and pushed to the back (newest)
53  boost::circular_buffer<boost::shared_ptr<PointStampedVisual> > visuals_;
54 
55  // Property objects for user-editable properties.
59 };
60 } // namespace rviz
61 
62 #endif // POINT_DISPLAY_H
rviz::MessageFilterDisplay
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
Definition: message_filter_display.h:90
Ogre
Definition: axes_display.h:35
rviz::PointStampedDisplay::updateColorAndAlpha
void updateColorAndAlpha()
Definition: point_display.cpp:53
message_filter_display.h
rviz::PointStampedDisplay::history_length_property_
rviz::IntProperty * history_length_property_
Definition: point_display.h:58
rviz::ColorProperty
Definition: color_property.h:40
rviz::FloatProperty
Property specialized to enforce floating point max/min.
Definition: float_property.h:37
rviz::PointStampedDisplay::onInitialize
void onInitialize() override
Override this function to do subclass-specific initialization.
Definition: point_display.cpp:35
rviz
Definition: add_display_dialog.cpp:54
rviz::PointStampedDisplay::color_property_
rviz::ColorProperty * color_property_
Definition: point_display.h:56
rviz::PointStampedDisplay::updateHistoryLength
void updateHistoryLength()
Definition: point_display.cpp:67
rviz::PointStampedDisplay::processMessage
void processMessage(const geometry_msgs::PointStamped::ConstPtr &msg) override
Definition: point_display.cpp:73
rviz::PointStampedDisplay
Definition: point_display.h:28
rviz::PointStampedDisplay::radius_property_
rviz::FloatProperty * radius_property_
Definition: point_display.h:57
rviz::PointStampedDisplay::PointStampedDisplay
PointStampedDisplay()
Definition: point_display.cpp:17
rviz::PointStampedDisplay::reset
void reset() override
Called to tell the display to clear its state.
Definition: point_display.cpp:46
rviz::PointStampedDisplay::~PointStampedDisplay
~PointStampedDisplay() override
Definition: point_display.cpp:41
rviz::PointStampedDisplay::visuals_
boost::circular_buffer< boost::shared_ptr< PointStampedVisual > > visuals_
Definition: point_display.h:53
rviz::PointStampedDisplay::alpha_property_
rviz::FloatProperty * alpha_property_
Definition: point_display.h:57
rviz::IntProperty
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:37


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:53