Go to the documentation of this file.
31 #ifndef RVIZ_VISUALIZATION_MANAGER_H_
32 #define RVIZ_VISUALIZATION_MANAGER_H_
42 #include <rviz/rviz_export.h>
57 class CallbackQueueInterface;
70 class PropertyTreeModel;
72 class SelectionManager;
74 class TfFrameProperty;
75 class ViewportMouseEvent;
76 class WindowManagerInterface;
78 class OgreRenderQueueClearer;
80 class VisualizationManagerPrivate;
114 std::shared_ptr<tf2_ros::Buffer>
tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
115 std::shared_ptr<tf2_ros::TransformListener> tf_listener =
116 std::shared_ptr<tf2_ros::TransformListener>());
150 Display* createDisplay(
const QString& class_lookup_name,
const QString& name,
bool enabled);
156 void addDisplay(
Display* display,
bool enabled);
161 void removeAllDisplays();
184 QString getFixedFrame()
const override;
189 void setFixedFrame(
const QString& frame);
194 std::shared_ptr<tf2_ros::Buffer> getTF2BufferPtr()
const;
201 return scene_manager_;
209 return render_panel_;
215 double getWallClock();
225 double getWallClockElapsed();
230 double getROSTimeElapsed();
239 void handleChar(QKeyEvent* event,
RenderPanel* panel)
override;
260 return selection_manager_;
266 return tool_manager_;
272 return view_manager_;
289 void queueRender()
override;
296 return window_manager_;
312 return frame_manager_;
327 void notifyConfigChanged();
332 return display_factory_;
337 return display_property_tree_model_;
341 void emitStatusUpdate(
const QString& message);
345 return root_display_group_;
350 return default_visibility_bit_;
355 return &visibility_bit_allocator_;
358 void setStatus(
const QString& message)
override;
362 help_path_ = help_path;
375 void configChanged();
378 void statusUpdate(
const QString& message);
381 void escapePressed();
395 void onToolChanged(
Tool* );
401 void createColorMaterials();
403 void threadedQueueThreadFunc();
450 void updateFixedFrame();
451 void updateBackgroundColor();
453 void updateDefaultLightVisible();
WindowManagerInterface * window_manager_
Helper class for transforming data into Ogre's world frame (the fixed frame).
ros::Time last_update_ros_time_
Stores how long it's been since the last update.
BitAllocator * visibilityBits() override
DisplayGroup * getRootDisplayGroup() const 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::WallTime wall_clock_begin_
ros::Time ros_time_begin_
The VisualizationManager class is the central manager class of rviz, holding all the Displays,...
Ogre::Root * ogre_root_
Ogre Root.
Property * global_options_
SelectionManager * getSelectionManager() const override
Return a pointer to the SelectionManager.
uint32_t render_requested_
Property specialized to provide getter for booleans.
FrameManager * frame_manager_
Allocation manager for bit positions within a 32-bit word.
uint32_t getDefaultVisibilityBit() const override
float frame_update_timer_
DisplayFactory * display_factory_
ros::Duration ros_time_elapsed_
ToolManager * getToolManager() const override
Return a pointer to the ToolManager.
ColorProperty * background_color_property_
A single element of a property tree, with a name, value, description, and possibly children.
PropertyTreeModel * display_property_tree_model_
SelectionManager * selection_manager_
virtual void setHelpPath(const QString &help_path)
uint32_t default_visibility_bit_
ViewManager * getViewManager() const override
Return a pointer to the ViewManager.
DisplayFactory * getDisplayFactory() const override
Return a factory for creating Display subclasses based on a class id string.
Ogre::SceneManager * scene_manager_
Ogre scene manager associated with this panel.
ros::WallTime last_update_wall_time_
ros::WallDuration wall_clock_elapsed_
OgreRenderQueueClearer * ogre_render_queue_clearer_
RenderPanel * render_panel_
Pure-virtual base class for objects which give Display subclasses context in which to work.
FrameManager * getFrameManager() const override
Return the FrameManager instance.
IntProperty * fps_property_
DisplayGroup * root_display_group_
VisualizationManagerPrivate * private_
volatile bool shutting_down_
tf2_ros::Buffer * tf_buffer
Ogre::Light * directional_light_
TfFrameProperty * fixed_frame_property_
Frame to transform fixed data to.
BitAllocator visibility_bit_allocator_
StatusList * global_status_
ROSCONSOLE_DECL void initialize()
ToolManager * tool_manager_
BoolProperty * default_light_enabled_property_
ViewManager * view_manager_
Ogre::SceneManager * getSceneManager() const override
Returns the Ogre::SceneManager used for the main RenderPanel.
RenderPanel * getRenderPanel() const
Return the main RenderPanel.
Configuration data storage class.
A Display object which stores other Displays as children.
PropertyTreeModel * getDisplayTreeModel() const
Property specialized to provide max/min enforcement for integers.
QTimer * update_timer_
Display::update is called on each display whenever this timer fires.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:10