fps_motion_tool.cpp
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.cpp
00022  *
00023  * Author: Henning Deeken {hdeeken@uos.de}
00024  *
00025  */
00026 
00027 #include <fps_motion_tool.h>
00028 
00029 namespace rviz
00030 {
00031 
00032 FPSMotionTool::FPSMotionTool()
00033 {
00034   shortcut_key_ = 'q';
00035 }
00036 
00037 FPSMotionTool::~FPSMotionTool() {}
00038 
00039 void FPSMotionTool::onInitialize()
00040 {
00041   setName( "FPS Motion" );
00042 
00043   step_length_property_ = new FloatProperty( "Step Length", 0.1,
00044                                                             "The length by with the position is updated on each step.",
00045                                                             getPropertyContainer(), SLOT( setOffset() ), this );
00046 
00047   boost_property_ = new FloatProperty( "Boost Property", 0.5,
00048                                                             "Gives the boost factor which is applied if pressing shift.",
00049                                                             getPropertyContainer(), SLOT( setBoost() ), this );
00050 
00051   fly_property_ = new BoolProperty( "Fly Mode", false,
00052                                                             "In fly mode it is possible to move along the z axis as well.",
00053                                                             getPropertyContainer(), SLOT( setFlyMode() ), this );
00054 
00055   left_hand_property_ = new BoolProperty( "Left Hand Mode", false,
00056                                                             "In left hand mode one uses the arrows to move around, instead of wasd.",
00057                                                             getPropertyContainer(), SLOT( setLeftHandMode() ), this );
00058 
00059   fallback_tool_property_ = new EnumProperty( "Fallback Tool", QString("rviz/Interact"),
00060                                                             "Determines to which tool the control switches, if the tool is deactivated.",
00061                                                             getPropertyContainer(), SLOT( setFallbackTool() ), this );
00062 
00063   fallback_view_controller_property_ = new EnumProperty( "Fallback ViewController", QString("rviz/Orbit"),
00064                                                             "Determines to which view controller the control switches, if the tool is deactivated.",
00065                                                             getPropertyContainer(), SLOT( setFallbackViewController() ), this );
00066   m_pos_offset = 0.1;
00067   m_boost = 0.5;
00068   m_fly_mode = false;
00069   m_left_hand_mode = false;
00070 
00071   setFallbackToolProperty();
00072   setFallbackViewControllerProperty();
00073 }
00074 
00075 void FPSMotionTool::setFallbackViewControllerProperty()
00076 {
00077   fallback_view_controller_property_->clearOptions();
00078   m_view_controller_classes.clear();
00079 
00080   m_view_controller_classes = context_->getViewManager()->getFactory()->getDeclaredClassIds();
00081 
00082   for( int i = 0; i < m_view_controller_classes.size(); i++ )
00083   {
00084     if(m_view_controller_classes[i] != QString("rviz/FPSMotion"))
00085     {
00086       fallback_view_controller_property_->addOption(m_view_controller_classes[i], i);
00087       m_view_controller.push_back(context_->getViewManager()->getViewAt(i));
00088     }
00089 
00090   }
00091 
00092   fallback_view_controller_property_->show();
00093   setFallbackViewController();
00094 }
00095 
00096 void FPSMotionTool::setFallbackToolProperty()
00097 {
00098   fallback_tool_property_->clearOptions();
00099   m_tools.clear();
00100 
00101   m_tool_classes = context_->getToolManager()->getToolClasses();
00102 
00103   for(int i = 0; i < m_tool_classes.size(); i++)
00104   {
00105     if(m_tool_classes[i] != getClassId())
00106     {
00107       fallback_tool_property_->addOption(m_tool_classes[i], i);
00108       m_tools.push_back(context_->getToolManager()->getTool(i));
00109     }
00110   }
00111 
00112   fallback_tool_property_->show();
00113   setFallbackTool();
00114 }
00115 
00116 void FPSMotionTool::activate()
00117 {
00118   context_->getViewManager()->setCurrentViewControllerType(QString("rviz/FPSMotion"));
00119   setFallbackToolProperty();
00120   setFallbackViewControllerProperty();
00121 
00122   if(m_tool_classes.contains(QString("rviz/Select")))
00123   {
00124     m_removed_select = true;
00125     context_->getToolManager()->removeTool(m_tool_classes.indexOf(QString("rviz/Select")));
00126   }
00127 }
00128 
00129 void FPSMotionTool::deactivate(){ }
00130 
00131 int FPSMotionTool::processKeyEvent(QKeyEvent *event, rviz::RenderPanel* panel)
00132 {
00133   if(panel->getViewController()->getClassId().toStdString() != "rviz/FPSMotion")
00134   {
00135     ROS_WARN("The FPS Motion Tool only works with an active rviz/FPSMotion ViewController. \n If you use the shortkeys to select ('e') and deselect ('e') this tool, the switching will be automatized for you.");
00136   }
00137   else
00138   {
00139     double update = m_pos_offset;
00140 
00141     if(event->modifiers() & Qt::ShiftModifier)
00142     {
00143       update += m_boost * m_pos_offset;
00144     }
00145 
00146     // move forward / backward
00147     if ((event->key() == Qt::Key_W && !m_left_hand_mode) || (event->key() == Qt::Key_Up && m_left_hand_mode))
00148     {
00149       if(m_fly_mode)
00150         ((rviz::FPSMotionViewController*) panel->getViewController())->fly(0.0, 0.0, -update);
00151       else
00152         ((rviz::FPSMotionViewController*) panel->getViewController())->move(0.0, 0.0, -update);
00153     }
00154 
00155     if ((event->key() == Qt::Key_S && !m_left_hand_mode) || (event->key() == Qt::Key_Down && m_left_hand_mode))
00156     {
00157       if(m_fly_mode)
00158         ((rviz::FPSMotionViewController*) panel->getViewController())->fly(0.0, 0.0, update);
00159       else
00160         ((rviz::FPSMotionViewController*) panel->getViewController())->move(0.0, 0.0, update);
00161     }
00162 
00163     // move left / right
00164     if ((event->key() == Qt::Key_A && !m_left_hand_mode) || (event->key() == Qt::Key_Left && m_left_hand_mode))
00165     {
00166       if(m_fly_mode)
00167       ((rviz::FPSMotionViewController*) panel->getViewController())->fly(-update, 0.0, 0.0);
00168       else
00169       ((rviz::FPSMotionViewController*) panel->getViewController())->move(-update, 0.0, 0.0);
00170     }
00171 
00172 
00173     if ((event->key() == Qt::Key_D && !m_left_hand_mode) || (event->key() == Qt::Key_Right && m_left_hand_mode))
00174     {
00175       if(m_fly_mode)
00176         ((rviz::FPSMotionViewController*) panel->getViewController())->fly(update, 0.0, 0.0);
00177       else
00178         ((rviz::FPSMotionViewController*) panel->getViewController())->move(update, 0.0, 0.0);
00179     }
00180 
00181     // move up / down
00182 
00183     if ((event->key() == Qt::Key_Up && !m_left_hand_mode) || (event->key() == Qt::Key_W && m_left_hand_mode))
00184     {
00185         ((rviz::FPSMotionViewController*) panel->getViewController())->changeZ(update);
00186     }
00187 
00188     if ((event->key() == Qt::Key_Down && !m_left_hand_mode) || (event->key() == Qt::Key_S && m_left_hand_mode))
00189     {
00190       ((rviz::FPSMotionViewController*) panel->getViewController())->changeZ(-update);
00191     }
00192 
00193     // yaw left / down
00194 
00195     if ((event->key() == Qt::Key_Left && !m_left_hand_mode) || (event->key() == Qt::Key_A && m_left_hand_mode))
00196     {
00197         ((rviz::FPSMotionViewController*) panel->getViewController())->yaw(update);
00198     }
00199 
00200     if ((event->key() == Qt::Key_Right && !m_left_hand_mode) || (event->key() == Qt::Key_D && m_left_hand_mode))
00201     {
00202       ((rviz::FPSMotionViewController*) panel->getViewController())->yaw(-update);
00203     }
00204 
00205     // switch walk/fly mode
00206     if (event->key() == Qt::Key_F)
00207     {
00208       m_fly_mode = !m_fly_mode;
00209       fly_property_->setValue(m_fly_mode);
00210       fly_property_->show();
00211     }
00212 
00213     // reset the view
00214     if (event->key() == Qt::Key_R)
00215     {
00216       m_fly_mode = false;
00217       fly_property_->setValue(m_fly_mode);
00218       fly_property_->show();
00219 
00220       ((rviz::FPSMotionViewController*) panel->getViewController())->reset();
00221     }
00222 
00223     // deactivate tool and switch back into interactive mode
00224     if (event->key() == Qt::Key_E)
00225     {
00226       context_->getToolManager()->setCurrentTool(m_fallback_tool);
00227       context_->getViewManager()->setCurrentViewControllerType(m_fallback_view_controller);
00228 
00229       if(m_removed_select)
00230       {
00231         context_->getToolManager()->addTool(QString("rviz/Select"));
00232       }
00233     }
00234   }
00235 
00236   return Render;
00237 }
00238 
00239 int FPSMotionTool::processMouseEvent(rviz::ViewportMouseEvent& event)
00240 {
00241   if (event.panel->getViewController())
00242   {
00243     event.panel->getViewController()->handleMouseEvent(event);
00244     setCursor( event.panel->getViewController()->getCursor() );
00245   }
00246   return 0;
00247 }
00248 
00249 } // end namespace rviz
00250 
00251 #include <pluginlib/class_list_macros.h>
00252 PLUGINLIB_EXPORT_CLASS(rviz::FPSMotionTool, rviz::Tool)


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