Go to the documentation of this file. 1 #include <OgreSceneNode.h>
2 #include <OgreSceneManager.h>
29 new rviz::IntProperty(
"History Length", 1,
"Number of prior measurements to display.",
this,
59 for (
size_t i = 0; i <
visuals_.size(); i++)
61 visuals_[i]->setColor(color.r, color.g, color.b, alpha);
78 "Message contained invalid floating point values (nans or infs)");
85 Ogre::Quaternion orientation;
86 Ogre::Vector3 position;
90 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(),
110 visual->setRadius(radius);
111 visual->setMessage(msg);
112 visual->setFramePosition(position);
113 visual->setFrameOrientation(orientation);
116 visual->setColor(color.r, color.g, color.b, alpha);
void updateColorAndAlpha()
rviz::IntProperty * history_length_property_
bool validateFloats(const sensor_msgs::CameraInfo &msg)
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
Property specialized to enforce floating point max/min.
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual float getFloat() const
void onInitialize() override
Override this function to do subclass-specific initialization.
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
rviz::ColorProperty * color_property_
void updateHistoryLength()
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
void processMessage(const geometry_msgs::PointStamped::ConstPtr &msg) override
rviz::FloatProperty * radius_property_
void onInitialize() override
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.
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.
void reset() override
Called to tell the display to clear its state.
~PointStampedDisplay() override
boost::circular_buffer< boost::shared_ptr< PointStampedVisual > > visuals_
rviz::FloatProperty * alpha_property_
Ogre::ColourValue getOgreColor() const
Property specialized to provide max/min enforcement for integers.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:10