#include <wrench_display.h>
Public Member Functions | |
WrenchStampedDisplay () | |
virtual | ~WrenchStampedDisplay () |
Protected Member Functions | |
virtual void | onInitialize () |
Override this function to do subclass-specific initialization. | |
virtual void | reset () |
Called to tell the display to clear its state. | |
Private Slots | |
void | updateColorAndAlpha () |
void | updateHistoryLength () |
Private Member Functions | |
void | processMessage (const geometry_msgs::WrenchStamped::ConstPtr &msg) |
Private Attributes | |
rviz::FloatProperty * | alpha_property_ |
rviz::ColorProperty * | force_color_property_ |
rviz::FloatProperty * | force_scale_property_ |
rviz::IntProperty * | history_length_property_ |
rviz::ColorProperty * | torque_color_property_ |
rviz::FloatProperty * | torque_scale_property_ |
boost::circular_buffer < boost::shared_ptr < WrenchStampedVisual > > | visuals_ |
rviz::FloatProperty * | width_property_ |
Definition at line 27 of file wrench_display.h.
Definition at line 21 of file wrench_display.cpp.
rviz::WrenchStampedDisplay::~WrenchStampedDisplay | ( | ) | [virtual] |
Definition at line 69 of file wrench_display.cpp.
void rviz::WrenchStampedDisplay::onInitialize | ( | ) | [protected, 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::MessageFilterDisplay< geometry_msgs::WrenchStamped >.
Definition at line 63 of file wrench_display.cpp.
void rviz::WrenchStampedDisplay::processMessage | ( | const geometry_msgs::WrenchStamped::ConstPtr & | msg | ) | [private] |
Definition at line 111 of file wrench_display.cpp.
void rviz::WrenchStampedDisplay::reset | ( | ) | [protected, virtual] |
Called to tell the display to clear its state.
Reimplemented from rviz::MessageFilterDisplay< geometry_msgs::WrenchStamped >.
Definition at line 74 of file wrench_display.cpp.
void rviz::WrenchStampedDisplay::updateColorAndAlpha | ( | ) | [private, slot] |
Definition at line 80 of file wrench_display.cpp.
void rviz::WrenchStampedDisplay::updateHistoryLength | ( | ) | [private, slot] |
Definition at line 100 of file wrench_display.cpp.
Definition at line 57 of file wrench_display.h.
Definition at line 56 of file wrench_display.h.
Definition at line 57 of file wrench_display.h.
Definition at line 58 of file wrench_display.h.
Definition at line 56 of file wrench_display.h.
Definition at line 57 of file wrench_display.h.
boost::circular_buffer<boost::shared_ptr<WrenchStampedVisual> > rviz::WrenchStampedDisplay::visuals_ [private] |
Definition at line 53 of file wrench_display.h.
Definition at line 57 of file wrench_display.h.