Go to the documentation of this file.
30 #include <boost/bind/bind.hpp>
31 #include <OgreSceneNode.h>
32 #include <OgreSceneManager.h>
33 #include <OgreManualObject.h>
62 ss <<
"PolyLine" << count++;
117 "Message contained invalid floating point values (nans or infs)");
121 Ogre::Vector3 position;
122 Ogre::Quaternion orientation;
125 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(),
132 if (msg->cell_width == 0)
136 else if (msg->cell_height == 0)
144 uint32_t num_points = msg->cells.size();
146 typedef std::vector<PointCloud::Point> V_Point;
148 points.resize(num_points);
149 for (uint32_t i = 0; i < num_points; i++)
152 current_point.
position.x = msg->cells[i].x;
153 current_point.
position.y = msg->cells[i].y;
154 current_point.
position.z = msg->cells[i].z;
155 current_point.
color = color_int;
A visual representation of a set of points.
FloatProperty * alpha_property_
virtual QColor getColor() const
Ogre::ColourValue qtToOgre(const QColor &c)
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
virtual void unsubscribe()
void setAlpha(float alpha, bool per_point_alpha=false)
bool initialized() const
Returns true if the display has been initialized.
void addPoints(Point *points, uint32_t num_points)
Add points to this point cloud.
bool validateFloats(const sensor_msgs::CameraInfo &msg)
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
void reset() override
Called to tell the display to clear its state.
Representation of a point, with x/y/z position and r/g/b color.
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.
void onInitialize() override
Override this function to do subclass-specific initialization.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual float getFloat() const
ColorProperty * color_property_
Displays a nav_msgs::GridCells message.
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
void setDimensions(float width, float height, float depth)
Set the dimensions of the billboards used to render each point.
void setRenderMode(RenderMode mode)
Set what type of rendering primitives should be used, currently points, billboards and boxes are supp...
~GridCellsDisplay() override
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....
void clear()
Clear all the points.
uint64_t last_frame_count_
virtual uint64_t getFrameCount() const =0
Return the current value of the frame count.
void processMessage(const nav_msgs::GridCells::ConstPtr &msg) override
void setCommonDirection(const Ogre::Vector3 &vec)
See Ogre::BillboardSet::setCommonDirection.
void setCommonUpVector(const Ogre::Vector3 &vec)
See Ogre::BillboardSet::setCommonUpVector.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09