#include <effort_display.h>

Public Member Functions | |
| virtual void | createProperties () | 
| EffortDisplay () | |
| virtual void | fixedFrameChanged () | 
| bool | getAllEnabled () | 
| float | getAlpha () | 
| int | getHistoryLength () const | 
| std::string & | getRobotDescription () | 
| float | getScale () | 
| const std::string & | getTopic () | 
| float | getWidth () | 
| void | load () | 
| virtual void | onInitialize () | 
| virtual void | reset () | 
| void | setAllEnabled (bool enabled) | 
| void | setAlpha (float alpha) | 
| void | setHistoryLength (int history_length) | 
| void | setJointEnabled (JointInfo *joint, bool enabled) | 
| void | setRobotDescription (const std::string &description_param) | 
| void | setScale (float scale) | 
| void | setTopic (const std::string &topic) | 
| void | setWidth (float width) | 
| virtual | ~EffortDisplay () | 
Protected Member Functions | |
| JointInfo * | createJoint (const std::string &joint) | 
| void | deleteJoint (JointInfo *joint, bool delete_properties) | 
| JointInfo * | getJointInfo (const std::string &joint) | 
| virtual void | onDisable () | 
| virtual void | onEnable () | 
| void | updateJoint (JointInfo *joint) | 
Private Types | |
| typedef std::map< std::string,  JointInfo * >  | M_JointInfo | 
| typedef std::vector < EffortVisual * >  | MapEffortVisual | 
Private Member Functions | |
| void | clear () | 
| void | incomingMessage (const sensor_msgs::JointState::ConstPtr &msg) | 
| void | subscribe () | 
| void | unsubscribe () | 
| void | updateColorAndAlpha () | 
Private Attributes | |
| bool | all_enabled_ | 
| rviz::BoolPropertyWPtr | all_enabled_property_ | 
| float | alpha_ | 
| rviz::FloatPropertyWPtr | alpha_property_ | 
| std::string | description_param_ | 
| int | history_length_ | 
| rviz::IntPropertyWPtr | history_length_property_ | 
| M_JointInfo | joints_ | 
| rviz::CategoryPropertyWPtr | joints_category_ | 
| int | messages_received_ | 
| rviz::StringPropertyWPtr | robot_description_property_ | 
| float | scale_ | 
| rviz::FloatPropertyWPtr | scale_property_ | 
| Ogre::SceneNode * | scene_node_ | 
| message_filters::Subscriber < sensor_msgs::JointState >  | sub_ | 
| tf::MessageFilterJointState * | tf_filter_ | 
| std::string | topic_ | 
| rviz::ROSTopicStringPropertyWPtr | topic_property_ | 
| boost::shared_ptr< urdf::Model > | urdfModel | 
| MapEffortVisual | visuals_ | 
| float | width_ | 
| rviz::FloatPropertyWPtr | width_property_ | 
Definition at line 33 of file effort_display.h.
typedef std::map<std::string, JointInfo*> jsk_rviz_plugin::EffortDisplay::M_JointInfo [private] | 
        
Definition at line 116 of file effort_display.h.
typedef std::vector<EffortVisual*> jsk_rviz_plugin::EffortDisplay::MapEffortVisual [private] | 
        
Definition at line 105 of file effort_display.h.
Definition at line 569 of file effort_display.cpp.
| jsk_rviz_plugin::EffortDisplay::~EffortDisplay | ( | ) |  [virtual] | 
        
Definition at line 607 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::clear | ( | void | ) |  [private] | 
        
Definition at line 617 of file effort_display.cpp.
| JointInfo * jsk_rviz_plugin::EffortDisplay::createJoint | ( | const std::string & | joint | ) |  [protected] | 
        
Definition at line 532 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::createProperties | ( | ) |  [virtual] | 
        
Reimplemented from rviz::Display.
Definition at line 927 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::deleteJoint | ( | JointInfo * | joint, | 
| bool | delete_properties | ||
| ) |  [protected] | 
        
Definition at line 565 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::fixedFrameChanged | ( | ) |  [virtual] | 
        
Reimplemented from rviz::Display.
Definition at line 832 of file effort_display.cpp.
| bool jsk_rviz_plugin::EffortDisplay::getAllEnabled | ( | ) |  [inline] | 
        
Definition at line 67 of file effort_display.h.
| float jsk_rviz_plugin::EffortDisplay::getAlpha | ( | ) |  [inline] | 
        
Definition at line 52 of file effort_display.h.
| int jsk_rviz_plugin::EffortDisplay::getHistoryLength | ( | ) |  const [inline] | 
        
Definition at line 61 of file effort_display.h.
| JointInfo * jsk_rviz_plugin::EffortDisplay::getJointInfo | ( | const std::string & | joint | ) |  [protected] | 
        
Definition at line 515 of file effort_display.cpp.
Definition at line 65 of file effort_display.h.
| float jsk_rviz_plugin::EffortDisplay::getScale | ( | void | ) |  [inline] | 
        
