rviz::PoseArrayDisplay Class Reference

Displays a std_msgs::ParticleCloud2D message. More...

#include <pose_array_display.h>

Inheritance diagram for rviz::PoseArrayDisplay:
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.
const ColorgetColor ()
const std::string & getTopic ()
 PoseArrayDisplay (const std::string &name, VisualizationManager *manager)
virtual void reset ()
 Called to tell the display to clear its state.
void setColor (const 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 ~PoseArrayDisplay ()

Protected Member Functions

void clear ()
void incomingMessage (const geometry_msgs::PoseArray::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 geometry_msgs::PoseArray::ConstPtr &msg)
void subscribe ()
void unsubscribe ()

Protected Attributes

Color color_
ColorPropertyWPtr color_property_
Ogre::ManualObject * manual_object_
uint32_t messages_received_
Ogre::SceneNode * scene_node_
message_filters::Subscriber
< geometry_msgs::PoseArray > 
sub_
tf::MessageFilter
< geometry_msgs::PoseArray > 
tf_filter_
std::string topic_
ROSTopicStringPropertyWPtr topic_property_

Detailed Description

Displays a std_msgs::ParticleCloud2D message.

Definition at line 63 of file pose_array_display.h.


Constructor & Destructor Documentation

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

Definition at line 51 of file pose_array_display.cpp.

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

Definition at line 71 of file pose_array_display.cpp.


Member Function Documentation

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

Definition at line 79 of file pose_array_display.cpp.

void rviz::PoseArrayDisplay::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 137 of file pose_array_display.cpp.

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

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

Implements rviz::Display.

Definition at line 150 of file pose_array_display.cpp.

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

Definition at line 73 of file pose_array_display.h.

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

Definition at line 70 of file pose_array_display.h.

void rviz::PoseArrayDisplay::incomingMessage ( const geometry_msgs::PoseArray::ConstPtr &  msg  )  [protected]

Definition at line 232 of file pose_array_display.cpp.

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

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

Implements rviz::Display.

Definition at line 130 of file pose_array_display.cpp.

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

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

Implements rviz::Display.

Definition at line 124 of file pose_array_display.cpp.

void rviz::PoseArrayDisplay::processMessage ( const geometry_msgs::PoseArray::ConstPtr &  msg  )  [protected]

Definition at line 165 of file pose_array_display.cpp.

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

Called to tell the display to clear its state.

Reimplemented from rviz::Display.

Definition at line 237 of file pose_array_display.cpp.

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

Definition at line 100 of file pose_array_display.cpp.

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

Definition at line 87 of file pose_array_display.cpp.

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

Definition at line 109 of file pose_array_display.cpp.

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

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

Implements rviz::Display.

Definition at line 76 of file pose_array_display.h.

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

Definition at line 119 of file pose_array_display.cpp.

void rviz::PoseArrayDisplay::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 156 of file pose_array_display.cpp.


Member Data Documentation

Definition at line 94 of file pose_array_display.h.

ColorPropertyWPtr rviz::PoseArrayDisplay::color_property_ [protected]

Definition at line 110 of file pose_array_display.h.

Ogre::ManualObject* rviz::PoseArrayDisplay::manual_object_ [protected]

Definition at line 105 of file pose_array_display.h.

Definition at line 96 of file pose_array_display.h.

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

Definition at line 104 of file pose_array_display.h.

message_filters::Subscriber<geometry_msgs::PoseArray> rviz::PoseArrayDisplay::sub_ [protected]

Definition at line 107 of file pose_array_display.h.

tf::MessageFilter<geometry_msgs::PoseArray> rviz::PoseArrayDisplay::tf_filter_ [protected]

Definition at line 108 of file pose_array_display.h.

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

Definition at line 93 of file pose_array_display.h.

ROSTopicStringPropertyWPtr rviz::PoseArrayDisplay::topic_property_ [protected]

Definition at line 111 of file pose_array_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
autogenerated on Fri Jan 11 09:36:34 2013