38 : fieldOfView_(
M_PI/4.0f)
72 for (
unsigned short j=0; j<16; ++j)
101 for (
unsigned short j=0; j<16; ++j)
329 const float ZNear =
zNear();
330 const float ZFar =
zFar();
377 const double q00 = 2.0l * q[0] * q[0];
378 const double q11 = 2.0l * q[1] * q[1];
379 const double q22 = 2.0l * q[2] * q[2];
381 const double q01 = 2.0l * q[0] * q[1];
382 const double q02 = 2.0l * q[0] * q[2];
383 const double q03 = 2.0l * q[0] * q[3];
385 const double q12 = 2.0l * q[1] * q[2];
386 const double q13 = 2.0l * q[1] * q[3];
388 const double q23 = 2.0l * q[2] * q[3];
435 glMatrixMode(GL_PROJECTION);
472 glMatrixMode(GL_MODELVIEW);
507 float left, right, bottom, top;
508 float screenHalfWidth, halfWidth, side, shift, delta;
510 glMatrixMode(GL_PROJECTION);
527 side = leftBuffer ? -1.0 : 1.0;
529 left = -halfWidth + side * delta;
530 right = halfWidth + side * delta;
533 glFrustum(left, right, bottom, top,
zNear(),
zFar() );
537 qWarning(
"Camera::setProjectionMatrixStereo: Stereo not available with Ortho mode");
563 glMatrixMode(GL_MODELVIEW);
594 for (
unsigned short i=0; i<16; ++i)
617 for (
unsigned short i=0; i<16; ++i)
631 for (
unsigned short i=0; i<4; ++i)
633 for (
unsigned short j=0; j<4; ++j)
636 for (
unsigned short k=0; k<4; ++k)
637 sum += proj[i+4*k]*mv[k+4*j];
646 qWarning(
"Warning : Camera::getProjectionMatrix requires a GLdouble matrix array");
647 static GLdouble mat[16];
649 for (
int i=0; i<16; ++i)
650 m[i] =
float(mat[i]);
655 qWarning(
"Warning : Camera::getModelViewMatrix requires a GLdouble matrix array");
656 static GLdouble mat[16];
658 for (
int i=0; i<16; ++i)
659 m[i] =
float(mat[i]);
671 qWarning(
"Scene radius must be positive - Ignoring value");
725 if ((prevDist > 1E-9) && (newDist > 1E-9))
819 const float coef = 0.1f;
917 glReadPixels(pixel.x(),
screenHeight()-1-pixel.y(), 1, 1, GL_DEPTH_COMPONENT, GL_FLOAT, &depth);
919 Vec point(pixel.x(), pixel.y(), depth);
964 float distance = 0.0f;
969 const float yview = radius / sin(
fieldOfView()/2.0);
971 distance =
qMax(xview,yview);
988 float diameter =
qMax(fabs(max[1]-min[1]), fabs(max[0]-min[0]));
989 diameter =
qMax(fabsf(max[2]-min[2]), diameter);
1004 const QPoint center = rectangle.center();
1008 Vec newCenter = orig + distToPlane / (dir*vd) * dir;
1011 const Vec pointX = orig + distToPlane / (dir*vd) * dir;
1014 const Vec pointY = orig + distToPlane / (dir*vd) * dir;
1016 float distance = 0.0f;
1022 const float distY = (pointY-newCenter).norm() / sin(
fieldOfView()/2.0);
1023 distance =
qMax(distX, distY);
1032 distance = dist +
qMax(distX, distY);
1037 Vec newPos(newCenter - distance * vd);
1082 Vec axis(0.0, 1.0, 0.0);
1084 axis =
Vec(-cos(theta), 0., sin(theta));
1120 static float det(
float m00,
float m01,
float m02,
1121 float m10,
float m11,
float m12,
1122 float m20,
float m21,
float m22)
1124 return m00*m11*m22 + m01*m12*m20 + m02*m10*m21 - m20*m11*m02 - m10*m01*m22 - m00*m21*m12;
1128 static inline unsigned int ind(
unsigned int i,
unsigned int j)
1154 double upperLeft[3][3];
1155 for (
int i=0; i<3; ++i)
1156 for (
int j=0; j<3; ++j)
1157 upperLeft[i][j] = modelViewMatrix[i*4+j];
1193 Vec line_0(matrix[
ind(0,0)],matrix[
ind(0,1)],matrix[
ind(0,2)]);
1194 Vec line_1(matrix[
ind(1,0)],matrix[
ind(1,1)],matrix[
ind(1,2)]);
1195 Vec line_2(matrix[
ind(2,0)],matrix[
ind(2,1)],matrix[
ind(2,2)]);
1211 matrix[
ind(1,1)],matrix[
ind(1,2)],matrix[
ind(1,3)],
1212 matrix[
ind(2,1)],matrix[
ind(2,2)],matrix[
ind(2,3)]),
1214 -
det(matrix[
ind(0,0)],matrix[
ind(0,2)],matrix[
ind(0,3)],
1215 matrix[
ind(1,0)],matrix[
ind(1,2)],matrix[
ind(1,3)],
1216 matrix[
ind(2,0)],matrix[
ind(2,2)],matrix[
ind(2,3)]),
1218 det(matrix[
ind(0,0)],matrix[
ind(0,1)],matrix[
ind(0,3)],
1219 matrix[
ind(1,0)],matrix[
ind(1,1)],matrix[
ind(1,3)],
1220 matrix[
ind(2,0)],matrix[
ind(2,1)],matrix[
ind(2,3)])) /
1222 (-
det(matrix[
ind(0,0)],matrix[
ind(0,1)],matrix[
ind(0,2)],
1223 matrix[
ind(1,0)],matrix[
ind(1,1)],matrix[
ind(1,2)],
1224 matrix[
ind(2,0)],matrix[
ind(2,1)],matrix[
ind(2,2)]));
1229 Vec column_2 = -line_2;
1232 Vec column_0 = ((column_2^line_0)^column_2);
1237 Vec column_1 = -((column_2^line_1)^column_2);
1241 rot[0][0] = column_0[0];
1242 rot[1][0] = column_0[1];
1243 rot[2][0] = column_0[2];
1245 rot[0][1] = column_1[0];
1246 rot[1][1] = column_1[1];
1247 rot[2][1] = column_1[2];
1249 rot[0][2] = column_2[0];
1250 rot[1][2] = column_2[1];
1251 rot[2][2] = column_2[2];
1261 Vec dummy = line_1^column_0;
1263 float fov = acos(column_2*dummy) * 2.0;
1342 for (
int i=0; i<3; ++i)
1350 for (
int i=0; i<3; ++i)
1444 static GLint viewport[4];
1486 static GLint viewport[4];
1499 for (
int i=0; i<3; ++i)
1507 for (
int i=0; i<3; ++i)
1518 if (
kfi_.contains(i))
1564 if (!
kfi_.contains(i))
1580 if (
kfi_.contains(i)) {
1581 if (
kfi_[i]->interpolationIsStarted())
1582 kfi_[i]->stopInterpolation();
1584 kfi_[i]->startInterpolation();
1595 if (
kfi_.contains(i)) {
1596 if ((
kfi_[i]->interpolationIsStarted()))
1597 kfi_[i]->stopInterpolation();
1600 kfi_[i]->resetInterpolation();
1601 kfi_[i]->interpolateAtTime(
kfi_[i]->interpolationTime());
1616 if (
kfi_.contains(i))
1618 kfi_[i]->stopInterpolation();
1632 for (QMap<int, KeyFrameInterpolator*>::ConstIterator it =
kfi_.begin(), end=
kfi_.end(); it != end; ++it)
1633 #
if QT_VERSION >= 0x040000
1669 QDomElement de = document.createElement(name);
1670 QDomElement paramNode = document.createElement(
"Parameters");
1671 paramNode.setAttribute(
"fieldOfView", QString::number(
fieldOfView()));
1672 paramNode.setAttribute(
"zNearCoefficient", QString::number(
zNearCoefficient()));
1674 paramNode.setAttribute(
"orthoCoef", QString::number(
orthoCoef_));
1675 paramNode.setAttribute(
"sceneRadius", QString::number(
sceneRadius()));
1683 de.appendChild(paramNode);
1685 QDomElement stereoNode = document.createElement(
"Stereo");
1686 stereoNode.setAttribute(
"IODist", QString::number(
IODistance()));
1687 stereoNode.setAttribute(
"focusDistance", QString::number(
focusDistance()));
1689 de.appendChild(stereoNode);
1691 de.appendChild(
frame()->
domElement(
"ManipulatedCameraFrame", document));
1694 for (QMap<int, KeyFrameInterpolator*>::ConstIterator it =
kfi_.begin(), end=
kfi_.end(); it != end; ++it)
1696 #if QT_VERSION >= 0x040000 1697 QDomElement kfNode = (it.value())->
domElement(
"KeyFrameInterpolator", document);
1699 QDomElement kfNode = (it.data())->
domElement(
"KeyFrameInterpolator", document);
1701 kfNode.setAttribute(
"index", QString::number(it.key()));
1702 de.appendChild(kfNode);
1731 QDomElement child=element.firstChild().toElement();
1733 #if QT_VERSION >= 0x040000 1734 QMutableMapIterator<int, KeyFrameInterpolator*> it(
kfi_);
1735 while (it.hasNext()) {
1738 for (QMap<int, KeyFrameInterpolator*>::Iterator it =
kfi_.begin(), end=
kfi_.end(); it != end; ++it) {
1743 while (!child.isNull())
1745 if (child.tagName() ==
"Parameters")
1755 QString
type = child.attribute(
"Type",
"PERSPECTIVE");
1759 QDomElement child2=child.firstChild().toElement();
1760 while (!child2.isNull())
1764 if (child2.tagName() ==
"SceneCenter")
1767 child2 = child2.nextSibling().toElement();
1771 if (child.tagName() ==
"ManipulatedCameraFrame")
1774 if (child.tagName() ==
"Stereo")
1781 if (child.tagName() ==
"KeyFrameInterpolator")
1789 child = child.nextSibling().toElement();
1833 qWarning(
"drawCamera is deprecated. Use Camera::draw() instead.");
1860 glMultMatrixd(
frame()->worldMatrix());
1865 points[0].
z = scale *
zNear();
1866 points[1].
z = scale *
zFar();
1875 const float ratio = points[1].
z / points[0].
z;
1877 points[1].
y = ratio * points[0].
y;
1878 points[1].
x = ratio * points[0].
x;
1885 points[0].
x = points[1].
x = scale * float(hw);
1886 points[0].
y = points[1].
y = scale * float(hh);
1891 const int farIndex = drawFarPlane?1:0;
1895 for (
int i=farIndex; i>=0; --i)
1897 glNormal3f(0.0, 0.0, (i==0)?1.0:-1.0);
1898 glVertex3f( points[i].x, points[i].y, -points[i].z);
1899 glVertex3f(-points[i].x, points[i].y, -points[i].z);
1900 glVertex3f(-points[i].x, -points[i].y, -points[i].z);
1901 glVertex3f( points[i].x, -points[i].y, -points[i].z);
1906 const float arrowHeight = 1.5f * points[0].
y;
1907 const float baseHeight = 1.2f * points[0].
y;
1908 const float arrowHalfWidth = 0.5f * points[0].
x;
1909 const float baseHalfWidth = 0.3f * points[0].
x;
1911 glPolygonMode(GL_FRONT_AND_BACK, GL_FILL);
1914 glVertex3f(-baseHalfWidth, points[0].y, -points[0].z);
1915 glVertex3f( baseHalfWidth, points[0].y, -points[0].z);
1916 glVertex3f( baseHalfWidth, baseHeight, -points[0].z);
1917 glVertex3f(-baseHalfWidth, baseHeight, -points[0].z);
1921 glBegin(GL_TRIANGLES);
1922 glVertex3f( 0.0f, arrowHeight, -points[0].z);
1923 glVertex3f(-arrowHalfWidth, baseHeight, -points[0].z);
1924 glVertex3f( arrowHalfWidth, baseHeight, -points[0].z);
1932 glVertex3f(0.0f, 0.0f, 0.0f);
1933 glVertex3f( points[farIndex].x, points[farIndex].y, -points[farIndex].z);
1934 glVertex3f(0.0f, 0.0f, 0.0f);
1935 glVertex3f(-points[farIndex].x, points[farIndex].y, -points[farIndex].z);
1936 glVertex3f(0.0f, 0.0f, 0.0f);
1937 glVertex3f(-points[farIndex].x, -points[farIndex].y, -points[farIndex].z);
1938 glVertex3f(0.0f, 0.0f, 0.0f);
1939 glVertex3f( points[farIndex].x, -points[farIndex].y, -points[farIndex].z);
1946 glVertex3f( points[0].x, points[0].y, -points[0].z);
1947 glVertex3f( points[1].x, points[1].y, -points[1].z);
1948 glVertex3f(-points[0].x, points[0].y, -points[0].z);
1949 glVertex3f(-points[1].x, points[1].y, -points[1].z);
1950 glVertex3f(-points[0].x, -points[0].y, -points[0].z);
1951 glVertex3f(-points[1].x, -points[1].y, -points[1].z);
1952 glVertex3f( points[0].x, -points[0].y, -points[0].z);
1953 glVertex3f( points[1].x, -points[1].y, -points[1].z);
1992 const float posViewDir = pos * viewDir;
1994 static Vec normal[6];
1995 static GLdouble dist[6];
2002 const float chhfov = cos(hhfov);
2003 const float shhfov = sin(hhfov);
2004 normal[0] = - shhfov * viewDir;
2005 normal[1] = normal[0] + chhfov * right;
2006 normal[0] = normal[0] - chhfov * right;
2008 normal[2] = -viewDir;
2009 normal[3] = viewDir;
2012 const float chfov = cos(hfov);
2013 const float shfov = sin(hfov);
2014 normal[4] = - shfov * viewDir;
2015 normal[5] = normal[4] - chfov * up;
2016 normal[4] = normal[4] + chfov * up;
2018 for (
int i=0; i<2; ++i)
2019 dist[i] = pos * normal[i];
2020 for (
int j=4; j<6; ++j)
2021 dist[j] = pos * normal[j];
2029 const float posRightCosHH = chhfov * pos * right;
2030 dist[0] = -shhfov * posViewDir;
2031 dist[1] = dist[0] + posRightCosHH;
2032 dist[0] = dist[0] - posRightCosHH;
2033 const float posUpCosH = chfov * pos * up;
2034 dist[4] = - shfov * posViewDir;
2035 dist[5] = dist[4] - posUpCosH;
2036 dist[4] = dist[4] + posUpCosH;
2048 dist[0] = (pos - hw * right) * normal[0];
2049 dist[1] = (pos + hw * right) * normal[1];
2050 dist[4] = (pos + hh * up) * normal[4];
2051 dist[5] = (pos - hh * up) * normal[5];
2056 normal[2] = -viewDir;
2057 normal[3] = viewDir;
2058 dist[2] = -posViewDir -
zNear();
2059 dist[3] = posViewDir +
zFar();
2061 for (
int i=0; i<6; ++i)
2063 coef[i][0] = GLdouble(normal[i].x);
2064 coef[i][1] = GLdouble(normal[i].y);
2065 coef[i][2] = GLdouble(normal[i].z);
2066 coef[i][3] = dist[i];
void setScreenWidthAndHeight(int width, int height)
void startInterpolation(int period=-1)
A keyFrame Catmull-Rom Frame interpolator.
virtual QDomElement domElement(const QString &name, QDomDocument &document) const
float horizontalFieldOfView() const
The ManipulatedCameraFrame class represents a ManipulatedFrame with Camera specific mouse bindings...
virtual void drawAllPaths()
void resetInterpolation()
Vec inverseTransformOf(const Vec &src) const
float zClippingCoefficient() const
virtual void loadProjectionMatrixStereo(bool leftBuffer=true) const
void setFrame(Frame *const frame)
void convertClickToLine(const QPoint &pixel, Vec &orig, Vec &dir) const
Camera & operator=(const Camera &camera)
static float det(float m00, float m01, float m02, float m10, float m11, float m12, float m20, float m21, float m22)
void interpolateToFitScene()
void getProjectionMatrix(GLdouble m[16]) const
void setOrientation(const Quaternion &q)
bool setRevolveAroundPointFromPixel(const QPoint &pixel)
void addKeyFrame(const Frame &frame)
void lookAt(const Vec &target)
virtual void loadProjectionMatrix(bool reset=true) const
float focusDistance() const
void computeModelViewMatrix() const
float distanceToSceneCenter() const
void setSceneCenter(const Vec ¢er)
void setPhysicalScreenWidth(float width)
virtual void addKeyFrameToPath(int i)
Vec projectedCoordinatesOf(const Vec &src, const Frame *frame=NULL) const
void setSceneBoundingBox(const Vec &min, const Vec &max)
void setPositionWithConstraint(Vec &position)
GLdouble projectionMatrix_[16]
static void drawCamera(float scale=1.0, float aspectRatio=1.33, float fieldOfView=M_PI/4.0)
virtual void loadModelViewMatrix(bool reset=true) const
QMap< int, KeyFrameInterpolator * > kfi_
void setRevolveAroundPoint(const Vec &rap)
virtual void loadModelViewMatrixStereo(bool leftBuffer=true) const
virtual void deletePath(int i)
Vec rotate(const Vec &v) const
void setZClippingCoefficient(float coef)
void getViewport(GLint viewport[4]) const
void getModelViewMatrix(GLdouble m[16]) const
Vec pointUnderPixel(const QPoint &pixel, bool &found) const
void fitSphere(const Vec ¢er, float radius)
virtual void draw(bool drawFarPlane=true, float scale=1.0) 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])
void setReferenceFrame(const Frame *const refFrame)
void computeProjectionMatrix() const
ManipulatedCameraFrame * frame() const
void fitScreenRegion(const QRect &rectangle)
void rotate(Quaternion &q)
void setFocusDistance(float distance)
The Vec class represents 3D positions and 3D vectors.
void setViewDirection(const Vec &direction)
void setKeyFrameInterpolator(int i, KeyFrameInterpolator *const kfi)
float sceneRadius() const
virtual void getOrthoWidthHeight(GLdouble &halfWidth, GLdouble &halfHeight) const
ManipulatedCameraFrame * frame_
void setZNearCoefficient(float coef)
void getWorldCoordinatesOf(const float src[3], float res[3]) const
float physicalScreenWidth() const
void fitBoundingBox(const Vec &min, const Vec &max)
KeyFrameInterpolator * interpolationKfi_
void projectOnLine(const Vec &origin, const Vec &direction)
void setFromProjectionMatrix(const float matrix[12])
void getModelViewProjectionMatrix(GLdouble m[16]) const
Vec revolveAroundPoint() const
void interpolateToZoomOnPixel(const QPoint &pixel)
bool interpolationIsStarted() const
void setRevolveAroundPoint(const Vec &revolveAroundPoint)
float zNearCoefficient() const
KeyFrameInterpolator * keyFrameInterpolator(int i) const
double squaredNorm() const
Vec coordinatesOf(const Vec &src) const
Quaternion orientation() const
A perspective or orthographic camera.
void getProjectedCoordinatesOf(const float src[3], float res[3], const Frame *frame=NULL) const
void setFrame(ManipulatedCameraFrame *const mcf)
virtual void initFromDOMElement(const QDomElement &element)
virtual void playPath(int i)
The Quaternion class represents 3D rotations and orientations.
void setFromRotatedBasis(const Vec &X, const Vec &Y, const Vec &Z)
Quaternion orientation() const
void setOrientationWithConstraint(Quaternion &orientation)
void getUnprojectedCoordinatesOf(const float src[3], float res[3], const Frame *frame=NULL) const
void setPosition(const Vec &pos)
void setPosition(const Vec &position)
virtual float zNear() const
virtual void resetPath(int i)
void setSceneRadius(float radius)
virtual void initFromDOMElement(const QDomElement &element)
The Frame class represents a coordinate system, defined by a position and an orientation.
void setFromModelViewMatrix(const GLdouble *const modelViewMatrix)
static unsigned int ind(unsigned int i, unsigned int j)
static int intFromDom(const QDomElement &e, const QString &attribute, int defValue)
float fieldOfView() const
void setOrientation(const Quaternion &orientation)
Vec worldCoordinatesOf(const Vec &src) const
void setUpVector(const Vec &up, bool noMove=true)
GLdouble modelViewMatrix_[16]
void setIODistance(float distance)
virtual float zFar() const
void getCameraCoordinatesOf(const float src[3], float res[3]) const
Vec inverseCoordinatesOf(const Vec &src) const
Vec cameraCoordinatesOf(const Vec &src) const
void setFlySpeed(float speed)
Vec unprojectedCoordinatesOf(const Vec &src, const Frame *frame=NULL) const
float aspectRatio() const
Vec viewDirection() const
void interpolateTo(const Frame &fr, float duration)
static float floatFromDom(const QDomElement &e, const QString &attribute, float defValue)
void setFieldOfView(float fov)
float pixelGLRatio(const Vec &position) const