Definition at line 58 of file effort_display.h.
| const std::string& jsk_rviz_plugin::EffortDisplay::getTopic | ( | ) |  [inline] | 
        
Definition at line 49 of file effort_display.h.
| float jsk_rviz_plugin::EffortDisplay::getWidth | ( | ) |  [inline] | 
        
Definition at line 55 of file effort_display.h.
| void jsk_rviz_plugin::EffortDisplay::incomingMessage | ( | const sensor_msgs::JointState::ConstPtr & | msg | ) |  [private] | 
        
Definition at line 839 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::load | ( | ) | 
Definition at line 728 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::onDisable | ( | ) |  [protected, virtual] | 
        
Implements rviz::Display.
Definition at line 824 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::onEnable | ( | ) |  [protected, virtual] | 
        
Implements rviz::Display.
Definition at line 819 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::onInitialize | ( | ) |  [virtual] | 
        
Reimplemented from rviz::Display.
Definition at line 580 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::reset | ( | ) |  [virtual] | 
        
Reimplemented from rviz::Display.
Definition at line 921 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::setAllEnabled | ( | bool | enabled | ) | 
Definition at line 768 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::setAlpha | ( | float | alpha | ) | 
Definition at line 642 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::setHistoryLength | ( | int | history_length | ) | 
Definition at line 682 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::setJointEnabled | ( | JointInfo * | joint, | 
| bool | enabled | ||
| ) | 
Definition at line 526 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::setRobotDescription | ( | const std::string & | description_param | ) | 
Definition at line 753 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::setScale | ( | float | scale | ) | 
Definition at line 660 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::setTopic | ( | const std::string & | topic | ) | 
Definition at line 628 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::setWidth | ( | float | width | ) | 
Definition at line 651 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::subscribe | ( | ) |  [private] | 
        
Definition at line 785 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::unsubscribe | ( | ) |  [private] | 
        
Definition at line 814 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::updateColorAndAlpha | ( | ) |  [private] | 
        
Definition at line 670 of file effort_display.cpp.
| void jsk_rviz_plugin::EffortDisplay::updateJoint | ( | JointInfo * | joint | ) |  [protected] | 
        
Definition at line 561 of file effort_display.cpp.
Definition at line 123 of file effort_display.h.
rviz::BoolPropertyWPtr jsk_rviz_plugin::EffortDisplay::all_enabled_property_ [private] | 
        
Definition at line 132 of file effort_display.h.
float jsk_rviz_plugin::EffortDisplay::alpha_ [private] | 
        
Definition at line 121 of file effort_display.h.
rviz::FloatPropertyWPtr jsk_rviz_plugin::EffortDisplay::alpha_property_ [private] | 
        
Definition at line 127 of file effort_display.h.
Definition at line 120 of file effort_display.h.
int jsk_rviz_plugin::EffortDisplay::history_length_ [private] | 
        
Definition at line 122 of file effort_display.h.
rviz::IntPropertyWPtr jsk_rviz_plugin::EffortDisplay::history_length_property_ [private] | 
        
Definition at line 128 of file effort_display.h.
Definition at line 117 of file effort_display.h.
rviz::CategoryPropertyWPtr jsk_rviz_plugin::EffortDisplay::joints_category_ [private] | 
        
Definition at line 131 of file effort_display.h.
int jsk_rviz_plugin::EffortDisplay::messages_received_ [private] | 
        
Definition at line 114 of file effort_display.h.
rviz::StringPropertyWPtr jsk_rviz_plugin::EffortDisplay::robot_description_property_ [private] | 
        
Definition at line 130 of file effort_display.h.
float jsk_rviz_plugin::EffortDisplay::scale_ [private] | 
        
Definition at line 121 of file effort_display.h.
rviz::FloatPropertyWPtr jsk_rviz_plugin::EffortDisplay::scale_property_ [private] | 
        
Definition at line 127 of file effort_display.h.
Ogre::SceneNode* jsk_rviz_plugin::EffortDisplay::scene_node_ [private] | 
        
Definition at line 109 of file effort_display.h.
message_filters::Subscriber<sensor_msgs::JointState> jsk_rviz_plugin::EffortDisplay::sub_ [private] | 
        
Definition at line 112 of file effort_display.h.
Definition at line 113 of file effort_display.h.
Definition at line 120 of file effort_display.h.
rviz::ROSTopicStringPropertyWPtr jsk_rviz_plugin::EffortDisplay::topic_property_ [private] | 
        
Definition at line 126 of file effort_display.h.
boost::shared_ptr<urdf::Model> jsk_rviz_plugin::EffortDisplay::urdfModel [private] | 
        
Definition at line 135 of file effort_display.h.
Definition at line 106 of file effort_display.h.
float jsk_rviz_plugin::EffortDisplay::width_ [private] | 
        
Definition at line 121 of file effort_display.h.
rviz::FloatPropertyWPtr jsk_rviz_plugin::EffortDisplay::width_property_ [private] | 
        
Definition at line 127 of file effort_display.h.