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 #include "orbit_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 float MIN_DISTANCE = 0.01;
00050 static const float PITCH_LIMIT_LOW = 0.001;
00051 static const float PITCH_LIMIT_HIGH = Ogre::Math::PI - 0.001;
00052 static const float YAW_START = Ogre::Math::PI;
00053 static const float PITCH_START = Ogre::Math::HALF_PI;
00054
00055 OrbitViewController::OrbitViewController(VisualizationManager* manager, const std::string& name)
00056 : ViewController(manager, name)
00057 , focal_point_( Ogre::Vector3::ZERO )
00058 , yaw_( YAW_START )
00059 , pitch_( PITCH_START )
00060 , distance_( 10.0f )
00061 {
00062 focal_shape_ = new ogre_tools::Shape(ogre_tools::Shape::Sphere, manager_->getSceneManager(), reference_node_);
00063 focal_shape_->setScale(Ogre::Vector3(0.05f, 0.01f, 0.05f));
00064 focal_shape_->setColor(1.0f, 1.0f, 0.0f, 0.5f);
00065 focal_shape_->getRootNode()->setVisible(false);
00066 }
00067
00068 OrbitViewController::~OrbitViewController()
00069 {
00070 delete focal_shape_;
00071 }
00072
00073 void OrbitViewController::handleMouseEvent(ViewportMouseEvent& event)
00074 {
00075 bool moved = false;
00076 if ( event.event.LeftDown() || event.event.RightDown() || event.event.MiddleDown() )
00077 {
00078 focal_shape_->getRootNode()->setVisible(true);
00079 moved = true;
00080 }
00081 else if ( event.event.LeftUp() || event.event.RightUp() || event.event.MiddleUp() )
00082 {
00083 focal_shape_->getRootNode()->setVisible(false);
00084 moved = true;
00085 }
00086 else if ( event.event.Dragging() )
00087 {
00088 int32_t diff_x = event.event.GetX() - event.last_x;
00089 int32_t diff_y = event.event.GetY() - event.last_y;
00090
00091 if ( event.event.LeftIsDown() )
00092 {
00093 yaw( diff_x*0.005 );
00094 pitch( -diff_y*0.005 );
00095 }
00096 else if ( event.event.MiddleIsDown() )
00097 {
00098 float fovY = camera_->getFOVy().valueRadians();
00099 float fovX = 2.0f * atan( tan( fovY / 2.0f ) * camera_->getAspectRatio() );
00100
00101 int width = camera_->getViewport()->getActualWidth();
00102 int height = camera_->getViewport()->getActualHeight();
00103
00104 move( -((float)diff_x / (float)width) * distance_ * tan( fovX / 2.0f ) * 2.0f, ((float)diff_y / (float)height) * distance_ * tan( fovY / 2.0f ) * 2.0f, 0.0f );
00105 }
00106 else if ( event.event.RightIsDown() )
00107 {
00108 if (event.event.ShiftDown())
00109 {
00110 move(0.0f, 0.0f, diff_y * 0.1 * (distance_ / 10.0f));
00111 }
00112 else
00113 {
00114 zoom( -diff_y * 0.1 * (distance_ / 10.0f) );
00115 }
00116 }
00117
00118 moved = true;
00119 }
00120
00121 if ( event.event.GetWheelRotation() != 0 )
00122 {
00123 int diff = event.event.GetWheelRotation();
00124 if (event.event.ShiftDown())
00125 {
00126 move(0.0f, 0.0f, -diff * 0.01 * (distance_ / 10.0f));
00127 }
00128 else
00129 {
00130 zoom( diff * 0.01 * (distance_ / 10.0f) );
00131 }
00132
00133 moved = true;
00134 }
00135
00136 if (moved)
00137 {
00138 manager_->queueRender();
00139 }
00140 }
00141
00142 void OrbitViewController::onActivate()
00143 {
00144 if (camera_->getProjectionType() == Ogre::PT_ORTHOGRAPHIC)
00145 {
00146 camera_->setProjectionType(Ogre::PT_PERSPECTIVE);
00147 }
00148 else
00149 {
00150 Ogre::Vector3 position = camera_->getPosition();
00151 Ogre::Quaternion orientation = camera_->getOrientation();
00152
00153
00154 distance_ = position.length();
00155
00156 Ogre::Vector3 direction = orientation * (Ogre::Vector3::NEGATIVE_UNIT_Z * distance_);
00157 focal_point_ = position + direction;
00158
00159 calculatePitchYawFromPosition( position );
00160 }
00161
00162 reference_node_->attachObject(camera_);
00163 }
00164
00165 void OrbitViewController::onDeactivate()
00166 {
00167 reference_node_->detachObject(camera_);
00168 focal_shape_->getRootNode()->setVisible(false);
00169 camera_->setFixedYawAxis(false);
00170 }
00171
00172 void OrbitViewController::onUpdate(float dt, float ros_dt)
00173 {
00174 updateCamera();
00175 }
00176
00177 void OrbitViewController::lookAt( const Ogre::Vector3& point )
00178 {
00179 Ogre::Vector3 camera_position = camera_->getPosition();
00180 focal_point_ = reference_node_->getOrientation().Inverse() * (point - reference_node_->getPosition());
00181 distance_ = focal_point_.distance( camera_position );
00182
00183 calculatePitchYawFromPosition(camera_position);
00184 }
00185
00186 void OrbitViewController::onReferenceFrameChanged(const Ogre::Vector3& old_reference_position, const Ogre::Quaternion& old_reference_orientation)
00187 {
00188
00189 Ogre::Vector3 old_camera_pos = old_reference_position + old_reference_orientation * camera_->getPosition();
00190
00191
00192
00193 Ogre::Vector3 camera_position = reference_node_->getOrientation().Inverse() * (old_camera_pos - reference_node_->getPosition());
00194
00195 focal_point_ = Ogre::Vector3::ZERO;
00196 distance_ = focal_point_.distance( camera_position );
00197
00198 calculatePitchYawFromPosition(camera_position);
00199 }
00200
00201 void OrbitViewController::normalizePitch()
00202 {
00203 if ( pitch_ < PITCH_LIMIT_LOW )
00204 {
00205 pitch_ = PITCH_LIMIT_LOW;
00206 }
00207 else if ( pitch_ > PITCH_LIMIT_HIGH )
00208 {
00209 pitch_ = PITCH_LIMIT_HIGH;
00210 }
00211 }
00212
00213 void OrbitViewController::normalizeYaw()
00214 {
00215 yaw_ = fmod( yaw_, Ogre::Math::TWO_PI );
00216
00217 if ( yaw_ < 0.0f )
00218 {
00219 yaw_ = Ogre::Math::TWO_PI + yaw_;
00220 }
00221 }
00222
00223 void OrbitViewController::updateCamera()
00224 {
00225 float x = distance_ * cos( yaw_ ) * sin( pitch_ ) + focal_point_.x;
00226 float y = distance_ * cos( pitch_ ) + focal_point_.y;
00227 float z = distance_ * sin( yaw_ ) * sin( pitch_ ) + focal_point_.z;
00228
00229 Ogre::Vector3 pos( x, y, z );
00230
00231 camera_->setPosition(pos);
00232 camera_->setFixedYawAxis(true, reference_node_->getOrientation() * Ogre::Vector3::UNIT_Y);
00233 camera_->setDirection(reference_node_->getOrientation() * (focal_point_ - pos));
00234
00235 focal_shape_->setPosition(focal_point_);
00236 }
00237
00238 void OrbitViewController::yaw( float angle )
00239 {
00240 yaw_ += angle;
00241
00242 normalizeYaw();
00243 }
00244
00245 void OrbitViewController::pitch( float angle )
00246 {
00247 pitch_ += angle;
00248
00249 normalizePitch();
00250 }
00251
00252 void OrbitViewController::calculatePitchYawFromPosition( const Ogre::Vector3& position )
00253 {
00254 float x = position.x - focal_point_.x;
00255 float y = position.y - focal_point_.y;
00256 pitch_ = acos( y / distance_ );
00257
00258 normalizePitch();
00259
00260 float val = x / ( distance_ * sin( pitch_ ) );
00261
00262 yaw_ = acos( val );
00263
00264 Ogre::Vector3 direction = focal_point_ - position;
00265
00266 if ( direction.dotProduct( Ogre::Vector3::NEGATIVE_UNIT_Z ) < 0 )
00267 {
00268 yaw_ = Ogre::Math::TWO_PI - yaw_;
00269 }
00270 }
00271
00272 void OrbitViewController::zoom( float amount )
00273 {
00274 distance_ -= amount;
00275
00276 if ( distance_ <= MIN_DISTANCE )
00277 {
00278 distance_ = MIN_DISTANCE;
00279 }
00280 }
00281
00282 void OrbitViewController::move( float x, float y, float z )
00283 {
00284 focal_point_ += camera_->getOrientation() * Ogre::Vector3( x, y, z );
00285 }
00286
00287 void OrbitViewController::fromString(const std::string& str)
00288 {
00289 std::istringstream iss(str);
00290
00291 iss >> pitch_;
00292 iss.ignore();
00293 iss >> yaw_;
00294 iss.ignore();
00295 iss >> distance_;
00296 iss.ignore();
00297 iss >> focal_point_.x;
00298 iss.ignore();
00299 iss >> focal_point_.y;
00300 iss.ignore();
00301 iss >> focal_point_.z;
00302 }
00303
00304 std::string OrbitViewController::toString()
00305 {
00306 std::ostringstream oss;
00307 oss << pitch_ << " " << yaw_ << " " << distance_ << " " << focal_point_.x << " " << focal_point_.y << " " << focal_point_.z;
00308
00309 return oss.str();
00310 }
00311
00312
00313 }