1 #include <OgreSceneNode.h> 2 #include <OgreSceneManager.h> 27 "0 is fully transparent, 1.0 is fully opaque.",
37 "Number of prior measurements to display.",
67 for(
size_t i = 0; i <
visuals_.size(); i++ )
69 visuals_[i]->setColor( color.r, color.g, color.b, alpha );
93 Ogre::Quaternion orientation;
94 Ogre::Vector3 position;
97 position, orientation ))
99 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'",
100 msg->header.frame_id.c_str(), qPrintable(
fixed_frame_ ) );
118 visual->setMessage( msg );
119 visual->setFramePosition( position );
120 visual->setFrameOrientation( orientation );
124 visual->setColor( color.r, color.g, color.b, alpha);
125 visual->setRadius( radius );
Ogre::ColourValue getOgreColor() const
virtual void onInitialize()
void updateColorAndAlpha()
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
virtual int getInt() const
Return the internal property value as an integer.
virtual float getFloat() const
boost::circular_buffer< boost::shared_ptr< PointStampedVisual > > visuals_
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.
virtual ~PointStampedDisplay()
rviz::FloatProperty * alpha_property_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
bool validateFloats(const sensor_msgs::CameraInfo &msg)
rviz::FloatProperty * radius_property_
void updateHistoryLength()
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
rviz::IntProperty * history_length_property_
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.
rviz::ColorProperty * color_property_