fps_view_controller.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include "fps_view_controller.h"
00031 #include "rviz/viewport_mouse_event.h"
00032 #include "rviz/visualization_manager.h"
00033 
00034 #include <OGRE/OgreCamera.h>
00035 #include <OGRE/OgreSceneManager.h>
00036 #include <OGRE/OgreSceneNode.h>
00037 #include <OGRE/OgreVector3.h>
00038 #include <OGRE/OgreQuaternion.h>
00039 #include <OGRE/OgreViewport.h>
00040 
00041 #include <ogre_tools/shape.h>
00042 
00043 #include <stdint.h>
00044 #include <sstream>
00045 
00046 namespace rviz
00047 {
00048 
00049 static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION =
00050   Ogre::Quaternion( Ogre::Radian( -Ogre::Math::HALF_PI ), Ogre::Vector3::UNIT_Y ) *
00051   Ogre::Quaternion( Ogre::Radian( -Ogre::Math::HALF_PI ), Ogre::Vector3::UNIT_Z );
00052 
00053 static const float PITCH_LIMIT_LOW = -Ogre::Math::HALF_PI + 0.001;
00054 static const float PITCH_LIMIT_HIGH = Ogre::Math::HALF_PI - 0.001;
00055 
00056 FPSViewController::FPSViewController(VisualizationManager* manager, const std::string& name, Ogre::SceneNode* target_scene_node)
00057 : ViewController(manager, name, target_scene_node)
00058 , yaw_(0.0f)
00059 , pitch_(0.0f)
00060 {
00061 }
00062 
00063 FPSViewController::~FPSViewController()
00064 {
00065 }
00066 
00067 void FPSViewController::handleMouseEvent(ViewportMouseEvent& event)
00068 {
00069   bool moved = false;
00070   if( event.type == QEvent::MouseMove )
00071   {
00072     int32_t diff_x = event.x - event.last_x;
00073     int32_t diff_y = event.y - event.last_y;
00074 
00075     if( event.left() && !event.shift() )
00076     {
00077       yaw( -diff_x*0.005 );
00078       pitch( diff_y*0.005 );
00079     }
00080     else if( event.middle() || ( event.shift() && event.left() ))
00081     {
00082       move( diff_x*0.01, -diff_y*0.01, 0.0f );
00083     }
00084     else if( event.right() )
00085     {
00086       move( 0.0f, 0.0f, diff_y*0.1 );
00087     }
00088 
00089     moved = true;
00090   }
00091 
00092   if ( event.wheel_delta != 0 )
00093   {
00094     int diff = event.wheel_delta;
00095     move( 0.0f, 0.0f, -diff * 0.01 );
00096 
00097     moved = true;
00098   }
00099 
00100   if (moved)
00101   {
00102     manager_->queueRender();
00103   }
00104 }
00105 
00106 void FPSViewController::setYawPitchFromCamera()
00107 {
00108   Ogre::Quaternion quat = camera_->getOrientation() * ROBOT_TO_CAMERA_ROTATION.Inverse();
00109   yaw_ = quat.getRoll( false ).valueRadians(); // OGRE camera frame looks along -Z, so they call rotation around Z "roll".
00110   pitch_ = quat.getYaw( false ).valueRadians(); // OGRE camera frame has +Y as "up", so they call rotation around Y "yaw".
00111 
00112   Ogre::Vector3 direction = quat * Ogre::Vector3::NEGATIVE_UNIT_Z;
00113 
00114   if ( direction.dotProduct( Ogre::Vector3::NEGATIVE_UNIT_Z ) < 0 )
00115   {
00116     if ( pitch_ > Ogre::Math::HALF_PI )
00117     {
00118       pitch_ -= Ogre::Math::PI;
00119     }
00120     else if ( pitch_ < -Ogre::Math::HALF_PI )
00121     {
00122       pitch_ += Ogre::Math::PI;
00123     }
00124 
00125     yaw_ = -yaw_;
00126 
00127     if ( direction.dotProduct( Ogre::Vector3::UNIT_X ) < 0 )
00128     {
00129       yaw_ -= Ogre::Math::PI;
00130     }
00131     else
00132     {
00133       yaw_ += Ogre::Math::PI;
00134     }
00135   }
00136 
00137   normalizePitch();
00138   normalizeYaw();
00139 }
00140 
00141 void FPSViewController::onActivate()
00142 {
00143   if (camera_->getProjectionType() == Ogre::PT_ORTHOGRAPHIC)
00144   {
00145     camera_->setProjectionType(Ogre::PT_PERSPECTIVE);
00146   }
00147   else
00148   {
00149     setYawPitchFromCamera();
00150   }
00151 }
00152 
00153 void FPSViewController::onDeactivate()
00154 {
00155 }
00156 
00157 void FPSViewController::onUpdate(float dt, float ros_dt)
00158 {
00159   updateCamera();
00160 }
00161 
00162 void FPSViewController::lookAt( const Ogre::Vector3& point )
00163 {
00164   camera_->lookAt( point );
00165   setYawPitchFromCamera();
00166 }
00167 
00168 void FPSViewController::onTargetFrameChanged(const Ogre::Vector3& old_reference_position, const Ogre::Quaternion& old_reference_orientation)
00169 {
00170   camera_->setPosition( camera_->getPosition() + old_reference_position - reference_position_ );
00171 }
00172 
00173 void FPSViewController::normalizePitch()
00174 {
00175   if ( pitch_ < PITCH_LIMIT_LOW )
00176   {
00177     pitch_ = PITCH_LIMIT_LOW;
00178   }
00179   else if ( pitch_ > PITCH_LIMIT_HIGH )
00180   {
00181     pitch_ = PITCH_LIMIT_HIGH;
00182   }
00183 }
00184 
00185 void FPSViewController::normalizeYaw()
00186 {
00187   yaw_ = fmod( yaw_, Ogre::Math::TWO_PI );
00188 
00189   if ( yaw_ < 0.0f )
00190   {
00191     yaw_ = Ogre::Math::TWO_PI + yaw_;
00192   }
00193 }
00194 
00195 void FPSViewController::updateCamera()
00196 {
00197   Ogre::Quaternion pitch, yaw;
00198 
00199   yaw.FromAngleAxis( Ogre::Radian( yaw_ ), Ogre::Vector3::UNIT_Z );
00200   pitch.FromAngleAxis( Ogre::Radian( pitch_ ), Ogre::Vector3::UNIT_Y );
00201 
00202   camera_->setOrientation( yaw * pitch * ROBOT_TO_CAMERA_ROTATION );
00203 }
00204 
00205 void FPSViewController::yaw( float angle )
00206 {
00207   yaw_ += angle;
00208 
00209   normalizeYaw();
00210 }
00211 
00212 void FPSViewController::pitch( float angle )
00213 {
00214   pitch_ += angle;
00215 
00216   normalizePitch();
00217 }
00218 
00219 void FPSViewController::move( float x, float y, float z )
00220 {
00221   Ogre::Vector3 translate( x, y, z );
00222   camera_->setPosition( camera_->getPosition() + camera_->getOrientation() * translate );
00223 }
00224 
00225 void FPSViewController::fromString(const std::string& str)
00226 {
00227   std::istringstream iss(str);
00228 
00229   iss >> pitch_;
00230   iss.ignore();
00231   iss >> yaw_;
00232   iss.ignore();
00233 
00234   Ogre::Vector3 vec;
00235   iss >> vec.x;
00236   iss.ignore();
00237   iss >> vec.y;
00238   iss.ignore();
00239   iss >> vec.z;
00240   iss.ignore();
00241   camera_->setPosition(vec);
00242 }
00243 
00244 std::string FPSViewController::toString()
00245 {
00246   std::ostringstream oss;
00247   oss << pitch_ << " " << yaw_ << " " << camera_->getPosition().x << " " << camera_->getPosition().y << " " << camera_->getPosition().z;
00248 
00249   return oss.str();
00250 }
00251 
00252 
00253 }


rviz_qt
Author(s): Dave Hershberger
autogenerated on Fri Dec 6 2013 20:56:52