00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023 #include "domUtils.h"
00024 #include "camera.h"
00025 #include "qglviewer.h"
00026
00027 using namespace std;
00028 using namespace qglviewer;
00029
00037 Camera::Camera()
00038 : fieldOfView_(M_PI/4.0f)
00039 {
00040
00041 interpolationKfi_ = new KeyFrameInterpolator;
00042
00043 setFrame(new ManipulatedCameraFrame());
00044
00045
00046
00047
00048 setSceneRadius(1.0);
00049
00050
00051 orthoCoef_ = tan(fieldOfView()/2.0);
00052
00053
00054 setSceneCenter(Vec(0.0, 0.0, 0.0));
00055
00056
00057 setType(PERSPECTIVE);
00058
00059
00060 setZNearCoefficient(0.005f);
00061 setZClippingCoefficient(sqrt(3.0));
00062
00063
00064 setScreenWidthAndHeight(600, 400);
00065
00066
00067 setIODistance(0.062f);
00068 setPhysicalScreenWidth(0.5f);
00069
00070
00071
00072 for (unsigned short j=0; j<16; ++j)
00073 {
00074 modelViewMatrix_[j] = ((j%5 == 0) ? 1.0 : 0.0);
00075
00076 projectionMatrix_[j] = 0.0;
00077 }
00078 computeProjectionMatrix();
00079 }
00080
00085 Camera::~Camera()
00086 {
00087 delete frame_;
00088 delete interpolationKfi_;
00089 }
00090
00091
00093 Camera::Camera(const Camera& camera)
00094 : QObject()
00095 {
00096
00097 interpolationKfi_ = new KeyFrameInterpolator;
00098
00099 setFrame(new ManipulatedCameraFrame());
00100
00101 for (unsigned short j=0; j<16; ++j)
00102 {
00103 modelViewMatrix_[j] = ((j%5 == 0) ? 1.0 : 0.0);
00104
00105 projectionMatrix_[j] = 0.0;
00106 }
00107
00108 (*this)=camera;
00109 }
00110
00123 Camera& Camera::operator=(const Camera& camera)
00124 {
00125 setScreenWidthAndHeight(camera.screenWidth(), camera.screenHeight());
00126 setFieldOfView(camera.fieldOfView());
00127 setSceneRadius(camera.sceneRadius());
00128 setSceneCenter(camera.sceneCenter());
00129 setZNearCoefficient(camera.zNearCoefficient());
00130 setZClippingCoefficient(camera.zClippingCoefficient());
00131 setType(camera.type());
00132
00133
00134 setIODistance(camera.IODistance());
00135 setFocusDistance(camera.focusDistance());
00136 setPhysicalScreenWidth(camera.physicalScreenWidth());
00137
00138 orthoCoef_ = camera.orthoCoef_;
00139
00140
00141 frame_->setReferenceFrame(NULL);
00142 frame_->setPosition(camera.position());
00143 frame_->setOrientation(camera.orientation());
00144
00145 interpolationKfi_->resetInterpolation();
00146
00147 kfi_ = camera.kfi_;
00148
00149 computeProjectionMatrix();
00150 computeModelViewMatrix();
00151
00152 return *this;
00153 }
00154
00164 void Camera::setScreenWidthAndHeight(int width, int height)
00165 {
00166
00167 screenWidth_ = width > 0 ? width : 1;
00168 screenHeight_ = height > 0 ? height : 1;
00169 }
00170
00208 float Camera::zNear() const
00209 {
00210 float z = distanceToSceneCenter() - zClippingCoefficient()*sceneRadius();
00211
00212
00213 const float zMin = zNearCoefficient() * zClippingCoefficient() * sceneRadius();
00214 if (z < zMin)
00215 switch (type())
00216 {
00217 case Camera::PERSPECTIVE : z = zMin; break;
00218 case Camera::ORTHOGRAPHIC : z = 0.0; break;
00219 }
00220 return z;
00221 }
00222
00232 float Camera::zFar() const
00233 {
00234 return distanceToSceneCenter() + zClippingCoefficient()*sceneRadius();
00235 }
00236
00246 void Camera::setType(Type type)
00247 {
00248
00249
00250
00251 if ( (type == Camera::ORTHOGRAPHIC) && (type_ == Camera::PERSPECTIVE) )
00252 orthoCoef_ = tan(fieldOfView()/2.0);
00253 type_ = type;
00254 }
00255
00269 void Camera::setFrame(ManipulatedCameraFrame* const mcf)
00270 {
00271 if (!mcf)
00272 return;
00273
00274 frame_ = mcf;
00275 interpolationKfi_->setFrame(frame());
00276 }
00277
00280 float Camera::distanceToSceneCenter() const
00281 {
00282 return fabs((frame()->coordinatesOf(sceneCenter())).z);
00283 }
00284
00285
00301 void Camera::getOrthoWidthHeight(GLdouble& halfWidth, GLdouble& halfHeight) const
00302 {
00303 const float dist = orthoCoef_ * fabs(cameraCoordinatesOf(revolveAroundPoint()).z);
00304
00305 halfWidth = dist * ((aspectRatio() < 1.0) ? 1.0 : aspectRatio());
00306 halfHeight = dist * ((aspectRatio() < 1.0) ? 1.0/aspectRatio() : 1.0);
00307 }
00308
00309
00327 void Camera::computeProjectionMatrix() const
00328 {
00329 const float ZNear = zNear();
00330 const float ZFar = zFar();
00331
00332 switch (type())
00333 {
00334 case Camera::PERSPECTIVE:
00335 {
00336
00337 const float f = 1.0/tan(fieldOfView()/2.0);
00338 projectionMatrix_[0] = f/aspectRatio();
00339 projectionMatrix_[5] = f;
00340 projectionMatrix_[10] = (ZNear + ZFar) / (ZNear - ZFar);
00341 projectionMatrix_[11] = -1.0;
00342 projectionMatrix_[14] = 2.0 * ZNear * ZFar / (ZNear - ZFar);
00343 projectionMatrix_[15] = 0.0;
00344
00345 break;
00346 }
00347 case Camera::ORTHOGRAPHIC:
00348 {
00349 GLdouble w, h;
00350 getOrthoWidthHeight(w,h);
00351 projectionMatrix_[0] = 1.0/w;
00352 projectionMatrix_[5] = 1.0/h;
00353 projectionMatrix_[10] = -2.0/(ZFar - ZNear);
00354 projectionMatrix_[11] = 0.0;
00355 projectionMatrix_[14] = -(ZFar + ZNear)/(ZFar - ZNear);
00356 projectionMatrix_[15] = 1.0;
00357
00358 break;
00359 }
00360 }
00361 }
00362
00373 void Camera::computeModelViewMatrix() const
00374 {
00375 const Quaternion q = frame()->orientation();
00376
00377 const double q00 = 2.0l * q[0] * q[0];
00378 const double q11 = 2.0l * q[1] * q[1];
00379 const double q22 = 2.0l * q[2] * q[2];
00380
00381 const double q01 = 2.0l * q[0] * q[1];
00382 const double q02 = 2.0l * q[0] * q[2];
00383 const double q03 = 2.0l * q[0] * q[3];
00384
00385 const double q12 = 2.0l * q[1] * q[2];
00386 const double q13 = 2.0l * q[1] * q[3];
00387
00388 const double q23 = 2.0l * q[2] * q[3];
00389
00390 modelViewMatrix_[0] = 1.0l - q11 - q22;
00391 modelViewMatrix_[1] = q01 - q23;
00392 modelViewMatrix_[2] = q02 + q13;
00393 modelViewMatrix_[3] = 0.0l;
00394
00395 modelViewMatrix_[4] = q01 + q23;
00396 modelViewMatrix_[5] = 1.0l - q22 - q00;
00397 modelViewMatrix_[6] = q12 - q03;
00398 modelViewMatrix_[7] = 0.0l;
00399
00400 modelViewMatrix_[8] = q02 - q13;
00401 modelViewMatrix_[9] = q12 + q03;
00402 modelViewMatrix_[10] = 1.0l - q11 - q00;
00403 modelViewMatrix_[11] = 0.0l;
00404
00405 const Vec t = q.inverseRotate(frame()->position());
00406
00407 modelViewMatrix_[12] = -t.x;
00408 modelViewMatrix_[13] = -t.y;
00409 modelViewMatrix_[14] = -t.z;
00410 modelViewMatrix_[15] = 1.0l;
00411 }
00412
00413
00432 void Camera::loadProjectionMatrix(bool reset) const
00433 {
00434
00435 glMatrixMode(GL_PROJECTION);
00436
00437 if (reset)
00438 glLoadIdentity();
00439
00440 computeProjectionMatrix();
00441
00442 glMultMatrixd(projectionMatrix_);
00443 }
00444
00469 void Camera::loadModelViewMatrix(bool reset) const
00470 {
00471
00472 glMatrixMode(GL_MODELVIEW);
00473 computeModelViewMatrix();
00474 if (reset)
00475 glLoadMatrixd(modelViewMatrix_);
00476 else
00477 glMultMatrixd(modelViewMatrix_);
00478 }
00479
00505 void Camera::loadProjectionMatrixStereo(bool leftBuffer) const
00506 {
00507 float left, right, bottom, top;
00508 float screenHalfWidth, halfWidth, side, shift, delta;
00509
00510 glMatrixMode(GL_PROJECTION);
00511 glLoadIdentity();
00512
00513 switch (type())
00514 {
00515 case Camera::PERSPECTIVE:
00516
00517
00518 screenHalfWidth = focusDistance() * tan(horizontalFieldOfView() / 2.0);
00519 shift = screenHalfWidth * IODistance() / physicalScreenWidth();
00520
00521
00522
00523
00524
00525 halfWidth = zNear() * tan(horizontalFieldOfView() / 2.0);
00526 delta = shift * zNear() / focusDistance();
00527 side = leftBuffer ? -1.0 : 1.0;
00528
00529 left = -halfWidth + side * delta;
00530 right = halfWidth + side * delta;
00531 top = halfWidth / aspectRatio();
00532 bottom = -top;
00533 glFrustum(left, right, bottom, top, zNear(), zFar() );
00534 break;
00535
00536 case Camera::ORTHOGRAPHIC:
00537 qWarning("Camera::setProjectionMatrixStereo: Stereo not available with Ortho mode");
00538 break;
00539 }
00540 }
00541
00560 void Camera::loadModelViewMatrixStereo(bool leftBuffer) const
00561 {
00562
00563 glMatrixMode(GL_MODELVIEW);
00564
00565 float halfWidth = focusDistance() * tan(horizontalFieldOfView() / 2.0);
00566 float shift = halfWidth * IODistance() / physicalScreenWidth();
00567
00568 computeModelViewMatrix();
00569 if (leftBuffer)
00570 modelViewMatrix_[12] -= shift;
00571 else
00572 modelViewMatrix_[12] += shift;
00573 glLoadMatrixd(modelViewMatrix_);
00574 }
00575
00590 void Camera::getProjectionMatrix(GLdouble m[16]) const
00591 {
00592
00593 computeProjectionMatrix();
00594 for (unsigned short i=0; i<16; ++i)
00595 m[i] = projectionMatrix_[i];
00596 }
00597
00612 void Camera::getModelViewMatrix(GLdouble m[16]) const
00613 {
00614
00615
00616 computeModelViewMatrix();
00617 for (unsigned short i=0; i<16; ++i)
00618 m[i] = modelViewMatrix_[i];
00619 }
00620
00624 void Camera::getModelViewProjectionMatrix(GLdouble m[16]) const
00625 {
00626 GLdouble mv[16];
00627 GLdouble proj[16];
00628 getModelViewMatrix(mv);
00629 getProjectionMatrix(proj);
00630
00631 for (unsigned short i=0; i<4; ++i)
00632 {
00633 for (unsigned short j=0; j<4; ++j)
00634 {
00635 double sum = 0.0;
00636 for (unsigned short k=0; k<4; ++k)
00637 sum += proj[i+4*k]*mv[k+4*j];
00638 m[i+4*j] = sum;
00639 }
00640 }
00641 }
00642
00643 #ifndef DOXYGEN
00644 void Camera::getProjectionMatrix(GLfloat m[16]) const
00645 {
00646 qWarning("Warning : Camera::getProjectionMatrix requires a GLdouble matrix array");
00647 static GLdouble mat[16];
00648 getProjectionMatrix(mat);
00649 for (int i=0; i<16; ++i)
00650 m[i] = float(mat[i]);
00651 }
00652
00653 void Camera::getModelViewMatrix(GLfloat m[16]) const
00654 {
00655 qWarning("Warning : Camera::getModelViewMatrix requires a GLdouble matrix array");
00656 static GLdouble mat[16];
00657 getModelViewMatrix(mat);
00658 for (int i=0; i<16; ++i)
00659 m[i] = float(mat[i]);
00660 }
00661 #endif
00662
00667 void Camera::setSceneRadius(float radius)
00668 {
00669 if (radius <= 0.0)
00670 {
00671 qWarning("Scene radius must be positive - Ignoring value");
00672 return;
00673 }
00674
00675 sceneRadius_ = radius;
00676
00677 setFocusDistance(sceneRadius() / tan(fieldOfView()/2.0));
00678
00679 frame()->setFlySpeed(0.01*sceneRadius());
00680 }
00681
00684 void Camera::setSceneBoundingBox(const Vec& min, const Vec& max)
00685 {
00686 setSceneCenter((min+max)/2.0);
00687 setSceneRadius(0.5*(max-min).norm());
00688 }
00689
00690
00694 void Camera::setSceneCenter(const Vec& center)
00695 {
00696 sceneCenter_ = center;
00697 setRevolveAroundPoint(sceneCenter());
00698 }
00699
00705 bool Camera::setSceneCenterFromPixel(const QPoint& pixel)
00706 {
00707 bool found;
00708 Vec point = pointUnderPixel(pixel, found);
00709 if (found)
00710 setSceneCenter(point);
00711 return found;
00712 }
00713
00715 void Camera::setRevolveAroundPoint(const Vec& rap)
00716 {
00717 const float prevDist = fabs(cameraCoordinatesOf(revolveAroundPoint()).z);
00718
00719 frame()->setRevolveAroundPoint(rap);
00720
00721
00722
00723 const float newDist = fabs(cameraCoordinatesOf(revolveAroundPoint()).z);
00724
00725 if ((prevDist > 1E-9) && (newDist > 1E-9))
00726 orthoCoef_ *= prevDist / newDist;
00727 }
00728
00738 bool Camera::setRevolveAroundPointFromPixel(const QPoint& pixel)
00739 {
00740 bool found;
00741 Vec point = pointUnderPixel(pixel, found);
00742 if (found)
00743 setRevolveAroundPoint(point);
00744 return found;
00745 }
00746
00761 float Camera::pixelGLRatio(const Vec& position) const
00762 {
00763 switch (type())
00764 {
00765 case Camera::PERSPECTIVE :
00766 return 2.0 * fabs((frame()->coordinatesOf(position)).z) * tan(fieldOfView()/2.0) / screenHeight();
00767 case Camera::ORTHOGRAPHIC :
00768 {
00769 GLdouble w, h;
00770 getOrthoWidthHeight(w,h);
00771 return 2.0 * h / screenHeight();
00772 }
00773 }
00774
00775 return 1.0;
00776 }
00777
00803 void Camera::setFOVToFitScene()
00804 {
00805 if (distanceToSceneCenter() > sqrt(2.0)*sceneRadius())
00806 setFieldOfView(2.0 * asin(sceneRadius() / distanceToSceneCenter()));
00807 else
00808 setFieldOfView(M_PI / 2.0f);
00809 }
00810
00817 void Camera::interpolateToZoomOnPixel(const QPoint& pixel)
00818 {
00819 const float coef = 0.1f;
00820
00821 bool found;
00822 Vec target = pointUnderPixel(pixel, found);
00823
00824 if (!found)
00825 return;
00826
00827 if (interpolationKfi_->interpolationIsStarted())
00828 interpolationKfi_->stopInterpolation();
00829
00830 interpolationKfi_->deletePath();
00831 interpolationKfi_->addKeyFrame(*(frame()));
00832
00833 interpolationKfi_->addKeyFrame(Frame(0.3f*frame()->position() + 0.7f*target, frame()->orientation()), 0.4f);
00834
00835
00836 static ManipulatedCameraFrame* tempFrame = new ManipulatedCameraFrame();
00837 ManipulatedCameraFrame* const originalFrame = frame();
00838 tempFrame->setPosition(coef*frame()->position() + (1.0-coef)*target);
00839 tempFrame->setOrientation(frame()->orientation());
00840 setFrame(tempFrame);
00841 lookAt(target);
00842 setFrame(originalFrame);
00843
00844 interpolationKfi_->addKeyFrame(*(tempFrame), 1.0);
00845
00846 interpolationKfi_->startInterpolation();
00847 }
00848
00855 void Camera::interpolateToFitScene()
00856 {
00857 if (interpolationKfi_->interpolationIsStarted())
00858 interpolationKfi_->stopInterpolation();
00859
00860 interpolationKfi_->deletePath();
00861 interpolationKfi_->addKeyFrame(*(frame()));
00862
00863
00864 static ManipulatedCameraFrame* tempFrame = new ManipulatedCameraFrame();
00865 ManipulatedCameraFrame* const originalFrame = frame();
00866 tempFrame->setPosition(frame()->position());
00867 tempFrame->setOrientation(frame()->orientation());
00868 setFrame(tempFrame);
00869 showEntireScene();
00870 setFrame(originalFrame);
00871
00872 interpolationKfi_->addKeyFrame(*(tempFrame));
00873
00874 interpolationKfi_->startInterpolation();
00875 }
00876
00877
00884 void Camera::interpolateTo(const Frame& fr, float duration)
00885 {
00886 if (interpolationKfi_->interpolationIsStarted())
00887 interpolationKfi_->stopInterpolation();
00888
00889 interpolationKfi_->deletePath();
00890 interpolationKfi_->addKeyFrame(*(frame()));
00891 interpolationKfi_->addKeyFrame(fr, duration);
00892
00893 interpolationKfi_->startInterpolation();
00894 }
00895
00896
00913 Vec Camera::pointUnderPixel(const QPoint& pixel, bool& found) const
00914 {
00915 float depth;
00916
00917 glReadPixels(pixel.x(), screenHeight()-1-pixel.y(), 1, 1, GL_DEPTH_COMPONENT, GL_FLOAT, &depth);
00918 found = depth < 1.0;
00919 Vec point(pixel.x(), pixel.y(), depth);
00920 point = unprojectedCoordinatesOf(point);
00921 return point;
00922 }
00923
00929 void Camera::showEntireScene()
00930 {
00931 fitSphere(sceneCenter(), sceneRadius());
00932 }
00933
00939 void Camera::centerScene()
00940 {
00941 frame()->projectOnLine(sceneCenter(), viewDirection());
00942 }
00943
00950 void Camera::lookAt(const Vec& target)
00951 {
00952 setViewDirection(target - position());
00953 }
00954
00962 void Camera::fitSphere(const Vec& center, float radius)
00963 {
00964 float distance = 0.0f;
00965 switch (type())
00966 {
00967 case Camera::PERSPECTIVE :
00968 {
00969 const float yview = radius / sin(fieldOfView()/2.0);
00970 const float xview = radius / sin(horizontalFieldOfView()/2.0);
00971 distance = qMax(xview,yview);
00972 break;
00973 }
00974 case Camera::ORTHOGRAPHIC :
00975 {
00976 distance = ((center-revolveAroundPoint()) * viewDirection()) + (radius / orthoCoef_);
00977 break;
00978 }
00979 }
00980 Vec newPos(center - distance * viewDirection());
00981 frame()->setPositionWithConstraint(newPos);
00982 }
00983
00986 void Camera::fitBoundingBox(const Vec& min, const Vec& max)
00987 {
00988 float diameter = qMax(fabs(max[1]-min[1]), fabs(max[0]-min[0]));
00989 diameter = qMax(fabsf(max[2]-min[2]), diameter);
00990 fitSphere(0.5*(min+max), 0.5*diameter);
00991 }
00992
01000 void Camera::fitScreenRegion(const QRect& rectangle)
01001 {
01002 const Vec vd = viewDirection();
01003 const float distToPlane = distanceToSceneCenter();
01004 const QPoint center = rectangle.center();
01005
01006 Vec orig, dir;
01007 convertClickToLine( center, orig, dir );
01008 Vec newCenter = orig + distToPlane / (dir*vd) * dir;
01009
01010 convertClickToLine( QPoint(rectangle.x(), center.y()), orig, dir );
01011 const Vec pointX = orig + distToPlane / (dir*vd) * dir;
01012
01013 convertClickToLine( QPoint(center.x(), rectangle.y()), orig, dir );
01014 const Vec pointY = orig + distToPlane / (dir*vd) * dir;
01015
01016 float distance = 0.0f;
01017 switch (type())
01018 {
01019 case Camera::PERSPECTIVE :
01020 {
01021 const float distX = (pointX-newCenter).norm() / sin(horizontalFieldOfView()/2.0);
01022 const float distY = (pointY-newCenter).norm() / sin(fieldOfView()/2.0);
01023 distance = qMax(distX, distY);
01024 break;
01025 }
01026 case Camera::ORTHOGRAPHIC :
01027 {
01028 const float dist = ((newCenter-revolveAroundPoint()) * vd);
01029
01030 const float distX = (pointX-newCenter).norm() / orthoCoef_ / ((aspectRatio() < 1.0) ? 1.0 : aspectRatio());
01031 const float distY = (pointY-newCenter).norm() / orthoCoef_ / ((aspectRatio() < 1.0) ? 1.0/aspectRatio() : 1.0);
01032 distance = dist + qMax(distX, distY);
01033 break;
01034 }
01035 }
01036
01037 Vec newPos(newCenter - distance * vd);
01038 frame()->setPositionWithConstraint(newPos);
01039 }
01040
01056 void Camera::setUpVector(const Vec& up, bool noMove)
01057 {
01058 Quaternion q(Vec(0.0, 1.0, 0.0), frame()->transformOf(up));
01059
01060 if (!noMove)
01061 frame()->setPosition(revolveAroundPoint() - (frame()->orientation()*q).rotate(frame()->coordinatesOf(revolveAroundPoint())));
01062
01063 frame()->rotate(q);
01064
01065
01066 frame()->updateFlyUpVector();
01067 }
01068
01080 void Camera::setOrientation(float theta, float phi)
01081 {
01082 Vec axis(0.0, 1.0, 0.0);
01083 const Quaternion rot1(axis, theta);
01084 axis = Vec(-cos(theta), 0., sin(theta));
01085 const Quaternion rot2(axis, phi);
01086 setOrientation(rot1 * rot2);
01087 }
01088
01090 void Camera::setOrientation(const Quaternion& q)
01091 {
01092 frame()->setOrientation(q);
01093 frame()->updateFlyUpVector();
01094 }
01095
01101 void Camera::setViewDirection(const Vec& direction)
01102 {
01103 if (direction.squaredNorm() < 1E-10)
01104 return;
01105
01106 Vec xAxis = direction ^ upVector();
01107 if (xAxis.squaredNorm() < 1E-10)
01108 {
01109
01110
01111 xAxis = frame()->inverseTransformOf(Vec(1.0, 0.0, 0.0));
01112 }
01113
01114 Quaternion q;
01115 q.setFromRotatedBasis(xAxis, xAxis^direction, -direction);
01116 frame()->setOrientationWithConstraint(q);
01117 }
01118
01119
01120 static float det(float m00,float m01,float m02,
01121 float m10,float m11,float m12,
01122 float m20,float m21,float m22)
01123 {
01124 return m00*m11*m22 + m01*m12*m20 + m02*m10*m21 - m20*m11*m02 - m10*m01*m22 - m00*m21*m12;
01125 }
01126
01127
01128 static inline unsigned int ind(unsigned int i, unsigned int j)
01129 {
01130 return (i*4+j);
01131 }
01132
01133
01151 void Camera::setFromModelViewMatrix(const GLdouble* const modelViewMatrix)
01152 {
01153
01154 double upperLeft[3][3];
01155 for (int i=0; i<3; ++i)
01156 for (int j=0; j<3; ++j)
01157 upperLeft[i][j] = modelViewMatrix[i*4+j];
01158
01159
01160 Quaternion q;
01161 q.setFromRotationMatrix(upperLeft);
01162
01163 setOrientation(q);
01164 setPosition(-q.rotate(Vec(modelViewMatrix[12], modelViewMatrix[13], modelViewMatrix[14])));
01165 }
01166
01189 void Camera::setFromProjectionMatrix(const float matrix[12])
01190 {
01191
01192
01193 Vec line_0(matrix[ind(0,0)],matrix[ind(0,1)],matrix[ind(0,2)]);
01194 Vec line_1(matrix[ind(1,0)],matrix[ind(1,1)],matrix[ind(1,2)]);
01195 Vec line_2(matrix[ind(2,0)],matrix[ind(2,1)],matrix[ind(2,2)]);
01196
01197 line_0.normalize();
01198 line_1.normalize();
01199 line_2.normalize();
01200
01201
01202
01203
01204
01205
01206
01207
01208
01209
01210 const Vec cam_pos = Vec(det(matrix[ind(0,1)],matrix[ind(0,2)],matrix[ind(0,3)],
01211 matrix[ind(1,1)],matrix[ind(1,2)],matrix[ind(1,3)],
01212 matrix[ind(2,1)],matrix[ind(2,2)],matrix[ind(2,3)]),
01213
01214 -det(matrix[ind(0,0)],matrix[ind(0,2)],matrix[ind(0,3)],
01215 matrix[ind(1,0)],matrix[ind(1,2)],matrix[ind(1,3)],
01216 matrix[ind(2,0)],matrix[ind(2,2)],matrix[ind(2,3)]),
01217
01218 det(matrix[ind(0,0)],matrix[ind(0,1)],matrix[ind(0,3)],
01219 matrix[ind(1,0)],matrix[ind(1,1)],matrix[ind(1,3)],
01220 matrix[ind(2,0)],matrix[ind(2,1)],matrix[ind(2,3)])) /
01221
01222 (-det(matrix[ind(0,0)],matrix[ind(0,1)],matrix[ind(0,2)],
01223 matrix[ind(1,0)],matrix[ind(1,1)],matrix[ind(1,2)],
01224 matrix[ind(2,0)],matrix[ind(2,1)],matrix[ind(2,2)]));
01225
01226
01227
01228
01229 Vec column_2 = -line_2;
01230
01231
01232 Vec column_0 = ((column_2^line_0)^column_2);
01233 column_0.normalize();
01234
01235
01236
01237 Vec column_1 = -((column_2^line_1)^column_2);
01238 column_1.normalize();
01239
01240 double rot[3][3];
01241 rot[0][0] = column_0[0];
01242 rot[1][0] = column_0[1];
01243 rot[2][0] = column_0[2];
01244
01245 rot[0][1] = column_1[0];
01246 rot[1][1] = column_1[1];
01247 rot[2][1] = column_1[2];
01248
01249 rot[0][2] = column_2[0];
01250 rot[1][2] = column_2[1];
01251 rot[2][2] = column_2[2];
01252
01253
01254
01255
01256
01257
01258
01259
01260
01261 Vec dummy = line_1^column_0;
01262 dummy.normalize();
01263 float fov = acos(column_2*dummy) * 2.0;
01264
01265
01266 Quaternion q;
01267 q.setFromRotationMatrix(rot);
01268 setOrientation(q);
01269 setPosition(cam_pos);
01270 setFieldOfView(fov);
01271 }
01272
01273
01274
01275
01276
01277
01278
01279
01280
01281
01282
01283
01284
01285
01286
01287
01288
01289
01290
01291
01292
01293
01294
01295
01296
01297
01298
01299
01300
01301
01302
01303
01304
01305
01306
01307
01308
01309
01310
01311
01312
01313
01314
01315
01316
01317
01318
01319
01320
01321
01322
01323
01324
01325
01326
01327
01328
01329
01330
01331
01332
01333
01334
01335
01337
01339 void Camera::getCameraCoordinatesOf(const float src[3], float res[3]) const
01340 {
01341 Vec r = cameraCoordinatesOf(Vec(src));
01342 for (int i=0; i<3; ++i)
01343 res[i] = r[i];
01344 }
01345
01347 void Camera::getWorldCoordinatesOf(const float src[3], float res[3]) const
01348 {
01349 Vec r = worldCoordinatesOf(Vec(src));
01350 for (int i=0; i<3; ++i)
01351 res[i] = r[i];
01352 }
01353
01359 void Camera::getViewport(GLint viewport[4]) const
01360 {
01361 viewport[0] = 0;
01362 viewport[1] = screenHeight();
01363 viewport[2] = screenWidth();
01364 viewport[3] = -screenHeight();
01365 }
01366
01441 Vec Camera::projectedCoordinatesOf(const Vec& src, const Frame* frame) const
01442 {
01443 GLdouble x,y,z;
01444 static GLint viewport[4];
01445 getViewport(viewport);
01446
01447 if (frame)
01448 {
01449 const Vec tmp = frame->inverseCoordinatesOf(src);
01450 gluProject(tmp.x,tmp.y,tmp.z, modelViewMatrix_, projectionMatrix_, viewport, &x,&y,&z);
01451 }
01452 else
01453 gluProject(src.x,src.y,src.z, modelViewMatrix_, projectionMatrix_, viewport, &x,&y,&z);
01454
01455 return Vec(x,y,z);
01456 }
01457
01483 Vec Camera::unprojectedCoordinatesOf(const Vec& src, const Frame* frame) const
01484 {
01485 GLdouble x,y,z;
01486 static GLint viewport[4];
01487 getViewport(viewport);
01488 gluUnProject(src.x,src.y,src.z, modelViewMatrix_, projectionMatrix_, viewport, &x,&y,&z);
01489 if (frame)
01490 return frame->coordinatesOf(Vec(x,y,z));
01491 else
01492 return Vec(x,y,z);
01493 }
01494
01496 void Camera::getProjectedCoordinatesOf(const float src[3], float res[3], const Frame* frame) const
01497 {
01498 Vec r = projectedCoordinatesOf(Vec(src), frame);
01499 for (int i=0; i<3; ++i)
01500 res[i] = r[i];
01501 }
01502
01504 void Camera::getUnprojectedCoordinatesOf(const float src[3], float res[3], const Frame* frame) const
01505 {
01506 Vec r = unprojectedCoordinatesOf(Vec(src), frame);
01507 for (int i=0; i<3; ++i)
01508 res[i] = r[i];
01509 }
01510
01512
01516 KeyFrameInterpolator* Camera::keyFrameInterpolator(int i) const
01517 {
01518 if (kfi_.contains(i))
01519 return kfi_[i];
01520 else
01521 return NULL;
01522 }
01523
01542 void Camera::setKeyFrameInterpolator(int i, KeyFrameInterpolator* const kfi)
01543 {
01544 if (kfi)
01545 kfi_[i] = kfi;
01546 else
01547 kfi_.remove(i);
01548 }
01549
01562 void Camera::addKeyFrameToPath(int i)
01563 {
01564 if (!kfi_.contains(i))
01565 setKeyFrameInterpolator(i, new KeyFrameInterpolator(frame()));
01566
01567 kfi_[i]->addKeyFrame(*(frame()));
01568 }
01569
01578 void Camera::playPath(int i)
01579 {
01580 if (kfi_.contains(i)) {
01581 if (kfi_[i]->interpolationIsStarted())
01582 kfi_[i]->stopInterpolation();
01583 else
01584 kfi_[i]->startInterpolation();
01585 }
01586 }
01587
01593 void Camera::resetPath(int i)
01594 {
01595 if (kfi_.contains(i)) {
01596 if ((kfi_[i]->interpolationIsStarted()))
01597 kfi_[i]->stopInterpolation();
01598 else
01599 {
01600 kfi_[i]->resetInterpolation();
01601 kfi_[i]->interpolateAtTime(kfi_[i]->interpolationTime());
01602 }
01603 }
01604 }
01605
01614 void Camera::deletePath(int i)
01615 {
01616 if (kfi_.contains(i))
01617 {
01618 kfi_[i]->stopInterpolation();
01619 delete kfi_[i];
01620 kfi_.remove(i);
01621 }
01622 }
01623
01630 void Camera::drawAllPaths()
01631 {
01632 for (QMap<int, KeyFrameInterpolator*>::ConstIterator it = kfi_.begin(), end=kfi_.end(); it != end; ++it)
01633 #if QT_VERSION >= 0x040000
01634 (it.value())->drawPath(3, 5, sceneRadius());
01635 #else
01636 (it.data())->drawPath(3, 5, sceneRadius());
01637 #endif
01638 }
01639
01641
01667 QDomElement Camera::domElement(const QString& name, QDomDocument& document) const
01668 {
01669 QDomElement de = document.createElement(name);
01670 QDomElement paramNode = document.createElement("Parameters");
01671 paramNode.setAttribute("fieldOfView", QString::number(fieldOfView()));
01672 paramNode.setAttribute("zNearCoefficient", QString::number(zNearCoefficient()));
01673 paramNode.setAttribute("zClippingCoefficient", QString::number(zClippingCoefficient()));
01674 paramNode.setAttribute("orthoCoef", QString::number(orthoCoef_));
01675 paramNode.setAttribute("sceneRadius", QString::number(sceneRadius()));
01676 paramNode.appendChild(sceneCenter().domElement("SceneCenter", document));
01677
01678 switch (type())
01679 {
01680 case Camera::PERSPECTIVE : paramNode.setAttribute("Type", "PERSPECTIVE"); break;
01681 case Camera::ORTHOGRAPHIC : paramNode.setAttribute("Type", "ORTHOGRAPHIC"); break;
01682 }
01683 de.appendChild(paramNode);
01684
01685 QDomElement stereoNode = document.createElement("Stereo");
01686 stereoNode.setAttribute("IODist", QString::number(IODistance()));
01687 stereoNode.setAttribute("focusDistance", QString::number(focusDistance()));
01688 stereoNode.setAttribute("physScreenWidth", QString::number(physicalScreenWidth()));
01689 de.appendChild(stereoNode);
01690
01691 de.appendChild(frame()->domElement("ManipulatedCameraFrame", document));
01692
01693
01694 for (QMap<int, KeyFrameInterpolator*>::ConstIterator it = kfi_.begin(), end=kfi_.end(); it != end; ++it)
01695 {
01696 #if QT_VERSION >= 0x040000
01697 QDomElement kfNode = (it.value())->domElement("KeyFrameInterpolator", document);
01698 #else
01699 QDomElement kfNode = (it.data())->domElement("KeyFrameInterpolator", document);
01700 #endif
01701 kfNode.setAttribute("index", QString::number(it.key()));
01702 de.appendChild(kfNode);
01703 }
01704
01705 return de;
01706 }
01707
01729 void Camera::initFromDOMElement(const QDomElement& element)
01730 {
01731 QDomElement child=element.firstChild().toElement();
01732
01733 #if QT_VERSION >= 0x040000
01734 QMutableMapIterator<int, KeyFrameInterpolator*> it(kfi_);
01735 while (it.hasNext()) {
01736 it.next();
01737 #else
01738 for (QMap<int, KeyFrameInterpolator*>::Iterator it = kfi_.begin(), end=kfi_.end(); it != end; ++it) {
01739 #endif
01740 deletePath(it.key());
01741 }
01742
01743 while (!child.isNull())
01744 {
01745 if (child.tagName() == "Parameters")
01746 {
01747
01748 setFieldOfView(DomUtils::floatFromDom(child, "fieldOfView", M_PI/4.0f));
01749 setZNearCoefficient(DomUtils::floatFromDom(child, "zNearCoefficient", 0.005f));
01750 setZClippingCoefficient(DomUtils::floatFromDom(child, "zClippingCoefficient", sqrt(3.0)));
01751 orthoCoef_ = DomUtils::floatFromDom(child, "orthoCoef", tan(fieldOfView()/2.0));
01752 setSceneRadius(DomUtils::floatFromDom(child, "sceneRadius", sceneRadius()));
01753
01754 setType(PERSPECTIVE);
01755 QString type = child.attribute("Type", "PERSPECTIVE");
01756 if (type == "PERSPECTIVE") setType(Camera::PERSPECTIVE);
01757 if (type == "ORTHOGRAPHIC") setType(Camera::ORTHOGRAPHIC);
01758
01759 QDomElement child2=child.firstChild().toElement();
01760 while (!child2.isNull())
01761 {
01762
01763
01764 if (child2.tagName() == "SceneCenter")
01765 setSceneCenter(Vec(child2));
01766
01767 child2 = child2.nextSibling().toElement();
01768 }
01769 }
01770
01771 if (child.tagName() == "ManipulatedCameraFrame")
01772 frame()->initFromDOMElement(child);
01773
01774 if (child.tagName() == "Stereo")
01775 {
01776 setIODistance(DomUtils::floatFromDom(child, "IODist", 0.062f));
01777 setFocusDistance(DomUtils::floatFromDom(child, "focusDistance", focusDistance()));
01778 setPhysicalScreenWidth(DomUtils::floatFromDom(child, "physScreenWidth", 0.5f));
01779 }
01780
01781 if (child.tagName() == "KeyFrameInterpolator")
01782 {
01783 int index = DomUtils::intFromDom(child, "index", 0);
01784 setKeyFrameInterpolator(index, new KeyFrameInterpolator(frame()));
01785 if (keyFrameInterpolator(index))
01786 keyFrameInterpolator(index)->initFromDOMElement(child);
01787 }
01788
01789 child = child.nextSibling().toElement();
01790 }
01791 }
01792
01804 void Camera::convertClickToLine(const QPoint& pixel, Vec& orig, Vec& dir) const
01805 {
01806 switch (type())
01807 {
01808 case Camera::PERSPECTIVE:
01809 orig = position();
01810 dir = Vec( ((2.0 * pixel.x() / screenWidth()) - 1.0) * tan(fieldOfView()/2.0) * aspectRatio(),
01811 ((2.0 * (screenHeight()-pixel.y()) / screenHeight()) - 1.0) * tan(fieldOfView()/2.0),
01812 -1.0 );
01813 dir = worldCoordinatesOf(dir) - orig;
01814 dir.normalize();
01815 break;
01816
01817 case Camera::ORTHOGRAPHIC:
01818 {
01819 GLdouble w,h;
01820 getOrthoWidthHeight(w,h);
01821 orig = Vec((2.0 * pixel.x() / screenWidth() - 1.0)*w, -(2.0 * pixel.y() / screenHeight() - 1.0)*h, 0.0);
01822 orig = worldCoordinatesOf(orig);
01823 dir = viewDirection();
01824 break;
01825 }
01826 }
01827 }
01828
01829 #ifndef DOXYGEN
01830
01831 void Camera::drawCamera(float, float, float)
01832 {
01833 qWarning("drawCamera is deprecated. Use Camera::draw() instead.");
01834 }
01835 #endif
01836
01857 void Camera::draw(bool drawFarPlane, float scale) const
01858 {
01859 glPushMatrix();
01860 glMultMatrixd(frame()->worldMatrix());
01861
01862
01863 Vec points[2];
01864
01865 points[0].z = scale * zNear();
01866 points[1].z = scale * zFar();
01867
01868 switch (type())
01869 {
01870 case Camera::PERSPECTIVE:
01871 {
01872 points[0].y = points[0].z * tan(fieldOfView()/2.0);
01873 points[0].x = points[0].y * aspectRatio();
01874
01875 const float ratio = points[1].z / points[0].z;
01876
01877 points[1].y = ratio * points[0].y;
01878 points[1].x = ratio * points[0].x;
01879 break;
01880 }
01881 case Camera::ORTHOGRAPHIC:
01882 {
01883 GLdouble hw, hh;
01884 getOrthoWidthHeight(hw, hh);
01885 points[0].x = points[1].x = scale * float(hw);
01886 points[0].y = points[1].y = scale * float(hh);
01887 break;
01888 }
01889 }
01890
01891 const int farIndex = drawFarPlane?1:0;
01892
01893
01894 glBegin(GL_QUADS);
01895 for (int i=farIndex; i>=0; --i)
01896 {
01897 glNormal3f(0.0, 0.0, (i==0)?1.0:-1.0);
01898 glVertex3f( points[i].x, points[i].y, -points[i].z);
01899 glVertex3f(-points[i].x, points[i].y, -points[i].z);
01900 glVertex3f(-points[i].x, -points[i].y, -points[i].z);
01901 glVertex3f( points[i].x, -points[i].y, -points[i].z);
01902 }
01903 glEnd();
01904
01905
01906 const float arrowHeight = 1.5f * points[0].y;
01907 const float baseHeight = 1.2f * points[0].y;
01908 const float arrowHalfWidth = 0.5f * points[0].x;
01909 const float baseHalfWidth = 0.3f * points[0].x;
01910
01911 glPolygonMode(GL_FRONT_AND_BACK, GL_FILL);
01912
01913 glBegin(GL_QUADS);
01914 glVertex3f(-baseHalfWidth, points[0].y, -points[0].z);
01915 glVertex3f( baseHalfWidth, points[0].y, -points[0].z);
01916 glVertex3f( baseHalfWidth, baseHeight, -points[0].z);
01917 glVertex3f(-baseHalfWidth, baseHeight, -points[0].z);
01918 glEnd();
01919
01920
01921 glBegin(GL_TRIANGLES);
01922 glVertex3f( 0.0f, arrowHeight, -points[0].z);
01923 glVertex3f(-arrowHalfWidth, baseHeight, -points[0].z);
01924 glVertex3f( arrowHalfWidth, baseHeight, -points[0].z);
01925 glEnd();
01926
01927
01928 switch (type())
01929 {
01930 case Camera::PERSPECTIVE :
01931 glBegin(GL_LINES);
01932 glVertex3f(0.0f, 0.0f, 0.0f);
01933 glVertex3f( points[farIndex].x, points[farIndex].y, -points[farIndex].z);
01934 glVertex3f(0.0f, 0.0f, 0.0f);
01935 glVertex3f(-points[farIndex].x, points[farIndex].y, -points[farIndex].z);
01936 glVertex3f(0.0f, 0.0f, 0.0f);
01937 glVertex3f(-points[farIndex].x, -points[farIndex].y, -points[farIndex].z);
01938 glVertex3f(0.0f, 0.0f, 0.0f);
01939 glVertex3f( points[farIndex].x, -points[farIndex].y, -points[farIndex].z);
01940 glEnd();
01941 break;
01942 case Camera::ORTHOGRAPHIC :
01943 if (drawFarPlane)
01944 {
01945 glBegin(GL_LINES);
01946 glVertex3f( points[0].x, points[0].y, -points[0].z);
01947 glVertex3f( points[1].x, points[1].y, -points[1].z);
01948 glVertex3f(-points[0].x, points[0].y, -points[0].z);
01949 glVertex3f(-points[1].x, points[1].y, -points[1].z);
01950 glVertex3f(-points[0].x, -points[0].y, -points[0].z);
01951 glVertex3f(-points[1].x, -points[1].y, -points[1].z);
01952 glVertex3f( points[0].x, -points[0].y, -points[0].z);
01953 glVertex3f( points[1].x, -points[1].y, -points[1].z);
01954 glEnd();
01955 }
01956 }
01957
01958 glPopMatrix();
01959 }
01960
01961
01985 void Camera::getFrustumPlanesCoefficients(GLdouble coef[6][4]) const
01986 {
01987
01988 const Vec pos = position();
01989 const Vec viewDir = viewDirection();
01990 const Vec up = upVector();
01991 const Vec right = rightVector();
01992 const float posViewDir = pos * viewDir;
01993
01994 static Vec normal[6];
01995 static GLdouble dist[6];
01996
01997 switch (type())
01998 {
01999 case Camera::PERSPECTIVE :
02000 {
02001 const float hhfov = horizontalFieldOfView() / 2.0;
02002 const float chhfov = cos(hhfov);
02003 const float shhfov = sin(hhfov);
02004 normal[0] = - shhfov * viewDir;
02005 normal[1] = normal[0] + chhfov * right;
02006 normal[0] = normal[0] - chhfov * right;
02007
02008 normal[2] = -viewDir;
02009 normal[3] = viewDir;
02010
02011 const float hfov = fieldOfView() / 2.0;
02012 const float chfov = cos(hfov);
02013 const float shfov = sin(hfov);
02014 normal[4] = - shfov * viewDir;
02015 normal[5] = normal[4] - chfov * up;
02016 normal[4] = normal[4] + chfov * up;
02017
02018 for (int i=0; i<2; ++i)
02019 dist[i] = pos * normal[i];
02020 for (int j=4; j<6; ++j)
02021 dist[j] = pos * normal[j];
02022
02023
02024
02025
02026
02027
02028
02029 const float posRightCosHH = chhfov * pos * right;
02030 dist[0] = -shhfov * posViewDir;
02031 dist[1] = dist[0] + posRightCosHH;
02032 dist[0] = dist[0] - posRightCosHH;
02033 const float posUpCosH = chfov * pos * up;
02034 dist[4] = - shfov * posViewDir;
02035 dist[5] = dist[4] - posUpCosH;
02036 dist[4] = dist[4] + posUpCosH;
02037
02038 break;
02039 }
02040 case Camera::ORTHOGRAPHIC :
02041 normal[0] = -right;
02042 normal[1] = right;
02043 normal[4] = up;
02044 normal[5] = -up;
02045
02046 GLdouble hw, hh;
02047 getOrthoWidthHeight(hw, hh);
02048 dist[0] = (pos - hw * right) * normal[0];
02049 dist[1] = (pos + hw * right) * normal[1];
02050 dist[4] = (pos + hh * up) * normal[4];
02051 dist[5] = (pos - hh * up) * normal[5];
02052 break;
02053 }
02054
02055
02056 normal[2] = -viewDir;
02057 normal[3] = viewDir;
02058 dist[2] = -posViewDir - zNear();
02059 dist[3] = posViewDir + zFar();
02060
02061 for (int i=0; i<6; ++i)
02062 {
02063 coef[i][0] = GLdouble(normal[i].x);
02064 coef[i][1] = GLdouble(normal[i].y);
02065 coef[i][2] = GLdouble(normal[i].z);
02066 coef[i][3] = dist[i];
02067 }
02068 }