#include <target_visualizer_display.h>

| Public Types | |
| enum | ShapeType { SimpleCircle, GISCircle } | 
| Public Member Functions | |
| TargetVisualizerDisplay () | |
| virtual | ~TargetVisualizerDisplay () | 
| Protected Member Functions | |
| virtual void | onEnable () | 
| virtual void | onInitialize () | 
| void | processMessage (const geometry_msgs::PoseStamped::ConstPtr &msg) | 
| virtual void | reset () | 
| void | update (float wall_dt, float ros_dt) | 
| Protected Attributes | |
| double | alpha_ | 
| rviz::FloatProperty * | alpha_property_ | 
| QColor | color_ | 
| rviz::ColorProperty * | color_property_ | 
| ShapeType | current_type_ | 
| bool | message_recieved_ | 
| boost::mutex | mutex_ | 
| double | radius_ | 
| rviz::FloatProperty * | radius_property_ | 
| rviz::EnumProperty * | shape_type_property_ | 
| std::string | target_name_ | 
| rviz::StringProperty * | target_name_property_ | 
| FacingObject::Ptr | visualizer_ | 
| Private Slots | |
| void | updateAlpha () | 
| void | updateColor () | 
| void | updateRadius () | 
| void | updateShapeType () | 
| void | updateTargetName () | 
Definition at line 62 of file target_visualizer_display.h.
Definition at line 69 of file target_visualizer_display.h.
Definition at line 48 of file target_visualizer_display.cpp.
Definition at line 79 of file target_visualizer_display.cpp.
| void jsk_rviz_plugin::TargetVisualizerDisplay::onEnable | ( | ) |  [protected, virtual] | 
Reimplemented from rviz::MessageFilterDisplay< geometry_msgs::PoseStamped >.
Definition at line 87 of file target_visualizer_display.cpp.
| void jsk_rviz_plugin::TargetVisualizerDisplay::onInitialize | ( | ) |  [protected, virtual] | 
Reimplemented from rviz::MessageFilterDisplay< geometry_msgs::PoseStamped >.
Definition at line 126 of file target_visualizer_display.cpp.
| void jsk_rviz_plugin::TargetVisualizerDisplay::processMessage | ( | const geometry_msgs::PoseStamped::ConstPtr & | msg | ) |  [protected] | 
Definition at line 94 of file target_visualizer_display.cpp.
| void jsk_rviz_plugin::TargetVisualizerDisplay::reset | ( | ) |  [protected, virtual] | 
Reimplemented from rviz::MessageFilterDisplay< geometry_msgs::PoseStamped >.
Definition at line 138 of file target_visualizer_display.cpp.
| void jsk_rviz_plugin::TargetVisualizerDisplay::update | ( | float | wall_dt, | 
| float | ros_dt | ||
| ) |  [protected, virtual] | 
Reimplemented from rviz::Display.
Definition at line 117 of file target_visualizer_display.cpp.
| void jsk_rviz_plugin::TargetVisualizerDisplay::updateAlpha | ( | ) |  [private, slot] | 
Definition at line 163 of file target_visualizer_display.cpp.
| void jsk_rviz_plugin::TargetVisualizerDisplay::updateColor | ( | ) |  [private, slot] | 
Definition at line 172 of file target_visualizer_display.cpp.
| void jsk_rviz_plugin::TargetVisualizerDisplay::updateRadius | ( | ) |  [private, slot] | 
Definition at line 154 of file target_visualizer_display.cpp.
| void jsk_rviz_plugin::TargetVisualizerDisplay::updateShapeType | ( | ) |  [private, slot] | 
Definition at line 181 of file target_visualizer_display.cpp.
| void jsk_rviz_plugin::TargetVisualizerDisplay::updateTargetName | ( | ) |  [private, slot] | 
Definition at line 145 of file target_visualizer_display.cpp.
| double jsk_rviz_plugin::TargetVisualizerDisplay::alpha_  [protected] | 
Definition at line 90 of file target_visualizer_display.h.
Definition at line 82 of file target_visualizer_display.h.
| QColor jsk_rviz_plugin::TargetVisualizerDisplay::color_  [protected] | 
Definition at line 91 of file target_visualizer_display.h.
Definition at line 83 of file target_visualizer_display.h.
Definition at line 94 of file target_visualizer_display.h.
| bool jsk_rviz_plugin::TargetVisualizerDisplay::message_recieved_  [protected] | 
Definition at line 93 of file target_visualizer_display.h.
| boost::mutex jsk_rviz_plugin::TargetVisualizerDisplay::mutex_  [protected] | 
Definition at line 88 of file target_visualizer_display.h.
| double jsk_rviz_plugin::TargetVisualizerDisplay::radius_  [protected] | 
Definition at line 92 of file target_visualizer_display.h.
Definition at line 84 of file target_visualizer_display.h.
Definition at line 85 of file target_visualizer_display.h.
Definition at line 89 of file target_visualizer_display.h.
Definition at line 81 of file target_visualizer_display.h.
Definition at line 86 of file target_visualizer_display.h.