#include <wrench_display.h>

Public Member Functions | |
| virtual void | createProperties () | 
| virtual void | fixedFrameChanged () | 
| float | getAlpha () | 
| const rviz::Color & | getForceColor () | 
| int | getHistoryLength () const | 
| float | getScale () | 
| const std::string & | getTopic () | 
| const rviz::Color & | getTorqueColor () | 
| float | getWidth () | 
| virtual void | onInitialize () | 
| virtual void | reset () | 
| void | setAlpha (float alpha) | 
| void | setForceColor (const rviz::Color &color) | 
| void | setHistoryLength (int history_length) | 
| void | setScale (float scale) | 
| void | setTopic (const std::string &topic) | 
| void | setTorqueColor (const rviz::Color &color) | 
| void | setWidth (float width) | 
| WrenchStampedDisplay () | |
| virtual | ~WrenchStampedDisplay () | 
Protected Member Functions | |
| virtual void | onDisable () | 
| virtual void | onEnable () | 
Private Types | |
| typedef std::vector < WrenchStampedVisual * >  | MapWrenchStampedVisual | 
Private Member Functions | |
| void | clear () | 
| void | incomingMessage (const geometry_msgs::WrenchStamped::ConstPtr &msg) | 
| void | subscribe () | 
| void | unsubscribe () | 
| void | updateVisual () | 
Private Attributes | |
| float | alpha_ | 
| rviz::FloatPropertyWPtr | alpha_property_ | 
| rviz::Color | force_color_ | 
| rviz::ColorPropertyWPtr | force_color_property_ | 
| int | history_length_ | 
| rviz::IntPropertyWPtr | history_length_property_ | 
| int | messages_received_ | 
| float | scale_ | 
| rviz::FloatPropertyWPtr | scale_property_ | 
| Ogre::SceneNode * | scene_node_ | 
| message_filters::Subscriber < geometry_msgs::WrenchStamped >  | sub_ | 
| tf::MessageFilter < geometry_msgs::WrenchStamped > *  | tf_filter_ | 
| std::string | topic_ | 
| rviz::ROSTopicStringPropertyWPtr | topic_property_ | 
| rviz::Color | torque_color_ | 
| rviz::ColorPropertyWPtr | torque_color_property_ | 
| MapWrenchStampedVisual | visuals_ | 
| float | width_ | 
| rviz::FloatPropertyWPtr | width_property_ | 
Definition at line 19 of file wrench_display.h.
typedef std::vector<WrenchStampedVisual*> jsk_rviz_plugin::WrenchStampedDisplay::MapWrenchStampedVisual [private] | 
        
Definition at line 79 of file wrench_display.h.
Definition at line 20 of file wrench_display.cpp.
Definition at line 58 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::clear | ( | void | ) |  [private] | 
        
Definition at line 68 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::createProperties | ( | ) |  [virtual] | 
        
Reimplemented from rviz::Display.
Definition at line 297 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::fixedFrameChanged | ( | ) |  [virtual] | 
        
Reimplemented from rviz::Display.
Definition at line 240 of file wrench_display.cpp.
| float jsk_rviz_plugin::WrenchStampedDisplay::getAlpha | ( | ) |  [inline] | 
        
Definition at line 43 of file wrench_display.h.
| const rviz::Color& jsk_rviz_plugin::WrenchStampedDisplay::getForceColor | ( | ) |  [inline] | 
        
Definition at line 39 of file wrench_display.h.
| int jsk_rviz_plugin::WrenchStampedDisplay::getHistoryLength | ( | ) |  const [inline] | 
        
Definition at line 46 of file wrench_display.h.
| float jsk_rviz_plugin::WrenchStampedDisplay::getScale | ( | void | ) |  [inline] | 
        
Definition at line 49 of file wrench_display.h.
| const std::string& jsk_rviz_plugin::WrenchStampedDisplay::getTopic | ( | ) |  [inline] | 
        
Definition at line 35 of file wrench_display.h.
| const rviz::Color& jsk_rviz_plugin::WrenchStampedDisplay::getTorqueColor | ( | ) |  [inline] | 
        
Definition at line 40 of file wrench_display.h.
| float jsk_rviz_plugin::WrenchStampedDisplay::getWidth | ( | ) |  [inline] | 
        
