fps_motion_tool.h
Go to the documentation of this file.
00001 /*
00002  * UOS-ROS packages - Robot Operating System code by the University of Osnabrück
00003  * Copyright (C) 2014 University of Osnabrück
00004  *
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
00008  *
00009  * 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
00010  *
00011  * 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in
00012  * the documentation and/or other materials provided with the distribution.
00013  *
00014  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT
00015  * NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
00016  * THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00017  * DAMAGES  (INCLUDING,  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
00018  * BUSINESS  INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00019  * (INCLUDING NEGLIGENCE   OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00020  *
00021  * fps_motion_tool.h
00022  *
00023  *  Author: Henning Deeken <hdeeken@uos.de>
00024  *
00025  */
00026 
00027 #ifndef RVIZ_FPS_MOTION_TOOL_H
00028 #define RVIZ_FPS_MOTION_TOOL_H
00029 
00030 #include <map>
00031 #include <vector>
00032 
00033 #include <QIcon>
00034 #include <QMessageBox>
00035 #include <QApplication>
00036 
00037 #include <ros/console.h>
00038 #include <rviz/viewport_mouse_event.h>
00039 #include <rviz/visualization_manager.h>
00040 #include <rviz/geometry.h>
00041 #include <rviz/properties/vector_property.h>
00042 #include <rviz/properties/float_property.h>
00043 #include <rviz/properties/enum_property.h>
00044 #include <rviz/properties/bool_property.h>
00045 #include <rviz/tool.h>
00046 #include <rviz/tool_manager.h>
00047 #include <rviz/display_group.h>
00048 #include <rviz/display_context.h>
00049 #include <rviz/render_panel.h>
00050 #include <rviz/viewport_mouse_event.h>
00051 #include <rviz/selection/selection_manager.h>
00052 #include <rviz/view_controller.h>
00053 #include <rviz/view_manager.h>
00054 #include <rviz/load_resource.h>
00055 
00056 #include <rviz/default_plugin/tools/move_tool.h>
00057 
00058 #include <fps_motion_view_controller.h>
00059 
00067 namespace Ogre
00068 {
00069 class SceneNode;
00070 class Vector3;
00071 }
00072 
00073 namespace rviz
00074 {
00075 
00076 class FPSMotionConfigWidget;
00077 class FPSMotionTool: public rviz::Tool
00078 {
00079 Q_OBJECT
00080 
00081 public:
00082   FPSMotionTool();
00083   ~FPSMotionTool();
00084   virtual void onInitialize();
00085   virtual void activate();
00086   virtual void deactivate();
00087 
00088   virtual int processKeyEvent(QKeyEvent* event, rviz::RenderPanel* panel);
00089   virtual int processMouseEvent(rviz::ViewportMouseEvent& event);
00090 
00091 private Q_SLOTS:
00092 
00093   void setOffset(){ m_pos_offset = (double) step_length_property_->getFloat(); }
00094   void setBoost()
00095   {
00096     if(boost_property_->getFloat() < 0.0)
00097     {
00098       m_boost = 0.0;
00099     }
00100     else if(boost_property_->getFloat() > 1.0)
00101     {
00102       m_boost = 1.0;
00103     }
00104     else
00105     {
00106       m_boost = (double) boost_property_->getFloat();
00107     }
00108   }
00109 
00110   void setFlyMode(){ m_fly_mode = fly_property_->getBool(); }
00111   void setLeftHandMode(){ m_left_hand_mode = left_hand_property_->getBool(); }
00112   void setFallbackTool(){ m_fallback_tool = m_tools.at(fallback_tool_property_->getOptionInt()); }
00113   void setFallbackViewController(){ m_fallback_view_controller = m_view_controller_classes.at(fallback_view_controller_property_->getOptionInt()); }
00114 
00115 private:
00116   Ogre::SceneNode* m_sceneNode;
00117 
00118   bool m_fly_mode;
00119   bool m_left_hand_mode;
00120   bool m_removed_select;
00121 
00122   double m_pos_offset;
00123   double m_boost;
00124 
00125   QStringList m_tool_classes;
00126   std::vector<Tool*> m_tools;
00127   Tool* m_fallback_tool;
00128 
00129   QStringList m_view_controller_classes;
00130   QString m_fallback_view_controller;
00131   std::vector<ViewController*> m_view_controller;
00132 
00133   FloatProperty* step_length_property_;
00134   FloatProperty* boost_property_;
00135   BoolProperty* fly_property_;
00136   BoolProperty* left_hand_property_;
00137   EnumProperty* fallback_tool_property_;
00138   EnumProperty* fallback_view_controller_property_;
00139 
00140   void setFallbackToolProperty();
00141   void setFallbackViewControllerProperty();
00142 };
00143 } // end namespace rviz
00144 #endif


rviz_fps_plugin
Author(s): hdeeken
autogenerated on Wed Aug 26 2015 16:17:06