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 {
17 
19  {
21  new rviz::ColorProperty( "Color", QColor(204, 41, 204),
22  "Color of a point",
23  this, SLOT( updateColorAndAlpha() ));
24 
26  new rviz::FloatProperty( "Alpha", 1.0,
27  "0 is fully transparent, 1.0 is fully opaque.",
28  this, SLOT( updateColorAndAlpha() ));
29 
31  new rviz::FloatProperty( "Radius", 0.2,
32  "Radius of a point",
33  this, SLOT( updateColorAndAlpha() ));
34 
36  new rviz::IntProperty( "History Length", 1,
37  "Number of prior measurements to display.",
38  this, SLOT( updateHistoryLength() ));
41  }
42 
44  {
47  }
48 
50  {
51  }
52 
53  // Clear the visuals by deleting their objects.
55  {
57  visuals_.clear();
58  }
59 
60  // Set the current color and alpha values for each visual.
62  {
63  float alpha = alpha_property_->getFloat();
64  float radius = radius_property_->getFloat();
65  Ogre::ColourValue color = color_property_->getOgreColor();
66 
67  for( size_t i = 0; i < visuals_.size(); i++ )
68  {
69  visuals_[i]->setColor( color.r, color.g, color.b, alpha );
70  visuals_[i]->setRadius( radius );
71  }
72  }
73 
74  // Set the number of past visuals to show.
76  {
77  visuals_.rset_capacity(history_length_property_->getInt());
78  }
79 
80  // This is our callback to handle an incoming message.
81  void PointStampedDisplay::processMessage( const geometry_msgs::PointStamped::ConstPtr& msg )
82  {
83 
84  if( !rviz::validateFloats( msg->point ))
85  {
86  setStatus( rviz::StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)" );
87  return;
88  }
89 
90  // Here we call the rviz::FrameManager to get the transform from the
91  // fixed frame to the frame in the header of this Point message. If
92  // it fails, we can't do anything else so we return.
93  Ogre::Quaternion orientation;
94  Ogre::Vector3 position;
95  if( !context_->getFrameManager()->getTransform( msg->header.frame_id,
96  msg->header.stamp,
97  position, orientation ))
98  {
99  ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'",
100  msg->header.frame_id.c_str(), qPrintable( fixed_frame_ ) );
101  return;
102  }
103 
104  // We are keeping a circular buffer of visual pointers. This gets
105  // the next one, or creates and stores it if the buffer is not full
107  if( visuals_.full() )
108  {
109  visual = visuals_.front();
110  }
111  else
112  {
113  visual.reset(new PointStampedVisual( context_->getSceneManager(), scene_node_ ));
114  }
115 
116 
117  // Now set or update the contents of the chosen visual.
118  visual->setMessage( msg );
119  visual->setFramePosition( position );
120  visual->setFrameOrientation( orientation );
121  float alpha = alpha_property_->getFloat();
122  float radius = radius_property_->getFloat();
123  Ogre::ColourValue color = color_property_->getOgreColor();
124  visual->setColor( color.r, color.g, color.b, alpha);
125  visual->setRadius( radius );
126 
127 
128  // And send it to the end of the circular buffer
129  visuals_.push_back(visual);
130  }
131 
132 } // end namespace rviz
133 
134 // Tell pluginlib about this class. It is important to do this in
135 // global scope, outside our package's namespace.
138 
139 
Ogre::ColourValue getOgreColor() const
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
Definition: display.h:256
virtual int getInt() const
Return the internal property value as an integer.
Definition: int_property.h:73
virtual float getFloat() const
boost::circular_buffer< boost::shared_ptr< PointStampedVisual > > visuals_
Definition: point_display.h:54
void setMin(int min)
virtual void reset()
Called to tell the display to clear its state.
Property specialized to enforce floating point max/min.
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:38
rviz::FloatProperty * alpha_property_
Definition: point_display.h:58
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:264
void setMax(int max)
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:281
bool validateFloats(const sensor_msgs::CameraInfo &msg)
rviz::FloatProperty * radius_property_
Definition: point_display.h:58
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
rviz::IntProperty * history_length_property_
Definition: point_display.h:59
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
virtual void onInitialize()
Override this function to do subclass-specific initialization.
void processMessage(const geometry_msgs::PointStamped::ConstPtr &msg)
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.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
Definition: display.cpp:186
rviz::ColorProperty * color_property_
Definition: point_display.h:57
#define ROS_DEBUG(...)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51