Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Slots | Private Member Functions | Private Attributes
rviz::EffortDisplay Class Reference

#include <effort_display.h>

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

List of all members.

Public Member Functions

 EffortDisplay ()
virtual void onInitialize ()
 Override this function to do subclass-specific initialization.
virtual void reset ()
 Called to tell the display to clear its state.
virtual ~EffortDisplay ()

Protected Member Functions

void clear ()
void load ()
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.

Protected Attributes

std::string robot_description_
boost::shared_ptr< urdf::Modelrobot_model_

Private Types

typedef std::map< std::string,
JointInfo * > 
M_JointInfo

Private Slots

JointInfocreateJoint (const std::string &joint)
JointInfogetJointInfo (const std::string &joint)
void updateColorAndAlpha ()
void updateHistoryLength ()
void updateRobotDescription ()

Private Member Functions

void processMessage (const sensor_msgs::JointState::ConstPtr &msg)

Private Attributes

rviz::BoolPropertyall_enabled_property_
rviz::FloatPropertyalpha_property_
rviz::IntPropertyhistory_length_property_
M_JointInfo joints_
rviz::Propertyjoints_category_
rviz::StringPropertyrobot_description_property_
rviz::FloatPropertyscale_property_
boost::circular_buffer
< boost::shared_ptr
< EffortVisual > > 
visuals_
rviz::FloatPropertywidth_property_

Detailed Description

Definition at line 661 of file effort_display.h.


Member Typedef Documentation

typedef std::map<std::string, JointInfo*> rviz::EffortDisplay::M_JointInfo [private]

Definition at line 705 of file effort_display.h.


Constructor & Destructor Documentation

Definition at line 81 of file effort_display.cpp.

Definition at line 122 of file effort_display.cpp.


Member Function Documentation

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

Definition at line 134 of file effort_display.cpp.

JointInfo * rviz::EffortDisplay::createJoint ( const std::string &  joint) [private, slot]

Definition at line 73 of file effort_display.cpp.

JointInfo * rviz::EffortDisplay::getJointInfo ( const std::string &  joint) [private, slot]

Definition at line 62 of file effort_display.cpp.

void rviz::EffortDisplay::load ( ) [protected]

Definition at line 168 of file effort_display.cpp.

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

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

Reimplemented from rviz::MessageFilterJointStateDisplay.

Definition at line 229 of file effort_display.cpp.

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

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

Reimplemented from rviz::MessageFilterJointStateDisplay.

Definition at line 224 of file effort_display.cpp.

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::MessageFilterJointStateDisplay.

Definition at line 116 of file effort_display.cpp.

void rviz::EffortDisplay::processMessage ( const sensor_msgs::JointState::ConstPtr &  msg) [private]

Definition at line 268 of file effort_display.cpp.

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

Called to tell the display to clear its state.

Reimplemented from rviz::MessageFilterJointStateDisplay.

Definition at line 128 of file effort_display.cpp.

void rviz::EffortDisplay::updateColorAndAlpha ( ) [private, slot]

Definition at line 141 of file effort_display.cpp.

void rviz::EffortDisplay::updateHistoryLength ( ) [private, slot]

Definition at line 163 of file effort_display.cpp.

Definition at line 153 of file effort_display.cpp.


Member Data Documentation

Definition at line 714 of file effort_display.h.

Definition at line 709 of file effort_display.h.

Definition at line 710 of file effort_display.h.

Definition at line 706 of file effort_display.h.

Definition at line 713 of file effort_display.h.

std::string rviz::EffortDisplay::robot_description_ [protected]

Definition at line 696 of file effort_display.h.

Definition at line 712 of file effort_display.h.

boost::shared_ptr<urdf::Model> rviz::EffortDisplay::robot_model_ [protected]

Definition at line 693 of file effort_display.h.

Definition at line 709 of file effort_display.h.

boost::circular_buffer<boost::shared_ptr<EffortVisual> > rviz::EffortDisplay::visuals_ [private]

Definition at line 703 of file effort_display.h.

Definition at line 709 of file effort_display.h.


The documentation for this class was generated from the following files:


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:36