fixed_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 <stdint.h>
00031 
00032 #include <OGRE/OgreCamera.h>
00033 #include <OGRE/OgreQuaternion.h>
00034 #include <OGRE/OgreSceneManager.h>
00035 #include <OGRE/OgreSceneNode.h>
00036 #include <OGRE/OgreVector3.h>
00037 #include <OGRE/OgreViewport.h>
00038 
00039 #include "rviz/display_context.h"
00040 #include "rviz/geometry.h"
00041 #include "rviz/ogre_helpers/shape.h"
00042 #include "rviz/properties/float_property.h"
00043 #include "rviz/properties/vector_property.h"
00044 #include "rviz/uniform_string_stream.h"
00045 #include "rviz/viewport_mouse_event.h"
00046 #include "rviz/load_resource.h"
00047 #include "rviz/render_panel.h"
00048 
00049 #include "oculus_rviz_plugins/fixed_view_controller.h"
00050 
00051 using namespace rviz;
00052 
00053 namespace oculus_rviz_plugins
00054 {
00055 
00056 static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION =
00057   Ogre::Quaternion( Ogre::Radian( -Ogre::Math::HALF_PI ), Ogre::Vector3::UNIT_Y ) *
00058   Ogre::Quaternion( Ogre::Radian( -Ogre::Math::HALF_PI ), Ogre::Vector3::UNIT_Z );
00059 
00060 FixedViewController::FixedViewController()
00061 {
00062   fov_property_ = new FloatProperty( "Vertical Field Of View", 50.0, "Vertical opening angle of the camera.", this );
00063   fov_property_->setMin( 5.0 );
00064   fov_property_->setMax( 130.0 );
00065 }
00066 
00067 void FixedViewController::onInitialize()
00068 {
00069   FramePositionTrackingViewController::onInitialize();
00070   camera_->setProjectionType( Ogre::PT_PERSPECTIVE );
00071   camera_->setOrientation(ROBOT_TO_CAMERA_ROTATION);//.Inverse());
00072 }
00073 
00074 FixedViewController::~FixedViewController()
00075 {
00076 }
00077 
00078 void FixedViewController::reset()
00079 {
00080 }
00081 
00082 void FixedViewController::update(float dt, float ros_dt)
00083 {
00084   FramePositionTrackingViewController::update( dt, ros_dt );
00085   camera_->setFOVy( Ogre::Degree(fov_property_->getFloat()) );
00086   target_scene_node_->setOrientation( reference_orientation_ );
00087 }
00088 
00089 void FixedViewController::handleMouseEvent(ViewportMouseEvent& event)
00090 {
00091   setStatus( "<b>Right-Click / Mouse Wheel:</b>: Zoom.  " );
00092 
00093   int32_t diff_x = event.x - event.last_x;
00094   int32_t diff_y = event.y - event.last_y;
00095 
00096   if( event.right() )
00097   {
00098     setCursor( Zoom );
00099     zoom( -diff_y * 0.1);
00100   }
00101 
00102   if( event.wheel_delta != 0 )
00103   {
00104     int diff = event.wheel_delta;
00105     zoom( diff * 0.001 );
00106   }
00107 }
00108 
00109 void FixedViewController::zoom( float amount )
00110 {
00111   fov_property_->setFloat( fov_property_->getFloat() * (1.0 + amount) );
00112 }
00113 
00114 
00115 } // end namespace rviz
00116 
00117 #include <pluginlib/class_list_macros.h>
00118 PLUGINLIB_EXPORT_CLASS( oculus_rviz_plugins::FixedViewController, rviz::ViewController )


oculus_rviz_plugins
Author(s): David Gossow
autogenerated on Mon Oct 6 2014 03:00:55