31 #ifndef RVIZ_VISUALIZATION_MANAGER_H_ 32 #define RVIZ_VISUALIZATION_MANAGER_H_ 41 #include "rviz/rviz_export.h" 56 class CallbackQueueInterface;
61 class TransformListener;
74 class PropertyTreeModel;
76 class SelectionManager;
78 class TfFrameProperty;
79 class ViewportMouseEvent;
80 class WindowManagerInterface;
82 class OgreRenderQueueClearer;
84 class VisualizationManagerPrivate;
114 [[deprecated(
"This constructor signature will be removed in the next version. " 115 "If you still need to pass a boost::shared_ptr<tf::TransformListener>, " 116 "disable the warning explicitly. " 117 "When this constructor is removed, a new optional argument will added to " 118 "the other constructor and it will take a std::pair<> containing a " 119 "std::shared_ptr<tf2_ros::Buffer> and a " 120 "std::shared_ptr<tf2_ros::TransformListener>. " 121 "However, that cannot occur until the use of tf::TransformListener is " 158 Display* createDisplay(
const QString& class_lookup_name,
const QString& name,
bool enabled);
164 void addDisplay(
Display* display,
bool enabled);
169 void removeAllDisplays();
188 void save(
Config config)
const;
192 QString getFixedFrame()
const override;
197 void setFixedFrame(
const QString& frame);
207 std::shared_ptr<tf2_ros::Buffer> getTF2BufferPtr()
const override;
214 return scene_manager_;
222 return render_panel_;
228 double getWallClock();
238 double getWallClockElapsed();
243 double getROSTimeElapsed();
252 void handleChar(QKeyEvent* event,
RenderPanel* panel)
override;
273 return selection_manager_;
279 return tool_manager_;
285 return view_manager_;
302 void queueRender()
override;
309 return window_manager_;
325 return frame_manager_;
340 void notifyConfigChanged();
345 return display_factory_;
350 return display_property_tree_model_;
354 void emitStatusUpdate(
const QString& message);
358 return root_display_group_;
363 return default_visibility_bit_;
368 return &visibility_bit_allocator_;
371 void setStatus(
const QString& message)
override;
375 help_path_ = help_path;
388 void configChanged();
391 void statusUpdate(
const QString& message);
394 void escapePressed();
408 void onToolChanged(
Tool* tool);
414 void createColorMaterials();
416 void threadedQueueThreadFunc();
463 void updateFixedFrame();
464 void updateBackgroundColor();
466 void updateDefaultLightVisible();
RenderPanel * render_panel_
ros::WallTime last_update_wall_time_
ros::WallDuration wall_clock_elapsed_
OgreRenderQueueClearer * ogre_render_queue_clearer_
IntProperty * fps_property_
DisplayGroup * root_display_group_
FrameManager * getFrameManager() const override
Return the FrameManager instance.
ROSCONSOLE_DECL void initialize()
VisualizationManagerPrivate * private_
Ogre::Light * directional_light_
TfFrameProperty * fixed_frame_property_
Frame to transform fixed data to.
StatusList * global_status_
A single element of a property tree, with a name, value, description, and possibly children...
BoolProperty * default_light_enabled_property_
volatile bool shutting_down_
ViewManager * view_manager_
BitAllocator visibility_bit_allocator_
Ogre::SceneManager * getSceneManager() const override
Returns the Ogre::SceneManager used for the main RenderPanel.
ToolManager * tool_manager_
Property specialized to provide max/min enforcement for integers.
Configuration data storage class.
PropertyTreeModel * getDisplayTreeModel() const
QTimer * update_timer_
Display::update is called on each display whenever this timer fires.
WindowManagerInterface * window_manager_
Pure-virtual base class for objects which give Display subclasses context in which to work...
Helper class for transforming data into Ogre's world frame (the fixed frame).
RenderPanel * getRenderPanel() const
Return the main RenderPanel.
A Display object which stores other Displays as children.
DisplayGroup * getRootDisplayGroup() const override
BitAllocator * visibilityBits() override
WindowManagerInterface * getWindowManager() const override
Return the window manager, if any.
virtual QString getHelpPath() const
uint64_t getFrameCount() const override
Return the current value of the frame count.
ros::Time ros_time_begin_
The VisualizationManager class is the central manager class of rviz, holding all the Displays...
ros::Time last_update_ros_time_
Stores how long it's been since the last update.
Property * global_options_
Allocation manager for bit positions within a 32-bit word.
uint32_t render_requested_
ros::WallTime wall_clock_begin_
Ogre::Root * ogre_root_
Ogre Root.
FrameManager * frame_manager_
SelectionManager * getSelectionManager() const override
Return a pointer to the SelectionManager.
Property specialized to provide getter for booleans.
DisplayFactory * display_factory_
ColorProperty * background_color_property_
uint32_t getDefaultVisibilityBit() const override
PropertyTreeModel * display_property_tree_model_
ViewManager * getViewManager() const override
Return a pointer to the ViewManager.
float frame_update_timer_
Ogre::SceneManager * scene_manager_
Ogre scene manager associated with this panel.
ToolManager * getToolManager() const override
Return a pointer to the ToolManager.
ros::Duration ros_time_elapsed_
SelectionManager * selection_manager_
virtual void setHelpPath(const QString &help_path)
uint32_t default_visibility_bit_
DisplayFactory * getDisplayFactory() const override
Return a factory for creating Display subclasses based on a class id string.