$search

rviz::RangeDisplay Class Reference

Displays a sensor_msgs::Range message as a cone. More...

#include <range_display.h>

Inheritance diagram for rviz::RangeDisplay:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void createProperties ()
 Called from setPropertyManager, gives the display a chance to create some properties immediately.
virtual void fixedFrameChanged ()
 Called from within setFixedFrame, notifying child classes that the fixed frame has changed.
float getAlpha ()
int getBuffer ()
const rviz::ColorgetColor ()
const std::string & getTopic ()
virtual const char * getType () const
 RangeDisplay (const std::string &name, rviz::VisualizationManager *manager)
virtual void reset ()
 Called to tell the display to clear its state.
void setAlpha (float alpha)
void setBuffer (int buffer)
void setColor (const rviz::Color &color)
void setTopic (const std::string &topic)
virtual void targetFrameChanged ()
 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 ~RangeDisplay ()

Static Public Member Functions

static const char * getDescription ()
static const char * getTypeStatic ()

Protected Member Functions

void clear ()
void incomingMessage (const sensor_msgs::Range::ConstPtr &msg)
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.
void processMessage (const sensor_msgs::Range::ConstPtr &msg)
void subscribe ()
void unsubscribe ()

Protected Attributes

float alpha_
rviz::FloatPropertyWPtr alpha_property_
int buffer_len_
rviz::IntPropertyWPtr bufferLen_property_
rviz::Color color_
rviz::ColorPropertyWPtr color_property_
std::vector< ogre_tools::Shape * > cones_
 Handles actually drawing the cone.
sensor_msgs::Range::ConstPtr current_message_
uint32_t messages_received_
Ogre::SceneNode * scene_node_
message_filters::Subscriber
< sensor_msgs::Range
sub_
tf::MessageFilter
< sensor_msgs::Range
tf_filter_
std::string topic_
rviz::ROSTopicStringPropertyWPtr topic_property_

Detailed Description

Displays a sensor_msgs::Range message as a cone.

Definition at line 63 of file range_display.h.


Constructor & Destructor Documentation

rviz::RangeDisplay::RangeDisplay ( const std::string &  name,
rviz::VisualizationManager manager 
)

Definition at line 17 of file range_display.cpp.

rviz::RangeDisplay::~RangeDisplay (  )  [virtual]

Definition at line 35 of file range_display.cpp.


Member Function Documentation

void rviz::RangeDisplay::clear (  )  [protected]

Definition at line 44 of file range_display.cpp.

void rviz::RangeDisplay::createProperties (  )  [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 from rviz::Display.

Definition at line 207 of file range_display.cpp.

void rviz::RangeDisplay::fixedFrameChanged (  )  [virtual]

Called from within setFixedFrame, notifying child classes that the fixed frame has changed.

Implements rviz::Display.

Definition at line 146 of file range_display.cpp.

float rviz::RangeDisplay::getAlpha (  )  [inline]

Definition at line 79 of file range_display.h.

int rviz::RangeDisplay::getBuffer (  )  [inline]

Definition at line 76 of file range_display.h.

const rviz::Color& rviz::RangeDisplay::getColor (  )  [inline]

Definition at line 73 of file range_display.h.

const char * rviz::RangeDisplay::getDescription (  )  [static]

Definition at line 226 of file range_display.cpp.

const std::string& rviz::RangeDisplay::getTopic (  )  [inline]

Definition at line 70 of file range_display.h.

virtual const char* rviz::RangeDisplay::getType (  )  const [inline, virtual]

Definition at line 89 of file range_display.h.

static const char* rviz::RangeDisplay::getTypeStatic (  )  [inline, static]

Definition at line 88 of file range_display.h.

void rviz::RangeDisplay::incomingMessage ( const sensor_msgs::Range::ConstPtr msg  )  [protected]

Definition at line 196 of file range_display.cpp.

void rviz::RangeDisplay::onDisable (  )  [protected, virtual]

Derived classes override this to do the actual work of disabling themselves.

Implements rviz::Display.

Definition at line 139 of file range_display.cpp.

void rviz::RangeDisplay::onEnable (  )  [protected, virtual]

Derived classes override this to do the actual work of enabling themselves.

Implements rviz::Display.

Definition at line 133 of file range_display.cpp.

void rviz::RangeDisplay::processMessage ( const sensor_msgs::Range::ConstPtr msg  )  [protected]

Definition at line 157 of file range_display.cpp.

void rviz::RangeDisplay::reset (  )  [virtual]

Called to tell the display to clear its state.

Reimplemented from rviz::Display.

Definition at line 201 of file range_display.cpp.

void rviz::RangeDisplay::setAlpha ( float  alpha  ) 

Definition at line 108 of file range_display.cpp.

void rviz::RangeDisplay::setBuffer ( int  buffer  ) 

Definition at line 75 of file range_display.cpp.

void rviz::RangeDisplay::setColor ( const rviz::Color color  ) 

Definition at line 65 of file range_display.cpp.

void rviz::RangeDisplay::setTopic ( const std::string &  topic  ) 

Definition at line 52 of file range_display.cpp.

void rviz::RangeDisplay::subscribe (  )  [protected]

Definition at line 118 of file range_display.cpp.

virtual void rviz::RangeDisplay::targetFrameChanged (  )  [inline, virtual]

Called from within setTargetFrame, notifying child classes that the target frame has changed.

Implements rviz::Display.

Definition at line 82 of file range_display.h.

void rviz::RangeDisplay::unsubscribe (  )  [protected]

Definition at line 128 of file range_display.cpp.

void rviz::RangeDisplay::update ( float  wall_dt,
float  ros_dt 
) [virtual]

Called periodically by the visualization panel.

Parameters:
dt Wall-clock time, in seconds, since the last time the update list was run through.

Reimplemented from rviz::Display.

Definition at line 152 of file range_display.cpp.


Member Data Documentation

float rviz::RangeDisplay::alpha_ [protected]

Definition at line 105 of file range_display.h.

rviz::FloatPropertyWPtr rviz::RangeDisplay::alpha_property_ [protected]

Definition at line 119 of file range_display.h.

Definition at line 106 of file range_display.h.

rviz::IntPropertyWPtr rviz::RangeDisplay::bufferLen_property_ [protected]

Definition at line 120 of file range_display.h.

Definition at line 104 of file range_display.h.

rviz::ColorPropertyWPtr rviz::RangeDisplay::color_property_ [protected]

Definition at line 117 of file range_display.h.

std::vector<ogre_tools::Shape* > rviz::RangeDisplay::cones_ [protected]

Handles actually drawing the cone.

Definition at line 111 of file range_display.h.

Definition at line 115 of file range_display.h.

Definition at line 108 of file range_display.h.

Ogre::SceneNode* rviz::RangeDisplay::scene_node_ [protected]

Definition at line 110 of file range_display.h.

Definition at line 113 of file range_display.h.

Definition at line 114 of file range_display.h.

std::string rviz::RangeDisplay::topic_ [protected]

Definition at line 103 of file range_display.h.

rviz::ROSTopicStringPropertyWPtr rviz::RangeDisplay::topic_property_ [protected]

Definition at line 118 of file range_display.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


rviz
Author(s): Josh Faust, Dave Hershberger
autogenerated on Sat Mar 2 14:17:37 2013