Display subclass using a tf::MessageFilter, templated on the ROS message type. More...
#include <effort_display.h>
Public Types | |
typedef MessageFilterJointStateDisplay | MFDClass |
Convenience typedef so subclasses don't have to use the long templated class name to refer to their super class. | |
Public Member Functions | |
MessageFilterJointStateDisplay () | |
virtual void | onInitialize () |
Override this function to do subclass-specific initialization. | |
virtual void | reset () |
Called to tell the display to clear its state. | |
virtual | ~MessageFilterJointStateDisplay () |
Protected Member Functions | |
virtual void | fixedFrameChanged () |
Called by setFixedFrame(). Override to respond to changes to fixed_frame_. | |
void | incomingMessage (const sensor_msgs::JointState::ConstPtr &msg) |
Incoming message callback. Checks if the message pointer is valid, increments messages_received_, then calls processMessage(). | |
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 | processMessage (const sensor_msgs::JointState::ConstPtr &msg)=0 |
Implement this to process the contents of a message. | |
virtual void | subscribe () |
virtual void | unsubscribe () |
virtual void | updateTopic () |
Protected Attributes | |
uint32_t | messages_received_ |
message_filters::Subscriber < sensor_msgs::JointState > | sub_ |
tf::MessageFilterJointState * | tf_filter_ |
Display subclass using a tf::MessageFilter, templated on the ROS message type.
This class brings together some common things used in many Display types. It has a tf::MessageFilter to filter incoming messages, and it handles subscribing and unsubscribing when the display is enabled or disabled. It also has an Ogre::SceneNode which
Definition at line 526 of file effort_display.h.
Convenience typedef so subclasses don't have to use the long templated class name to refer to their super class.
Definition at line 532 of file effort_display.h.
Definition at line 534 of file effort_display.h.
virtual rviz::MessageFilterJointStateDisplay::~MessageFilterJointStateDisplay | ( | ) | [inline, virtual] |
Definition at line 553 of file effort_display.h.
virtual void rviz::MessageFilterJointStateDisplay::fixedFrameChanged | ( | ) | [inline, protected, virtual] |
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
Reimplemented from rviz::Display.
Definition at line 609 of file effort_display.h.
void rviz::MessageFilterJointStateDisplay::incomingMessage | ( | const sensor_msgs::JointState::ConstPtr & | msg | ) | [inline, protected] |
Incoming message callback. Checks if the message pointer is valid, increments messages_received_, then calls processMessage().
Definition at line 618 of file effort_display.h.
virtual void rviz::MessageFilterJointStateDisplay::onDisable | ( | ) | [inline, protected, virtual] |
Derived classes override this to do the actual work of disabling themselves.
Reimplemented from rviz::Display.
Reimplemented in rviz::EffortDisplay.
Definition at line 603 of file effort_display.h.
virtual void rviz::MessageFilterJointStateDisplay::onEnable | ( | ) | [inline, protected, virtual] |
Derived classes override this to do the actual work of enabling themselves.
Reimplemented from rviz::Display.
Reimplemented in rviz::EffortDisplay.
Definition at line 598 of file effort_display.h.
virtual void rviz::MessageFilterJointStateDisplay::onInitialize | ( | ) | [inline, 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 from rviz::Display.
Reimplemented in rviz::EffortDisplay.
Definition at line 543 of file effort_display.h.
virtual void rviz::MessageFilterJointStateDisplay::processMessage | ( | const sensor_msgs::JointState::ConstPtr & | msg | ) | [protected, pure virtual] |
Implement this to process the contents of a message.
This is called by incomingMessage().
Implemented in rviz::EffortDisplay.
virtual void rviz::MessageFilterJointStateDisplay::reset | ( | ) | [inline, virtual] |
Called to tell the display to clear its state.
Reimplemented from rviz::Display.
Reimplemented in rviz::EffortDisplay.
Definition at line 559 of file effort_display.h.
virtual void rviz::MessageFilterJointStateDisplay::subscribe | ( | ) | [inline, protected, virtual] |
Definition at line 575 of file effort_display.h.
virtual void rviz::MessageFilterJointStateDisplay::unsubscribe | ( | ) | [inline, protected, virtual] |
Definition at line 593 of file effort_display.h.
virtual void rviz::MessageFilterJointStateDisplay::updateTopic | ( | ) | [inline, protected, virtual] |
Implements rviz::_RosTopicDisplay.
Definition at line 567 of file effort_display.h.
uint32_t rviz::MessageFilterJointStateDisplay::messages_received_ [protected] |
Definition at line 638 of file effort_display.h.
message_filters::Subscriber<sensor_msgs::JointState> rviz::MessageFilterJointStateDisplay::sub_ [protected] |
Definition at line 636 of file effort_display.h.
Definition at line 637 of file effort_display.h.