39 : frame_(NULL), fieldOfView_(
M_PI/4.0), modelViewMatrixIsUpToDate_(false), projectionMatrixIsUpToDate_(false)
73 for (
unsigned short j=0; j<16; ++j)
102 for (
unsigned short j=0; j<16; ++j)
354 const qreal ZNear =
zNear();
355 const qreal ZFar =
zFar();
406 const qreal q00 = 2.0 * q[0] * q[0];
407 const qreal q11 = 2.0 * q[1] * q[1];
408 const qreal q22 = 2.0 * q[2] * q[2];
410 const qreal q01 = 2.0 * q[0] * q[1];
411 const qreal q02 = 2.0 * q[0] * q[2];
412 const qreal q03 = 2.0 * q[0] * q[3];
414 const qreal q12 = 2.0 * q[1] * q[2];
415 const qreal q13 = 2.0 * q[1] * q[3];
417 const qreal q23 = 2.0 * q[2] * q[3];
466 glMatrixMode(GL_PROJECTION);
503 glMatrixMode(GL_MODELVIEW);
538 qreal left, right, bottom, top;
539 qreal screenHalfWidth, halfWidth, side, shift, delta;
541 glMatrixMode(GL_PROJECTION);
558 side = leftBuffer ? -1.0 : 1.0;
560 left = -halfWidth + side * delta;
561 right = halfWidth + side * delta;
564 glFrustum(left, right, bottom, top,
zNear(),
zFar() );
568 qWarning(
"Camera::setProjectionMatrixStereo: Stereo not available with Ortho mode");
594 glMatrixMode(GL_MODELVIEW);
624 for (
unsigned short i=0; i<16; ++i)
631 static GLdouble mat[16];
633 for (
unsigned short i=0; i<16; ++i)
634 m[i] =
float(mat[i]);
656 for (
unsigned short i=0; i<16; ++i)
664 static GLdouble mat[16];
666 for (
unsigned short i=0; i<16; ++i)
667 m[i] =
float(mat[i]);
680 for (
unsigned short i=0; i<4; ++i)
682 for (
unsigned short j=0; j<4; ++j)
685 for (
unsigned short k=0; k<4; ++k)
686 sum += proj[i+4*k]*mv[k+4*j];
695 static GLdouble mat[16];
697 for (
unsigned short i=0; i<16; ++i)
698 m[i] =
float(mat[i]);
709 qWarning(
"Scene radius must be positive - Ignoring value");
756 qWarning(
"setRevolveAroundPoint() is deprecated, use setPivotPoint() instead");
760 qWarning(
"setRevolveAroundPointFromPixel() is deprecated, use setPivotPointFromPixel() instead");
764 qWarning(
"revolveAroundPoint() is deprecated, use pivotPoint() instead");
782 if ((prevDist > 1E-9) && (newDist > 1E-9))
877 const qreal coef = 0.1;
975 glReadPixels(pixel.x(),
screenHeight()-1-pixel.y(), 1, 1, GL_DEPTH_COMPONENT, GL_FLOAT, &depth);
977 Vec point(pixel.x(), pixel.y(), depth);
1022 qreal distance = 0.0;
1027 const qreal yview = radius / sin(
fieldOfView() / 2.0);
1029 distance = qMax(xview, yview);
1046 qreal diameter = qMax(fabs(max[1]-min[1]), fabs(max[0]-min[0]));
1047 diameter = qMax(fabs(max[2]-min[2]), diameter);
1062 const QPoint center = rectangle.center();
1066 Vec newCenter = orig + distToPlane / (dir*vd) * dir;
1069 const Vec pointX = orig + distToPlane / (dir*vd) * dir;
1072 const Vec pointY = orig + distToPlane / (dir*vd) * dir;
1074 qreal distance = 0.0;
1080 const qreal distY = (pointY-newCenter).norm() / sin(
fieldOfView()/2.0);
1081 distance = qMax(distX, distY);
1086 const qreal dist = ((newCenter-
pivotPoint()) * vd);
1090 distance = dist + qMax(distX, distY);
1095 Vec newPos(newCenter - distance * vd);
1142 Vec axis(0.0, 1.0, 0.0);
1144 axis =
Vec(-cos(theta), 0.0, sin(theta));
1180 static qreal
det(qreal m00,qreal m01,qreal m02,
1181 qreal m10,qreal m11,qreal m12,
1182 qreal m20,qreal m21,qreal m22)
1184 return m00*m11*m22 + m01*m12*m20 + m02*m10*m21 - m20*m11*m02 - m10*m01*m22 - m00*m21*m12;
1188 static inline unsigned int ind(
unsigned int i,
unsigned int j)
1297 qreal upperLeft[3][3];
1298 for (
int i=0; i<3; ++i)
1299 for (
int j=0; j<3; ++j)
1300 upperLeft[i][j] = modelViewMatrix[i*4+j];
1336 Vec line_0(matrix[
ind(0,0)],matrix[
ind(0,1)],matrix[
ind(0,2)]);
1337 Vec line_1(matrix[
ind(1,0)],matrix[
ind(1,1)],matrix[
ind(1,2)]);
1338 Vec line_2(matrix[
ind(2,0)],matrix[
ind(2,1)],matrix[
ind(2,2)]);
1354 matrix[
ind(1,1)],matrix[
ind(1,2)],matrix[
ind(1,3)],
1355 matrix[
ind(2,1)],matrix[
ind(2,2)],matrix[
ind(2,3)]),
1357 -
det(matrix[
ind(0,0)],matrix[
ind(0,2)],matrix[
ind(0,3)],
1358 matrix[
ind(1,0)],matrix[
ind(1,2)],matrix[
ind(1,3)],
1359 matrix[
ind(2,0)],matrix[
ind(2,2)],matrix[
ind(2,3)]),
1361 det(matrix[
ind(0,0)],matrix[
ind(0,1)],matrix[
ind(0,3)],
1362 matrix[
ind(1,0)],matrix[
ind(1,1)],matrix[
ind(1,3)],
1363 matrix[
ind(2,0)],matrix[
ind(2,1)],matrix[
ind(2,3)])) /
1365 (-
det(matrix[
ind(0,0)],matrix[
ind(0,1)],matrix[
ind(0,2)],
1366 matrix[
ind(1,0)],matrix[
ind(1,1)],matrix[
ind(1,2)],
1367 matrix[
ind(2,0)],matrix[
ind(2,1)],matrix[
ind(2,2)]));
1372 Vec column_2 = -line_2;
1375 Vec column_0 = ((column_2^line_0)^column_2);
1380 Vec column_1 = -((column_2^line_1)^column_2);
1384 rot[0][0] = column_0[0];
1385 rot[1][0] = column_0[1];
1386 rot[2][0] = column_0[2];
1388 rot[0][1] = column_1[0];
1389 rot[1][1] = column_1[1];
1390 rot[2][1] = column_1[2];
1392 rot[0][2] = column_2[0];
1393 rot[1][2] = column_2[1];
1394 rot[2][2] = column_2[2];
1404 Vec dummy = line_1^column_0;
1406 qreal fov = acos(column_2*dummy) * 2.0;
1485 for (
int i=0; i<3; ++i)
1493 for (
int i=0; i<3; ++i)
1587 static GLint viewport[4];
1634 static GLint viewport[4];
1647 for (
int i=0; i<3; ++i)
1655 for (
int i=0; i<3; ++i)
1666 if (
kfi_.contains(i))
1712 if (!
kfi_.contains(i))
1728 if (
kfi_.contains(i)) {
1729 if (
kfi_[i]->interpolationIsStarted())
1730 kfi_[i]->stopInterpolation();
1732 kfi_[i]->startInterpolation();
1743 if (
kfi_.contains(i)) {
1744 if ((
kfi_[i]->interpolationIsStarted()))
1745 kfi_[i]->stopInterpolation();
1748 kfi_[i]->resetInterpolation();
1749 kfi_[i]->interpolateAtTime(
kfi_[i]->interpolationTime());
1764 if (
kfi_.contains(i))
1766 kfi_[i]->stopInterpolation();
1780 for (QMap<unsigned int, KeyFrameInterpolator*>::ConstIterator it =
kfi_.begin(), end=
kfi_.end(); it != end; ++it)
1813 QDomElement de = document.createElement(name);
1814 QDomElement paramNode = document.createElement(
"Parameters");
1815 paramNode.setAttribute(
"fieldOfView", QString::number(
fieldOfView()));
1816 paramNode.setAttribute(
"zNearCoefficient", QString::number(
zNearCoefficient()));
1818 paramNode.setAttribute(
"orthoCoef", QString::number(
orthoCoef_));
1819 paramNode.setAttribute(
"sceneRadius", QString::number(
sceneRadius()));
1827 de.appendChild(paramNode);
1829 QDomElement stereoNode = document.createElement(
"Stereo");
1830 stereoNode.setAttribute(
"IODist", QString::number(
IODistance()));
1831 stereoNode.setAttribute(
"focusDistance", QString::number(
focusDistance()));
1833 de.appendChild(stereoNode);
1835 de.appendChild(
frame()->
domElement(
"ManipulatedCameraFrame", document));
1838 for (QMap<unsigned int, KeyFrameInterpolator*>::ConstIterator it =
kfi_.begin(), end=
kfi_.end(); it != end; ++it)
1840 QDomElement kfNode = (it.value())->
domElement(
"KeyFrameInterpolator", document);
1841 kfNode.setAttribute(
"index", QString::number(it.key()));
1842 de.appendChild(kfNode);
1871 QDomElement child=element.firstChild().toElement();
1873 QMutableMapIterator<unsigned int, KeyFrameInterpolator*> it(
kfi_);
1874 while (it.hasNext()) {
1879 while (!child.isNull())
1881 if (child.tagName() ==
"Parameters")
1891 QString
type = child.attribute(
"Type",
"PERSPECTIVE");
1895 QDomElement child2=child.firstChild().toElement();
1896 while (!child2.isNull())
1900 if (child2.tagName() ==
"SceneCenter")
1903 child2 = child2.nextSibling().toElement();
1907 if (child.tagName() ==
"ManipulatedCameraFrame")
1910 if (child.tagName() ==
"Stereo")
1917 if (child.tagName() ==
"KeyFrameInterpolator")
1925 child = child.nextSibling().toElement();
1969 qWarning(
"drawCamera is deprecated. Use Camera::draw() instead.");
1996 glMultMatrixd(
frame()->worldMatrix());
2001 points[0].
z = scale *
zNear();
2002 points[1].
z = scale *
zFar();
2011 const qreal ratio = points[1].
z / points[0].
z;
2013 points[1].
y = ratio * points[0].
y;
2014 points[1].
x = ratio * points[0].
x;
2021 points[0].
x = points[1].
x = scale * qreal(hw);
2022 points[0].
y = points[1].
y = scale * qreal(hh);
2027 const int farIndex = drawFarPlane?1:0;
2031 for (
int i=farIndex; i>=0; --i)
2033 glNormal3d(0.0f, 0.0f, (i==0)?1.0f:-1.0f);
2034 glVertex3d( points[i].x, points[i].y, -points[i].z);
2035 glVertex3d(-points[i].x, points[i].y, -points[i].z);
2036 glVertex3d(-points[i].x, -points[i].y, -points[i].z);
2037 glVertex3d( points[i].x, -points[i].y, -points[i].z);
2042 const qreal arrowHeight = 1.5 * points[0].
y;
2043 const qreal baseHeight = 1.2 * points[0].
y;
2044 const qreal arrowHalfWidth = 0.5 * points[0].
x;
2045 const qreal baseHalfWidth = 0.3 * points[0].
x;
2047 glPolygonMode(GL_FRONT_AND_BACK, GL_FILL);
2050 glVertex3d(-baseHalfWidth, points[0].y, -points[0].z);
2051 glVertex3d( baseHalfWidth, points[0].y, -points[0].z);
2052 glVertex3d( baseHalfWidth, baseHeight, -points[0].z);
2053 glVertex3d(-baseHalfWidth, baseHeight, -points[0].z);
2057 glBegin(GL_TRIANGLES);
2058 glVertex3d( 0.0, arrowHeight, -points[0].z);
2059 glVertex3d(-arrowHalfWidth, baseHeight, -points[0].z);
2060 glVertex3d( arrowHalfWidth, baseHeight, -points[0].z);
2068 glVertex3d(0.0, 0.0, 0.0);
2069 glVertex3d( points[farIndex].x, points[farIndex].y, -points[farIndex].z);
2070 glVertex3d(0.0, 0.0, 0.0);
2071 glVertex3d(-points[farIndex].x, points[farIndex].y, -points[farIndex].z);
2072 glVertex3d(0.0, 0.0, 0.0);
2073 glVertex3d(-points[farIndex].x, -points[farIndex].y, -points[farIndex].z);
2074 glVertex3d(0.0, 0.0, 0.0);
2075 glVertex3d( points[farIndex].x, -points[farIndex].y, -points[farIndex].z);
2082 glVertex3d( points[0].x, points[0].y, -points[0].z);
2083 glVertex3d( points[1].x, points[1].y, -points[1].z);
2084 glVertex3d(-points[0].x, points[0].y, -points[0].z);
2085 glVertex3d(-points[1].x, points[1].y, -points[1].z);
2086 glVertex3d(-points[0].x, -points[0].y, -points[0].z);
2087 glVertex3d(-points[1].x, -points[1].y, -points[1].z);
2088 glVertex3d( points[0].x, -points[0].y, -points[0].z);
2089 glVertex3d( points[1].x, -points[1].y, -points[1].z);
2128 const qreal posViewDir = pos * viewDir;
2130 static Vec normal[6];
2131 static GLdouble dist[6];
2138 const qreal chhfov = cos(hhfov);
2139 const qreal shhfov = sin(hhfov);
2140 normal[0] = - shhfov * viewDir;
2141 normal[1] = normal[0] + chhfov * right;
2142 normal[0] = normal[0] - chhfov * right;
2144 normal[2] = -viewDir;
2145 normal[3] = viewDir;
2148 const qreal chfov = cos(hfov);
2149 const qreal shfov = sin(hfov);
2150 normal[4] = - shfov * viewDir;
2151 normal[5] = normal[4] - chfov * up;
2152 normal[4] = normal[4] + chfov * up;
2154 for (
int i=0; i<2; ++i)
2155 dist[i] = pos * normal[i];
2156 for (
int j=4; j<6; ++j)
2157 dist[j] = pos * normal[j];
2165 const qreal posRightCosHH = chhfov * pos * right;
2166 dist[0] = -shhfov * posViewDir;
2167 dist[1] = dist[0] + posRightCosHH;
2168 dist[0] = dist[0] - posRightCosHH;
2169 const qreal posUpCosH = chfov * pos * up;
2170 dist[4] = - shfov * posViewDir;
2171 dist[5] = dist[4] - posUpCosH;
2172 dist[4] = dist[4] + posUpCosH;
2184 dist[0] = (pos - hw * right) * normal[0];
2185 dist[1] = (pos + hw * right) * normal[1];
2186 dist[4] = (pos + hh * up) * normal[4];
2187 dist[5] = (pos - hh * up) * normal[5];
2192 normal[2] = -viewDir;
2193 normal[3] = viewDir;
2194 dist[2] = -posViewDir -
zNear();
2195 dist[3] = posViewDir +
zFar();
2197 for (
int i=0; i<6; ++i)
2199 coef[i][0] = GLdouble(normal[i].x);
2200 coef[i][1] = GLdouble(normal[i].y);
2201 coef[i][2] = GLdouble(normal[i].z);
2202 coef[i][3] = dist[i];
void setZClippingCoefficient(qreal coef)
void setScreenWidthAndHeight(int width, int height)
void startInterpolation(int period=-1)
void setKeyFrameInterpolator(unsigned int i, KeyFrameInterpolator *const kfi)
Vec worldCoordinatesOf(const Vec &src) const
A keyFrame Catmull-Rom Frame interpolator.
qreal aspectRatio() const
virtual QDomElement domElement(const QString &name, QDomDocument &document) const
virtual qreal zFar() const
void fitSphere(const Vec ¢er, qreal radius)
The ManipulatedCameraFrame class represents a ManipulatedFrame with Camera specific mouse bindings...
virtual void drawAllPaths()
void resetInterpolation()
Vec inverseTransformOf(const Vec &src) const
Vec revolveAroundPoint() const
virtual void loadProjectionMatrixStereo(bool leftBuffer=true) const
void setFrame(Frame *const frame)
void convertClickToLine(const QPoint &pixel, Vec &orig, Vec &dir) const
void getModelViewProjectionMatrix(GLfloat m[16]) const
Camera & operator=(const Camera &camera)
void interpolateToFitScene()
qreal fieldOfView() const
void setOrientation(const Quaternion &q)
bool setRevolveAroundPointFromPixel(const QPoint &pixel)
void setIODistance(qreal distance)
bool setPivotPointFromPixel(const QPoint &pixel)
qreal distanceToSceneCenter() const
static qreal det(qreal m00, qreal m01, qreal m02, qreal m10, qreal m11, qreal m12, qreal m20, qreal m21, qreal m22)
void addKeyFrame(const Frame &frame)
void lookAt(const Vec &target)
virtual void loadProjectionMatrix(bool reset=true) const
void getProjectionMatrix(GLfloat m[16]) const
void computeModelViewMatrix() const
void setSceneCenter(const Vec ¢er)
Vec projectedCoordinatesOf(const Vec &src, const Frame *frame=NULL) const
void setSceneBoundingBox(const Vec &min, const Vec &max)
virtual void deletePath(unsigned int i)
void setPositionWithConstraint(Vec &position)
GLdouble projectionMatrix_[16]
virtual void loadModelViewMatrix(bool reset=true) const
qreal squaredNorm() const
void setSceneRadius(qreal radius)
void setFlySpeed(qreal speed)
void setPosition(const Vec &pos)
virtual void loadModelViewMatrixStereo(bool leftBuffer=true) const
Vec rotate(const Vec &v) const
void setPivotPoint(const Vec &point)
void getProjectedCoordinatesOf(const qreal src[3], qreal res[3], const Frame *frame=NULL) const
void getViewport(GLint viewport[4]) const
Vec pointUnderPixel(const QPoint &pixel, bool &found) const
bool setSceneCenterFromPixel(const QPoint &pixel)
void getFrustumPlanesCoefficients(GLdouble coef[6][4]) const
virtual void initFromDOMElement(const QDomElement &element)
void setFromRotationMatrix(const float m[3][3])
static void drawCamera(qreal scale=1.0, qreal aspectRatio=1.33, qreal fieldOfView=qreal(M_PI)/4.0)
void setReferenceFrame(const Frame *const refFrame)
void computeProjectionMatrix() const
void updateSceneUpVector()
void getModelViewMatrix(GLfloat m[16]) const
qreal horizontalFieldOfView() const
ManipulatedCameraFrame * frame() const
qreal pixelGLRatio(const Vec &position) const
void fitScreenRegion(const QRect &rectangle)
void rotate(Quaternion &q)
qreal sceneRadius() const
The Vec class represents 3D positions and 3D vectors.
void setViewDirection(const Vec &direction)
virtual void getOrthoWidthHeight(GLdouble &halfWidth, GLdouble &halfHeight) const
ManipulatedCameraFrame * frame_
qreal zNearCoefficient() const
void fitBoundingBox(const Vec &min, const Vec &max)
KeyFrameInterpolator * interpolationKfi_
void projectOnLine(const Vec &origin, const Vec &direction)
QMap< unsigned int, KeyFrameInterpolator * > kfi_
Vec cameraCoordinatesOf(const Vec &src) const
void getCameraCoordinatesOf(const qreal src[3], qreal res[3]) const
bool modelViewMatrixIsUpToDate_
void interpolateToZoomOnPixel(const QPoint &pixel)
qreal focusDistance() const
bool interpolationIsStarted() const
static unsigned int uintFromDom(const QDomElement &e, const QString &attribute, unsigned int defValue)
void setZNearCoefficient(qreal coef)
void setPhysicalScreenWidth(qreal width)
static qreal qrealFromDom(const QDomElement &e, const QString &attribute, qreal defValue)
qreal physicalScreenWidth() const
KeyFrameInterpolator * keyFrameInterpolator(unsigned int i) const
virtual void draw(bool drawFarPlane=true, qreal scale=1.0) const
Vec coordinatesOf(const Vec &src) const
A perspective or orthographic camera.
void setFrame(ManipulatedCameraFrame *const mcf)
virtual void initFromDOMElement(const QDomElement &element)
void getWorldCoordinatesOf(const qreal src[3], qreal res[3]) const
The Quaternion class represents 3D rotations and orientations.
void setFromRotatedBasis(const Vec &X, const Vec &Y, const Vec &Z)
Quaternion orientation() const
virtual void addKeyFrameToPath(unsigned int i)
void getUnprojectedCoordinatesOf(const qreal src[3], qreal res[3], const Frame *frame=NULL) const
void setOrientationWithConstraint(Quaternion &orientation)
Vec viewDirection() const
virtual void resetPath(unsigned int i)
void interpolateTo(const Frame &fr, qreal duration)
void setPosition(const Vec &position)
Quaternion orientation() const
void setFocusDistance(qreal distance)
virtual void initFromDOMElement(const QDomElement &element)
void setFieldOfView(qreal fov)
The Frame class represents a coordinate system, defined by a position and an orientation.
void setRevolveAroundPoint(const Vec &point)
void setFromModelViewMatrix(const GLdouble *const modelViewMatrix)
static unsigned int ind(unsigned int i, unsigned int j)
void setFlySpeed(qreal speed)
virtual void playPath(unsigned int i)
void setOrientation(const Quaternion &orientation)
void setUpVector(const Vec &up, bool noMove=true)
GLdouble modelViewMatrix_[16]
bool projectionMatrixIsUpToDate_
virtual qreal zNear() const
Vec inverseCoordinatesOf(const Vec &src) const
Vec unprojectedCoordinatesOf(const Vec &src, const Frame *frame=NULL) const
qreal zClippingCoefficient() const
void setFromProjectionMatrix(const qreal matrix[12])
void setPivotPoint(const Vec &point)