#include <display.h>
Public Slots | |
void | setEnabled (bool enabled) |
Enable or disable this Display. | |
Public Member Functions | |
virtual void | deleteStatus (const QString &name) |
Delete the status entry with the given name. | |
void | deleteStatusStd (const std::string &name) |
Delete the status entry with the given std::string name. | |
Display () | |
virtual QString | getClassId () const |
Return the class identifier which was used to create this instance. This version just returns whatever was set with setClassId(). | |
virtual QVariant | getViewData (int column, int role) const |
Return data appropriate for the given column (0 or 1) and role for this Display. | |
virtual Qt::ItemFlags | getViewFlags (int column) const |
Return item flags appropriate for the given column (0 or 1) for this Display. | |
void | initialize (DisplayContext *context) |
Main initialization, called after constructor, before load() or setEnabled(). | |
bool | isEnabled () const |
Return true if this Display is enabled, false if not. | |
virtual void | load (const YAML::Node &yaml_node) |
Load the settings for this display from the given YAML node, which must be a map. | |
virtual void | loadChildren (const YAML::Node &yaml_node) |
Load the settings for this display from the given YAML node, which must be a map. | |
virtual void | reset () |
Called to tell the display to clear its state. | |
virtual void | save (YAML::Emitter &emitter) |
Write this display to the given YAML emitter. | |
virtual void | saveChildren (YAML::Emitter &emitter) |
Write the contents of this display to the given YAML emitter, which must be in a map context already. | |
virtual void | setClassId (const QString &class_id) |
Set the class identifier used to create this instance. Typically this will be set by the factory object which created it. | |
void | setFixedFrame (const QString &fixed_frame) |
Set the fixed frame in this display. | |
virtual void | setStatus (StatusProperty::Level level, const QString &name, const QString &text) |
Show status level and text. | |
void | setStatusStd (StatusProperty::Level level, const std::string &name, const std::string &text) |
Show status level and text, using a std::string. Convenience function which converts std::string to QString and calls setStatus(). | |
virtual void | update (float wall_dt, float ros_dt) |
Called periodically by the visualization manager. | |
Protected Member Functions | |
virtual void | clearStatuses () |
Delete all status children. | |
virtual void | fixedFrameChanged () |
Called by setFixedFrame(). Override to respond to changes to fixed_frame_. | |
virtual void | onDisable () |
Derived classes override this to do the actual work of disabling themselves. | |
virtual void | onEnable () |
Derived classes override this to do the actual work of enabling themselves. | |
virtual void | onInitialize () |
Override this function to do subclass-specific initialization. | |
Protected Attributes | |
DisplayContext * | context_ |
This DisplayContext pointer is the main connection a Display has into the rest of rviz. This is how the FrameManager is accessed, the SelectionManager, etc. When a Display subclass wants to signal that a new render should be done right away, call context_->queueRender(). | |
QString | fixed_frame_ |
A convenience variable equal to context_->getFixedFrame(). | |
Ogre::SceneManager * | scene_manager_ |
A convenience variable equal to context_->getSceneManager(). | |
ros::NodeHandle | threaded_nh_ |
A NodeHandle whose CallbackQueue is run from a different thread than the GUI. | |
ros::NodeHandle | update_nh_ |
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread). | |
Private Slots | |
void | onEnableChanged () |
Private Attributes | |
QString | class_id_ |
bool | initialized_ |
StatusList * | status_ |
Definition at line 50 of file display.h.
rviz::Display::Display | ( | ) |
Definition at line 45 of file display.cpp.
void rviz::Display::clearStatuses | ( | ) | [protected, virtual] |
Delete all status children.
This removes all status children and updates the top-level status.
Definition at line 116 of file display.cpp.
void rviz::Display::deleteStatus | ( | const QString & | name | ) | [virtual] |
Delete the status entry with the given name.
Definition at line 111 of file display.cpp.
void rviz::Display::deleteStatusStd | ( | const std::string & | name | ) | [inline] |
virtual void rviz::Display::fixedFrameChanged | ( | ) | [inline, protected, virtual] |
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
Reimplemented in rviz::CameraDisplay, rviz::GridCellsDisplay, rviz::InteractiveMarkerDisplay, rviz::LaserScanDisplay, rviz::MapDisplay, rviz::MarkerDisplay, rviz::OdometryDisplay, rviz::PointCloud2Display, rviz::PointCloudBase, rviz::PointCloudDisplay, rviz::PoseArrayDisplay, rviz::PoseDisplay, rviz::RobotModelDisplay, rviz::TFDisplay, rviz::DisplayGroup, rviz::MessageFilterDisplay< MessageType >, rviz::MessageFilterDisplay< geometry_msgs::PolygonStamped >, rviz::MessageFilterDisplay< nav_msgs::Path >, and rviz::MessageFilterDisplay< sensor_msgs::Range >.
virtual QString rviz::Display::getClassId | ( | ) | const [inline, virtual] |
Return the class identifier which was used to create this instance. This version just returns whatever was set with setClassId().
QVariant rviz::Display::getViewData | ( | int | column, | |
int | role | |||
) | const [virtual] |
Return data appropriate for the given column (0 or 1) and role for this Display.
Reimplemented from rviz::Property.
Reimplemented in rviz::DisplayGroup, and rviz::FailedDisplay.
Definition at line 68 of file display.cpp.
Qt::ItemFlags rviz::Display::getViewFlags | ( | int | column | ) | const [virtual] |
Return item flags appropriate for the given column (0 or 1) for this Display.
Reimplemented from rviz::Property.
Reimplemented in rviz::DisplayGroup.
Definition at line 91 of file display.cpp.
void rviz::Display::initialize | ( | DisplayContext * | context | ) |
Main initialization, called after constructor, before load() or setEnabled().
Definition at line 55 of file display.cpp.
bool rviz::Display::isEnabled | ( | ) | const |
Return true if this Display is enabled, false if not.
Definition at line 190 of file display.cpp.
void rviz::Display::load | ( | const YAML::Node & | yaml_node | ) | [virtual] |
Load the settings for this display from the given YAML node, which must be a map.
Overridden from Property::load(). This version just calls loadChildren().
load() is called after initialize().
Reimplemented from rviz::Property.
Reimplemented in rviz::FailedDisplay.
Definition at line 129 of file display.cpp.
void rviz::Display::loadChildren | ( | const YAML::Node & | yaml_node | ) | [virtual] |
Load the settings for this display from the given YAML node, which must be a map.
Overridden from Property::loadChildren() to load the Display's name and enabled state, then call Property::loadChildren().
Reimplemented from rviz::Property.
Reimplemented in rviz::DisplayGroup.
Definition at line 134 of file display.cpp.
virtual void rviz::Display::onDisable | ( | ) | [inline, protected, virtual] |
Derived classes override this to do the actual work of disabling themselves.
Reimplemented in rviz::AxesDisplay, rviz::CameraDisplay, rviz::GridCellsDisplay, rviz::GridDisplay, rviz::ImageDisplay, rviz::InteractiveMarkerDisplay, rviz::LaserScanDisplay, rviz::MapDisplay, rviz::MarkerDisplay, rviz::OdometryDisplay, rviz::PointCloud2Display, rviz::PointCloudBase, rviz::PointCloudDisplay, rviz::PoseArrayDisplay, rviz::PoseDisplay, rviz::RobotModelDisplay, rviz::TFDisplay, rviz::MessageFilterDisplay< MessageType >, rviz::MessageFilterDisplay< geometry_msgs::PolygonStamped >, rviz::MessageFilterDisplay< nav_msgs::Path >, and rviz::MessageFilterDisplay< sensor_msgs::Range >.
virtual void rviz::Display::onEnable | ( | ) | [inline, protected, virtual] |
Derived classes override this to do the actual work of enabling themselves.
Reimplemented in rviz::AxesDisplay, rviz::CameraDisplay, rviz::GridCellsDisplay, rviz::GridDisplay, rviz::ImageDisplay, rviz::InteractiveMarkerDisplay, rviz::LaserScanDisplay, rviz::MapDisplay, rviz::MarkerDisplay, rviz::OdometryDisplay, rviz::PointCloud2Display, rviz::PointCloudBase, rviz::PointCloudDisplay, rviz::PoseArrayDisplay, rviz::PoseDisplay, rviz::RobotModelDisplay, rviz::TFDisplay, rviz::MessageFilterDisplay< MessageType >, rviz::MessageFilterDisplay< geometry_msgs::PolygonStamped >, rviz::MessageFilterDisplay< nav_msgs::Path >, and rviz::MessageFilterDisplay< sensor_msgs::Range >.
void rviz::Display::onEnableChanged | ( | ) | [private, slot] |
Definition at line 209 of file display.cpp.
virtual void rviz::Display::onInitialize | ( | ) | [inline, protected, virtual] |
Override this function to do subclass-specific initialization.
This is called after vis_manager_ and scene_manager_ are set, and before load() or setEnabled().
setName() may or may not have been called before this.
Reimplemented in rviz::AxesDisplay, rviz::CameraDisplay, rviz::GridCellsDisplay, rviz::GridDisplay, rviz::ImageDisplay, rviz::InteractiveMarkerDisplay, rviz::LaserScanDisplay, rviz::MapDisplay, rviz::MarkerDisplay, rviz::OdometryDisplay, rviz::PathDisplay, rviz::PointCloud2Display, rviz::PointCloudBase, rviz::PointCloudDisplay, rviz::PolygonDisplay, rviz::PoseArrayDisplay, rviz::PoseDisplay, rviz::RangeDisplay, rviz::RobotModelDisplay, rviz::TFDisplay, rviz::MessageFilterDisplay< MessageType >, rviz::MessageFilterDisplay< geometry_msgs::PolygonStamped >, rviz::MessageFilterDisplay< nav_msgs::Path >, and rviz::MessageFilterDisplay< sensor_msgs::Range >.
void rviz::Display::reset | ( | ) | [virtual] |
Called to tell the display to clear its state.
Reimplemented in rviz::CameraDisplay, rviz::GridCellsDisplay, rviz::ImageDisplay, rviz::InteractiveMarkerDisplay, rviz::MapDisplay, rviz::MarkerDisplay, rviz::OdometryDisplay, rviz::PathDisplay, rviz::PointCloudBase, rviz::PolygonDisplay, rviz::PoseArrayDisplay, rviz::PoseDisplay, rviz::RangeDisplay, rviz::RobotModelDisplay, rviz::TFDisplay, rviz::DisplayGroup, rviz::MessageFilterDisplay< MessageType >, rviz::MessageFilterDisplay< geometry_msgs::PolygonStamped >, rviz::MessageFilterDisplay< nav_msgs::Path >, and rviz::MessageFilterDisplay< sensor_msgs::Range >.
Definition at line 204 of file display.cpp.
void rviz::Display::save | ( | YAML::Emitter & | emitter | ) | [virtual] |
Write this display to the given YAML emitter.
Overridden from Property::save(). This version just begins a map, calls saveChildren(), and ends the map.
Reimplemented from rviz::Property.
Reimplemented in rviz::FailedDisplay.
Definition at line 164 of file display.cpp.
void rviz::Display::saveChildren | ( | YAML::Emitter & | emitter | ) | [virtual] |
Write the contents of this display to the given YAML emitter, which must be in a map context already.
Reimplemented from rviz::Property.
Reimplemented in rviz::DisplayGroup.
Definition at line 171 of file display.cpp.
virtual void rviz::Display::setClassId | ( | const QString & | class_id | ) | [inline, virtual] |
void rviz::Display::setEnabled | ( | bool | enabled | ) | [slot] |
Enable or disable this Display.
SetEnabled is called after initialize() and at the end of load(), if the Display settings are being loaded from a file.
Definition at line 185 of file display.cpp.
void rviz::Display::setFixedFrame | ( | const QString & | fixed_frame | ) |
Set the fixed frame in this display.
Definition at line 195 of file display.cpp.
void rviz::Display::setStatus | ( | StatusProperty::Level | level, | |
const QString & | name, | |||
const QString & | text | |||
) | [virtual] |
Show status level and text.
level | One of StatusProperty::Ok, StatusProperty::Warn, or StatusProperty::Error. | |
name | The name of the child entry to set. | |
text | Description of the child's state. |
Every Display has a StatusList to indicate how it is doing. The StatusList has StatusPropertychildren indicating the status of various subcomponents of the Display. Each child of the status has a level, a name, and descriptive text. The top-level StatusList has a level which is set to the worst of all the children's levels.
Definition at line 96 of file display.cpp.
void rviz::Display::setStatusStd | ( | StatusProperty::Level | level, | |
const std::string & | name, | |||
const std::string & | text | |||
) | [inline] |
Show status level and text, using a std::string. Convenience function which converts std::string to QString and calls setStatus().
virtual void rviz::Display::update | ( | float | wall_dt, | |
float | ros_dt | |||
) | [inline, virtual] |
Called periodically by the visualization manager.
wall_dt | Wall-clock time, in seconds, since the last time the update list was run through. | |
ros_dt | ROS time, in seconds, since the last time the update list was run through. |
Reimplemented in rviz::AxesDisplay, rviz::CameraDisplay, rviz::GridDisplay, rviz::ImageDisplay, rviz::InteractiveMarkerDisplay, rviz::MarkerDisplay, rviz::OdometryDisplay, rviz::PointCloudBase, rviz::PoseArrayDisplay, rviz::PoseDisplay, rviz::RobotModelDisplay, rviz::TFDisplay, and rviz::DisplayGroup.
QString rviz::Display::class_id_ [private] |
DisplayContext* rviz::Display::context_ [protected] |
This DisplayContext pointer is the main connection a Display has into the rest of rviz. This is how the FrameManager is accessed, the SelectionManager, etc. When a Display subclass wants to signal that a new render should be done right away, call context_->queueRender().
This is set after the constructor and before onInitialize() is called.
QString rviz::Display::fixed_frame_ [protected] |
A convenience variable equal to context_->getFixedFrame().
This is set after the constructor and before onInitialize() is called. Every time it is updated (via setFixedFrame()), fixedFrameChanged() is called.
bool rviz::Display::initialized_ [private] |
Ogre::SceneManager* rviz::Display::scene_manager_ [protected] |
A convenience variable equal to context_->getSceneManager().
This is set after the constructor and before onInitialize() is called. The scene manager we're associated with
Reimplemented in rviz::ImageDisplay.
StatusList* rviz::Display::status_ [private] |
ros::NodeHandle rviz::Display::threaded_nh_ [protected] |
A NodeHandle whose CallbackQueue is run from a different thread than the GUI.
This is configured after the constructor and before onInitialize() is called.
ros::NodeHandle rviz::Display::update_nh_ [protected] |
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
This is configured after the constructor and before onInitialize() is called.