30 #include <OgreSceneNode.h> 31 #include <OgreSceneManager.h> 32 #include <OgreManualObject.h> 33 #include <OgreBillboardSet.h> 50 "Color to draw the polygon.",
this, SLOT(
queueRender() ));
52 "Amount of transparency to apply to the polygon.",
this, SLOT(
queueRender() ));
93 Ogre::Vector3 position;
94 Ogre::Quaternion orientation;
97 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'",
98 msg->header.frame_id.c_str(), qPrintable(
fixed_frame_ ));
113 uint32_t num_points = msg->polygon.points.size();
117 manual_object_->begin(
"BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_STRIP );
118 for( uint32_t i=0; i < num_points + 1; ++i )
120 const geometry_msgs::Point32& msg_point = msg->polygon.points[ i % num_points ];
121 manual_object_->position( msg_point.x, msg_point.y, msg_point.z );
virtual QColor getColor() const
virtual void onInitialize()
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
FloatProperty * alpha_property_
virtual float getFloat() const
Displays a geometry_msgs::PolygonStamped message.
virtual void onInitialize()
Overridden from MessageFilterDisplay.
Property specialized to enforce floating point max/min.
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Ogre::ColourValue qtToOgre(const QColor &c)
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
bool validateFloats(const sensor_msgs::CameraInfo &msg)
void queueRender()
Convenience function which calls context_->queueRender().
virtual void reset()
Overridden from MessageFilterDisplay.
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
Ogre::ManualObject * manual_object_
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
virtual ~PolygonDisplay()
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.
ColorProperty * color_property_
virtual void processMessage(const geometry_msgs::PolygonStamped::ConstPtr &msg)
Overridden from MessageFilterDisplay.
bool initialized() const
Returns true if the display has been initialized.
#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.