Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 #ifndef JSK_RVIZ_PLUGIN_OVERLAY_PICKER_TOOL_H_
00037 #define JSK_RVIZ_PLUGIN_OVERLAY_PICKER_TOOL_H_
00038 
00039 #include <rviz/tool.h>
00040 #include <rviz/properties/property.h>
00041 #include <rviz/properties/property_tree_model.h>
00042 #include <rviz/viewport_mouse_event.h>
00043 #include <rviz/render_panel.h>
00044 
00045 namespace jsk_rviz_plugins
00046 {
00047   class OverlayPickerTool: public rviz::Tool
00048   {
00049   public:
00050     OverlayPickerTool();
00051     virtual void activate() {}
00052     virtual void deactivate() {};
00053     virtual int processKeyEvent(QKeyEvent* event, rviz::RenderPanel* panel);
00054     virtual int processMouseEvent(rviz::ViewportMouseEvent& event);
00055     template <class T>
00056     T* isPropertyType(rviz::Property* p)
00057     {
00058       try {
00059         return dynamic_cast<T*>(p);
00060       }
00061       catch (const std::bad_cast& e) {
00062         return NULL;
00063       }
00064     }
00065 
00066     template <class T>
00067     bool startMovement(rviz::Property* property,
00068                        rviz::ViewportMouseEvent& event, const std::string& type)
00069     {
00070       if (isPropertyType<T>(property)) {
00071         bool res = isPropertyType<T>(property)->isInRegion(event.x, event.y);
00072         if (res) {
00073           target_property_ = property;
00074           target_property_type_ = type;
00075           move_offset_x_ = event.x - isPropertyType<T>(property)->getX();
00076           move_offset_y_ = event.y - isPropertyType<T>(property)->getY();
00077         }
00078         return res;
00079       }
00080       else {
00081         return false;
00082       }
00083     }
00084     
00085     template <class T>
00086     void movePosition(rviz::ViewportMouseEvent& event)
00087     {
00088       if (shift_pressing_) {
00089         int orig_x = event.x - move_offset_x_;
00090         int orig_y = event.y - move_offset_y_;
00091         isPropertyType<T>(target_property_)->movePosition(
00092           20 * (orig_x / 20), 20 * (orig_y / 20));
00093       }
00094       else {
00095         isPropertyType<T>(target_property_)->movePosition(
00096           event.x - move_offset_x_, event.y - move_offset_y_);
00097       }
00098     }
00099 
00100     template <class T>
00101     void setPosition(rviz::ViewportMouseEvent& event)
00102     {
00103       if (shift_pressing_) {
00104         int orig_x = event.x - move_offset_x_;
00105         int orig_y = event.y - move_offset_y_;
00106         isPropertyType<T>(target_property_)->setPosition(
00107           20 * (orig_x / 20), 20 * (orig_y / 20));
00108       }
00109       else {
00110         isPropertyType<T>(target_property_)->setPosition(
00111           event.x - move_offset_x_, event.y - move_offset_y_);
00112       }
00113     }
00114     
00115   protected:
00116     virtual void onClicked(rviz::ViewportMouseEvent& event);
00117     virtual void onMove(rviz::ViewportMouseEvent& event);
00118     virtual void onRelease(rviz::ViewportMouseEvent& event);
00119     virtual bool handleDisplayClick(rviz::Property* property, rviz::ViewportMouseEvent& event);
00120 
00121     bool is_moving_;
00122     rviz::Property* target_property_;
00123     std::string target_property_type_;
00124     int move_offset_x_, move_offset_y_;
00125     bool shift_pressing_;
00126   private:
00127     
00128   };
00129 }
00130 
00131 #endif