point_display.cpp
Go to the documentation of this file.
1 #include <OgreSceneNode.h>
2 #include <OgreSceneManager.h>
3 
8 #include <rviz/frame_manager.h>
9 #include <rviz/validate_floats.h>
10 
11 #include "point_visual.h"
12 
13 #include "point_display.h"
14 
15 namespace rviz
16 {
18 {
19  color_property_ = new rviz::ColorProperty("Color", QColor(204, 41, 204), "Color of a point", this,
21 
22  alpha_property_ = new rviz::FloatProperty("Alpha", 1.0, "0 is fully transparent, 1.0 is fully opaque.",
24 
25  radius_property_ = new rviz::FloatProperty("Radius", 0.2, "Radius of a point", this,
27 
29  new rviz::IntProperty("History Length", 1, "Number of prior measurements to display.", this,
33 }
34 
36 {
39 }
40 
42 {
43 }
44 
45 // Clear the visuals by deleting their objects.
47 {
49  visuals_.clear();
50 }
51 
52 // Set the current color and alpha values for each visual.
54 {
55  float alpha = alpha_property_->getFloat();
56  float radius = radius_property_->getFloat();
57  Ogre::ColourValue color = color_property_->getOgreColor();
58 
59  for (size_t i = 0; i < visuals_.size(); i++)
60  {
61  visuals_[i]->setColor(color.r, color.g, color.b, alpha);
62  visuals_[i]->setRadius(radius);
63  }
64 }
65 
66 // Set the number of past visuals to show.
68 {
69  visuals_.rset_capacity(history_length_property_->getInt());
70 }
71 
72 // This is our callback to handle an incoming message.
73 void PointStampedDisplay::processMessage(const geometry_msgs::PointStamped::ConstPtr& msg)
74 {
75  if (!rviz::validateFloats(msg->point))
76  {
78  "Message contained invalid floating point values (nans or infs)");
79  return;
80  }
81 
82  // Here we call the rviz::FrameManager to get the transform from the
83  // fixed frame to the frame in the header of this Point message. If
84  // it fails, we can't do anything else so we return.
85  Ogre::Quaternion orientation;
86  Ogre::Vector3 position;
87  if (!context_->getFrameManager()->getTransform(msg->header.frame_id, msg->header.stamp, position,
88  orientation))
89  {
90  ROS_DEBUG("Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(),
91  qPrintable(fixed_frame_));
92  return;
93  }
94 
95  // We are keeping a circular buffer of visual pointers. This gets
96  // the next one, or creates and stores it if the buffer is not full
98  if (visuals_.full())
99  {
100  visual = visuals_.front();
101  }
102  else
103  {
105  }
106 
107 
108  // Now set or update the contents of the chosen visual.
109  float radius = radius_property_->getFloat();
110  visual->setRadius(radius); // has to be set before setting message
111  visual->setMessage(msg);
112  visual->setFramePosition(position);
113  visual->setFrameOrientation(orientation);
114  float alpha = alpha_property_->getFloat();
115  Ogre::ColourValue color = color_property_->getOgreColor();
116  visual->setColor(color.r, color.g, color.b, alpha);
117 
118 
119  // And send it to the end of the circular buffer
120  visuals_.push_back(visual);
121 }
122 
123 } // end namespace rviz
124 
125 // Tell pluginlib about this class. It is important to do this in
126 // global scope, outside our package's namespace.
rviz::IntProperty::setMin
void setMin(int min)
Definition: int_property.cpp:52
rviz::MessageFilterDisplay< geometry_msgs::PointStamped >::reset
void reset() override
Definition: message_filter_display.h:125
validate_floats.h
frame_manager.h
rviz::PointStampedDisplay::updateColorAndAlpha
void updateColorAndAlpha()
Definition: point_display.cpp:53
boost::shared_ptr
rviz::StatusProperty::Error
@ Error
Definition: status_property.h:46
rviz::PointStampedVisual
Definition: point_visual.h:19
int_property.h
rviz::PointStampedDisplay::history_length_property_
rviz::IntProperty * history_length_property_
Definition: point_display.h:58
rviz::validateFloats
bool validateFloats(const sensor_msgs::CameraInfo &msg)
Definition: camera_display.cpp:72
float_property.h
rviz::Display::fixed_frame_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:312
rviz::DisplayContext::getSceneManager
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
rviz::ColorProperty
Definition: color_property.h:40
rviz::Display
Definition: display.h:63
rviz::FloatProperty
Property specialized to enforce floating point max/min.
Definition: float_property.h:37
rviz::Display::setStatus
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
Definition: display.cpp:176
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rviz::FloatProperty::getFloat
virtual float getFloat() const
Definition: float_property.h:79
ROS_DEBUG
#define ROS_DEBUG(...)
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::Display::scene_node_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:295
color_property.h
rviz::IntProperty::setMax
void setMax(int max)
Definition: int_property.cpp:58
rviz::PointStampedDisplay::color_property_
rviz::ColorProperty * color_property_
Definition: point_display.h:56
rviz::PointStampedDisplay::updateHistoryLength
void updateHistoryLength()
Definition: point_display.cpp:67
rviz::DisplayContext::getFrameManager
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
rviz::PointStampedDisplay::processMessage
void processMessage(const geometry_msgs::PointStamped::ConstPtr &msg) override
Definition: point_display.cpp:73
rviz::PointStampedDisplay
Definition: point_display.h:28
point_display.h
rviz::PointStampedDisplay::radius_property_
rviz::FloatProperty * radius_property_
Definition: point_display.h:57
visualization_manager.h
rviz::MessageFilterDisplay< geometry_msgs::PointStamped >::onInitialize
void onInitialize() override
Definition: message_filter_display.h:105
rviz::FrameManager::getTransform
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Return the pose for a header, relative to the fixed frame, in Ogre classes.
Definition: frame_manager.h:125
rviz::Display::context_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
Definition: display.h:287
rviz::PointStampedDisplay::PointStampedDisplay
PointStampedDisplay()
Definition: point_display.cpp:17
class_list_macros.hpp
rviz::IntProperty::getInt
virtual int getInt() const
Return the internal property value as an integer.
Definition: int_property.h:96
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
point_visual.h
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::ColorProperty::getOgreColor
Ogre::ColourValue getOgreColor() const
Definition: color_property.h:83
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