Pure-virtual base class for objects which give Display subclasses context in which to work. More...
#include <display_context.h>
Public Slots | |
virtual void | queueRender ()=0 |
Queues a render. Multiple calls before a render happens will only cause a single render. More... | |
Public Member Functions | |
virtual uint32_t | getDefaultVisibilityBit () const =0 |
virtual DisplayFactory * | getDisplayFactory () const =0 |
Return a factory for creating Display subclasses based on a class id string. More... | |
virtual QString | getFixedFrame () const =0 |
Return the fixed frame name. More... | |
virtual uint64_t | getFrameCount () const =0 |
Return the current value of the frame count. More... | |
virtual FrameManager * | getFrameManager () const =0 |
Return the FrameManager instance. More... | |
virtual DisplayGroup * | getRootDisplayGroup () const =0 |
virtual Ogre::SceneManager * | getSceneManager () const =0 |
Returns the Ogre::SceneManager used for the main RenderPanel. More... | |
virtual SelectionManager * | getSelectionManager () const =0 |
Return a pointer to the SelectionManager. More... | |
virtual std::shared_ptr< tf2_ros::Buffer > | getTF2BufferPtr () const =0 |
Convenience function: returns getFrameManager()->getTF2BufferPtr(). More... | |
virtual tf::TransformListener * | getTFClient () const =0 |
Convenience function: returns getFrameManager()->getTFClient(). More... | |
virtual ros::CallbackQueueInterface * | getThreadedQueue ()=0 |
Return a CallbackQueue using a different thread than the main GUI one. More... | |
virtual ToolManager * | getToolManager () const =0 |
Return the ToolManager. More... | |
virtual ros::CallbackQueueInterface * | getUpdateQueue ()=0 |
Return the CallbackQueue using the main GUI thread. More... | |
virtual ViewManager * | getViewManager () const =0 |
Return the ViewManager. More... | |
virtual WindowManagerInterface * | getWindowManager () const =0 |
Return the window manager, if any. More... | |
virtual void | handleChar (QKeyEvent *event, RenderPanel *panel)=0 |
Handle a single key event for a given RenderPanel. More... | |
virtual void | handleMouseEvent (const ViewportMouseEvent &event)=0 |
Handle a mouse event. More... | |
virtual void | setStatus (const QString &message)=0 |
virtual BitAllocator * | visibilityBits ()=0 |
Pure-virtual base class for objects which give Display subclasses context in which to work.
This interface class mainly exists to enable more isolated unit tests by enabling small mock objects to take the place of the large VisualizationManager implementation class. It also serves to define a narrower, more maintainable API for Display plugins.
Definition at line 81 of file display_context.h.
|
pure virtual |
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Return a factory for creating Display subclasses based on a class id string.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Return the fixed frame name.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Return the current value of the frame count.
The frame count is just a number which increments each time a frame is rendered. This lets clients check if a new frame has been rendered since the last time they did something.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Return the FrameManager instance.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Returns the Ogre::SceneManager used for the main RenderPanel.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Return a pointer to the SelectionManager.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Convenience function: returns getFrameManager()->getTF2BufferPtr().
Implemented in rviz::VisualizationManager.
|
pure virtual |
Convenience function: returns getFrameManager()->getTFClient().
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Return a CallbackQueue using a different thread than the main GUI one.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Return the ToolManager.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Return the CallbackQueue using the main GUI thread.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Return the ViewManager.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Return the window manager, if any.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Handle a single key event for a given RenderPanel.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Handle a mouse event.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtualslot |
Queues a render. Multiple calls before a render happens will only cause a single render.
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Set the message displayed in the status bar
Implemented in rviz::VisualizationManager, and rviz::MockContext.
|
pure virtual |
Implemented in rviz::VisualizationManager, and rviz::MockContext.