Definition at line 52 of file wrench_display.h.
| void jsk_rviz_plugin::WrenchStampedDisplay::incomingMessage | ( | const geometry_msgs::WrenchStamped::ConstPtr & | msg | ) |  [private] | 
        
Definition at line 247 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::onDisable | ( | ) |  [protected, virtual] | 
        
Implements rviz::Display.
Definition at line 232 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::onEnable | ( | ) |  [protected, virtual] | 
        
Implements rviz::Display.
Definition at line 227 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::onInitialize | ( | ) |  [virtual] | 
        
Reimplemented from rviz::Display.
Definition at line 32 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::reset | ( | ) |  [virtual] | 
        
Reimplemented from rviz::Display.
Definition at line 291 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::setAlpha | ( | float | alpha | ) | 
Definition at line 111 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::setForceColor | ( | const rviz::Color & | color | ) | 
Definition at line 93 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::setHistoryLength | ( | int | history_length | ) | 
Definition at line 153 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::setScale | ( | float | scale | ) | 
Definition at line 120 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::setTopic | ( | const std::string & | topic | ) | 
Definition at line 79 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::setTorqueColor | ( | const rviz::Color & | color | ) | 
Definition at line 102 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::setWidth | ( | float | width | ) | 
Definition at line 129 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::subscribe | ( | ) |  [private] | 
        
Definition at line 199 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::unsubscribe | ( | ) |  [private] | 
        
Definition at line 222 of file wrench_display.cpp.
| void jsk_rviz_plugin::WrenchStampedDisplay::updateVisual | ( | ) |  [private] | 
        
Definition at line 139 of file wrench_display.cpp.
float jsk_rviz_plugin::WrenchStampedDisplay::alpha_ [private] | 
        
Definition at line 93 of file wrench_display.h.
rviz::FloatPropertyWPtr jsk_rviz_plugin::WrenchStampedDisplay::alpha_property_ [private] | 
        
Definition at line 99 of file wrench_display.h.
Definition at line 91 of file wrench_display.h.
rviz::ColorPropertyWPtr jsk_rviz_plugin::WrenchStampedDisplay::force_color_property_ [private] | 
        
Definition at line 97 of file wrench_display.h.
int jsk_rviz_plugin::WrenchStampedDisplay::history_length_ [private] | 
        
Definition at line 94 of file wrench_display.h.
rviz::IntPropertyWPtr jsk_rviz_plugin::WrenchStampedDisplay::history_length_property_ [private] | 
        
Definition at line 100 of file wrench_display.h.
Definition at line 88 of file wrench_display.h.
float jsk_rviz_plugin::WrenchStampedDisplay::scale_ [private] | 
        
Definition at line 93 of file wrench_display.h.
rviz::FloatPropertyWPtr jsk_rviz_plugin::WrenchStampedDisplay::scale_property_ [private] | 
        
Definition at line 99 of file wrench_display.h.
Ogre::SceneNode* jsk_rviz_plugin::WrenchStampedDisplay::scene_node_ [private] | 
        
Definition at line 83 of file wrench_display.h.
message_filters::Subscriber<geometry_msgs::WrenchStamped> jsk_rviz_plugin::WrenchStampedDisplay::sub_ [private] | 
        
Definition at line 86 of file wrench_display.h.
tf::MessageFilter<geometry_msgs::WrenchStamped>* jsk_rviz_plugin::WrenchStampedDisplay::tf_filter_ [private] | 
        
Definition at line 87 of file wrench_display.h.
Definition at line 92 of file wrench_display.h.
rviz::ROSTopicStringPropertyWPtr jsk_rviz_plugin::WrenchStampedDisplay::topic_property_ [private] | 
        
Definition at line 98 of file wrench_display.h.
Definition at line 91 of file wrench_display.h.
rviz::ColorPropertyWPtr jsk_rviz_plugin::WrenchStampedDisplay::torque_color_property_ [private] | 
        
Definition at line 97 of file wrench_display.h.
Definition at line 80 of file wrench_display.h.
float jsk_rviz_plugin::WrenchStampedDisplay::width_ [private] | 
        
Definition at line 93 of file wrench_display.h.
rviz::FloatPropertyWPtr jsk_rviz_plugin::WrenchStampedDisplay::width_property_ [private] | 
        
Definition at line 99 of file wrench_display.h.