$search
Abstract base class for all displays. More...
#include <display.h>
Public Member Functions | |
void | clearStatuses () |
virtual void | createProperties () |
Called from setPropertyManager, gives the display a chance to create some properties immediately. | |
void | deleteStatus (const std::string &name) |
void | disable (bool force=false) |
Disable this display. | |
Display (const std::string &name, VisualizationManager *manager) | |
void | enable (bool force=false) |
Enable this display. | |
virtual void | fixedFrameChanged ()=0 |
Called from within setFixedFrame, notifying child classes that the fixed frame has changed. | |
const std::string & | getName () const |
DisplaySignal & | getStateChangedSignal () |
StatusLevel | getStatus () |
bool | isEnabled () |
virtual void | reset () |
Called to tell the display to clear its state. | |
void | setEnabled (bool enable, bool force=false) |
void | setFixedFrame (const std::string &frame) |
Set the fixed frame of this display. This is a frame id which should generally be the top-level frame being broadcast through TF. | |
void | setLockRenderCallback (boost::function< void()> func) |
Set the callback used to lock the renderer. | |
void | setName (const std::string &name) |
void | setPropertyManager (PropertyManager *manager, const CategoryPropertyWPtr &parent) |
Sets the property manager and parent category for this display. | |
void | setRenderCallback (boost::function< void()> func) |
Set the callback used for causing a render to happen. | |
void | setStatus (StatusLevel level, const std::string &name, const std::string &text) |
void | setTargetFrame (const std::string &frame) |
Set the target frame of this display. This is a frame id which should match something being broadcast through TF. | |
void | setUnlockRenderCallback (boost::function< void()> func) |
Set the callback used to unlock the renderer. | |
virtual void | targetFrameChanged ()=0 |
Called from within setTargetFrame, notifying child classes that the target frame has changed. | |
virtual void | update (float wall_dt, float ros_dt) |
Called periodically by the visualization panel. | |
virtual | ~Display () |
Protected Member Functions | |
void | causeRender () |
Cause the scene we're in to be rendered. | |
void | lockRender () |
Lock the renderer. | |
virtual void | onDisable ()=0 |
Derived classes override this to do the actual work of disabling themselves. | |
virtual void | onEnable ()=0 |
Derived classes override this to do the actual work of enabling themselves. | |
void | unlockRender () |
Unlock the renderer. | |
Protected Attributes | |
bool | enabled_ |
Are we enabled? | |
std::string | fixed_frame_ |
The frame we should transform all fixed data into. | |
std::string | name_ |
The name of this display. | |
CategoryPropertyWPtr | parent_category_ |
The parent category to use when creating properties. | |
PropertyManager * | property_manager_ |
The property manager to use to create properties. | |
std::string | property_prefix_ |
Prefix to prepend to our properties. | |
boost::function< void()> | render_callback_ |
Render callback. | |
boost::function< void()> | render_lock_ |
Render lock callback. | |
boost::function< void()> | render_unlock_ |
Render unlock callback. | |
Ogre::SceneManager * | scene_manager_ |
The scene manager we're associated with. | |
DisplaySignal | state_changed_ |
StatusLevel | status_ |
StatusPropertyWPtr | status_property_ |
std::string | target_frame_ |
The frame we should transform all periodically-updated data into. | |
ros::NodeHandle | threaded_nh_ |
ros::NodeHandle | update_nh_ |
VisualizationManager * | vis_manager_ |
Friends | |
class | RenderAutoLock |
Abstract base class for all displays.
Provides a common interface for the visualization panel to interact with, so that new displays can be added without the visualization panel knowing anything about them.
Definition at line 74 of file display.h.
rviz::Display::Display | ( | const std::string & | name, | |
VisualizationManager * | manager | |||
) |
Definition at line 36 of file display.cpp.
rviz::Display::~Display | ( | ) | [virtual] |
Definition at line 50 of file display.cpp.
void rviz::Display::causeRender | ( | ) | [protected] |
Cause the scene we're in to be rendered.
Definition at line 130 of file display.cpp.
void rviz::Display::clearStatuses | ( | ) |
Definition at line 203 of file display.cpp.
virtual void rviz::Display::createProperties | ( | ) | [inline, virtual] |
Called from setPropertyManager, gives the display a chance to create some properties immediately.
Once this function is called, the property_manager_ member is valid and will stay valid
Reimplemented in rviz::AxesDisplay, rviz::CameraDisplay, rviz::GridCellsDisplay, rviz::GridDisplay, rviz::ImageDisplay, rviz::InteractiveMarkerDisplay, rviz::LaserScanDisplay, rviz::MapDisplay, rviz::MarkerArrayDisplay, rviz::MarkerDisplay, rviz::OdometryDisplay, rviz::PathDisplay, rviz::PointCloud2Display, rviz::PointCloudBase, rviz::PointCloudDisplay, rviz::PolygonDisplay, rviz::PoseArrayDisplay, rviz::PoseDisplay, rviz::RangeDisplay, rviz::RobotModelDisplay, and rviz::TFDisplay.
void rviz::Display::deleteStatus | ( | const std::string & | name | ) |
Definition at line 188 of file display.cpp.
void rviz::Display::disable | ( | bool | force = false |
) |
Disable this display.
force | If false, does not re-disable if this display is already disabled. If true, it does. |
Definition at line 83 of file display.cpp.
void rviz::Display::enable | ( | bool | force = false |
) |
Enable this display.
force | If false, does not re-enable if this display is already enabled. If true, it does. |
Definition at line 64 of file display.cpp.
virtual void rviz::Display::fixedFrameChanged | ( | ) | [pure virtual] |
Called from within setFixedFrame, notifying child classes that the fixed frame has changed.
Implemented 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, and rviz::TFDisplay.
const std::string& rviz::Display::getName | ( | void | ) | const [inline] |
DisplaySignal& rviz::Display::getStateChangedSignal | ( | ) | [inline] |
StatusLevel rviz::Display::getStatus | ( | ) |
Definition at line 168 of file display.cpp.
void rviz::Display::lockRender | ( | ) | [protected] |
Lock the renderer.
Definition at line 138 of file display.cpp.
virtual void rviz::Display::onDisable | ( | ) | [protected, pure virtual] |
Derived classes override this to do the actual work of disabling themselves.
Implemented 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, and rviz::TFDisplay.
virtual void rviz::Display::onEnable | ( | ) | [protected, pure virtual] |
Derived classes override this to do the actual work of enabling themselves.
Implemented 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, and rviz::TFDisplay.
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, and rviz::TFDisplay.
Definition at line 230 of file display.cpp.
void rviz::Display::setEnabled | ( | bool | enable, | |
bool | force = false | |||
) |
Definition at line 102 of file display.cpp.
void rviz::Display::setFixedFrame | ( | const std::string & | frame | ) |
Set the fixed frame of this display. This is a frame id which should generally be the top-level frame being broadcast through TF.
frame | The fixed frame |
Definition at line 161 of file display.cpp.
void rviz::Display::setLockRenderCallback | ( | boost::function< void()> | func | ) |
Set the callback used to lock the renderer.
Definition at line 119 of file display.cpp.
void rviz::Display::setName | ( | const std::string & | name | ) |
Definition at line 58 of file display.cpp.
void rviz::Display::setPropertyManager | ( | PropertyManager * | manager, | |
const CategoryPropertyWPtr & | parent | |||
) |
Sets the property manager and parent category for this display.
manager | The property manager | |
parent | The parent category |
Definition at line 218 of file display.cpp.
void rviz::Display::setRenderCallback | ( | boost::function< void()> | func | ) |
Set the callback used for causing a render to happen.
func | a void(void) function that will cause a render to happen from the correct thread |
Definition at line 114 of file display.cpp.
void rviz::Display::setStatus | ( | StatusLevel | level, | |
const std::string & | name, | |||
const std::string & | text | |||
) |
Definition at line 173 of file display.cpp.
void rviz::Display::setTargetFrame | ( | const std::string & | frame | ) |
Set the target frame of this display. This is a frame id which should match something being broadcast through TF.
Definition at line 154 of file display.cpp.
void rviz::Display::setUnlockRenderCallback | ( | boost::function< void()> | func | ) |
Set the callback used to unlock the renderer.
Definition at line 124 of file display.cpp.
virtual void rviz::Display::targetFrameChanged | ( | ) | [pure virtual] |
Called from within setTargetFrame, notifying child classes that the target frame has changed.
Implemented 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::PointCloudDisplay, rviz::PolygonDisplay, rviz::PoseArrayDisplay, rviz::PoseDisplay, rviz::RangeDisplay, rviz::RobotModelDisplay, and rviz::TFDisplay.
void rviz::Display::unlockRender | ( | ) | [protected] |
Unlock the renderer.
Definition at line 146 of file display.cpp.
virtual void rviz::Display::update | ( | float | wall_dt, | |
float | ros_dt | |||
) | [inline, virtual] |
Called periodically by the visualization panel.
dt | Wall-clock time, in seconds, since the last time the update list was run through. |
Reimplemented in rviz::AxesDisplay, rviz::CameraDisplay, rviz::GridCellsDisplay, rviz::GridDisplay, rviz::ImageDisplay, rviz::InteractiveMarkerDisplay, rviz::MapDisplay, rviz::MarkerDisplay, rviz::OdometryDisplay, rviz::PathDisplay, rviz::PointCloudBase, rviz::PolygonDisplay, rviz::PoseArrayDisplay, rviz::PoseDisplay, rviz::RangeDisplay, rviz::RobotModelDisplay, and rviz::TFDisplay.
friend class RenderAutoLock [friend] |
bool rviz::Display::enabled_ [protected] |
std::string rviz::Display::fixed_frame_ [protected] |
std::string rviz::Display::name_ [protected] |
CategoryPropertyWPtr rviz::Display::parent_category_ [protected] |
PropertyManager* rviz::Display::property_manager_ [protected] |
std::string rviz::Display::property_prefix_ [protected] |
boost::function<void ()> rviz::Display::render_callback_ [protected] |
boost::function<void ()> rviz::Display::render_lock_ [protected] |
boost::function<void ()> rviz::Display::render_unlock_ [protected] |
Ogre::SceneManager* rviz::Display::scene_manager_ [protected] |
The scene manager we're associated with.
Reimplemented in rviz::ImageDisplay.
DisplaySignal rviz::Display::state_changed_ [protected] |
StatusLevel rviz::Display::status_ [protected] |
StatusPropertyWPtr rviz::Display::status_property_ [protected] |
std::string rviz::Display::target_frame_ [protected] |
ros::NodeHandle rviz::Display::threaded_nh_ [protected] |
ros::NodeHandle rviz::Display::update_nh_ [protected] |
VisualizationManager* rviz::Display::vis_manager_ [protected] |