13 #include <Eigen/Geometry> 19 #include <QMouseEvent> 20 #include <QInputDialog> 21 #include <QGridLayout> 22 #include <QButtonGroup> 23 #include <QRadioButton> 24 #include <QDockWidget> 25 #include <QPushButton> 28 using namespace Eigen;
38 const float scale = 0.33;
40 std::vector<int> parents;
43 mCenters.push_back(Vector3f::Zero());
44 parents.push_back(-1);
45 mRadii.push_back(radius);
50 float dist = mRadii[0]*0.9;
51 for (
int i=0;
i<12; ++
i)
53 mCenters.push_back(mIcoSphere.vertices()[
i] * dist);
54 mRadii.push_back(radius);
59 static const float angles [10] = {
69 for (
int l=1;
l<levels;
l++)
72 int end = mCenters.size();
73 for (
int i=start;
i<
end; ++
i)
75 Vector3f
c = mCenters[
i];
76 Vector3f ax0 = (c - mCenters[parents[
i]]).normalized();
77 Vector3f ax1 = ax0.unitOrthogonal();
81 for (
int j=0;
j<5; ++
j)
83 Vector3f newC = c + ( (
AngleAxisf(angles[
j*2+1], ax0)
84 *
AngleAxisf(angles[
j*2+0] * (
l==1 ? 0.35 : 0.5), ax1)) * ax0)
85 * (mRadii[
i] + radius*0.8);
86 mCenters.push_back(newC);
87 mRadii.push_back(radius);
97 int end = mCenters.size();
98 glEnable(GL_NORMALIZE);
107 glDisable(GL_NORMALIZE);
119 return a*(1-
t) + b*t;
124 {
return a.
slerp(t,b); }
128 template<
typename OrientationType>
154 const Vector3&
coeffs()
const {
return m_angles; }
176 Vector3
c = m_angles.array().cos();
177 Vector3
s = m_angles.array().sin();
179 res << c.y()*c.z(), -c.y()*s.z(), s.y(),
180 c.z()*s.x()*s.y()+c.x()*s.z(), c.x()*c.z()-s.x()*s.y()*s.z(), -c.y()*s.x(),
181 -c.x()*c.z()*s.y()+s.x()*s.z(), c.z()*s.x()+c.x()*s.y()*s.z(), c.x()*c.y();
192 res.coeffs() =
lerp(t, a.coeffs(), b.coeffs());
200 mCurrentTrackingMode = TM_NO_TRACK;
201 mNavMode = NavTurnAround;
202 mLerpMode = LerpQuaternion;
203 mRotationMode = RotationStable;
204 mTrackball.setCamera(&mCamera);
207 setFocusPolicy(Qt::ClickFocus);
215 if (!m_timeline.empty())
216 t = (--m_timeline.end())->first + 1.;
217 t = QInputDialog::getDouble(
this,
"Eigen's RenderingWidget",
"time value: ",
223 aux.
position = mCamera.viewMatrix().translation();
238 glLightfv(GL_LIGHT0, GL_AMBIENT, Vector4f(0.5,0.5,0.5,1).
data());
239 glLightfv(GL_LIGHT0, GL_DIFFUSE, Vector4f(0.5,1,0.5,1).
data());
240 glLightfv(GL_LIGHT0, GL_SPECULAR, Vector4f(1,1,1,1).
data());
241 glLightfv(GL_LIGHT0, GL_POSITION, Vector4f(-sqrt3,-sqrt3,sqrt3,0).
data());
243 glLightfv(GL_LIGHT1, GL_AMBIENT, Vector4f(0,0,0,1).
data());
244 glLightfv(GL_LIGHT1, GL_DIFFUSE, Vector4f(1,0.5,0.5,1).
data());
245 glLightfv(GL_LIGHT1, GL_SPECULAR, Vector4f(1,1,1,1).
data());
246 glLightfv(GL_LIGHT1, GL_POSITION, Vector4f(-sqrt3,sqrt3,-sqrt3,0).
data());
248 glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT, Vector4f(0.7, 0.7, 0.7, 1).
data());
249 glMaterialfv(GL_FRONT_AND_BACK, GL_DIFFUSE, Vector4f(0.8, 0.75, 0.6, 1).
data());
250 glMaterialfv(GL_FRONT_AND_BACK, GL_SPECULAR, Vector4f(1, 1, 1, 1).
data());
251 glMaterialf(GL_FRONT_AND_BACK, GL_SHININESS, 64);
253 glEnable(GL_LIGHTING);
257 sFancySpheres.
draw();
258 glVertexPointer(3, GL_FLOAT, 0, mVertices[0].
data());
259 glNormalPointer(GL_FLOAT, 0, mNormals[0].
data());
260 glEnableClientState(GL_VERTEX_ARRAY);
261 glEnableClientState(GL_NORMAL_ARRAY);
262 glDrawArrays(GL_TRIANGLES, 0, mVertices.size());
263 glDisableClientState(GL_VERTEX_ARRAY);
264 glDisableClientState(GL_NORMAL_ARRAY);
266 glDisable(GL_LIGHTING);
271 m_alpha += double(m_timer.interval()) * 1
e-3;
273 TimeLine::const_iterator hi = m_timeline.upper_bound(m_alpha);
274 TimeLine::const_iterator lo = hi;
279 if(hi==m_timeline.end())
282 currentFrame = lo->second;
285 else if(hi==m_timeline.begin())
288 currentFrame = hi->second;
292 float s = (m_alpha - lo->first)/(hi->first - lo->first);
293 if (mLerpMode==LerpEulerAngles)
294 currentFrame = ::lerpFrame<EulerAngles<float> >(
s, lo->second, hi->second);
295 else if (mLerpMode==LerpQuaternion)
296 currentFrame = ::lerpFrame<Eigen::Quaternionf>(
s, lo->second, hi->second);
299 std::cerr <<
"Invalid rotation interpolation mode (abort)\n";
307 mCamera.setFrame(currentFrame);
343 connect(&m_timer, SIGNAL(timeout()),
this, SLOT(animate()));
344 m_timer.start(1000/30);
357 disconnect(&m_timer, SIGNAL(timeout()),
this, SLOT(animate()));
365 mMouseCoords = Vector2i(e->pos().x(), e->pos().y());
366 bool fly = (mNavMode==NavFly) || (e->modifiers()&Qt::ControlModifier);
372 mCurrentTrackingMode = TM_LOCAL_ROTATE;
377 mCurrentTrackingMode = TM_ROTATE_AROUND;
380 mTrackball.track(mMouseCoords);
384 mCurrentTrackingMode = TM_FLY_Z;
386 mCurrentTrackingMode = TM_ZOOM;
388 case Qt::RightButton:
389 mCurrentTrackingMode = TM_FLY_PAN;
397 mCurrentTrackingMode = TM_NO_TRACK;
404 if(mCurrentTrackingMode != TM_NO_TRACK)
406 float dx =
float(e->x() - mMouseCoords.x()) /
float(mCamera.vpWidth());
407 float dy = -
float(e->y() - mMouseCoords.y()) /
float(mCamera.vpHeight());
410 if(e->modifiers() & Qt::ShiftModifier)
416 switch(mCurrentTrackingMode)
418 case TM_ROTATE_AROUND:
419 case TM_LOCAL_ROTATE:
420 if (mRotationMode==RotationStable)
424 mTrackball.track(Vector2i(e->pos().x(), e->pos().y()));
432 if (mCurrentTrackingMode==TM_LOCAL_ROTATE)
433 mCamera.localRotate(q);
435 mCamera.rotateAroundTarget(q);
439 mCamera.zoom(dy*100);
442 mCamera.localTranslate(Vector3f(0, 0, -dy*200));
445 mCamera.localTranslate(Vector3f(dx*200, dy*200, 0));
454 mMouseCoords = Vector2i(e->pos().x(), e->pos().y());
459 glEnable(GL_DEPTH_TEST);
460 glDisable(GL_CULL_FACE);
461 glPolygonMode(GL_FRONT_AND_BACK,GL_FILL);
462 glDisable(GL_COLOR_MATERIAL);
464 glDisable(GL_ALPHA_TEST);
465 glDisable(GL_TEXTURE_1D);
466 glDisable(GL_TEXTURE_2D);
467 glDisable(GL_TEXTURE_3D);
470 glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
472 mCamera.activateGL();
479 glClearColor(1., 1., 1., 0.);
480 glLightModeli(GL_LIGHT_MODEL_LOCAL_VIEWER, 1);
481 glDepthMask(GL_TRUE);
482 glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE);
484 mCamera.setPosition(Vector3f(-200, -200, -200));
485 mCamera.setTarget(Vector3f(0, 0, 0));
486 mInitFrame.orientation = mCamera.orientation().inverse();
487 mInitFrame.position = mCamera.viewMatrix().translation();
492 mCamera.setViewport(width,height);
515 Frame aux0 = mCamera.frame();
517 aux0.
position = mCamera.viewMatrix().translation();
518 m_timeline[0] = aux0;
520 Vector3f currentTarget = mCamera.target();
521 mCamera.setTarget(Vector3f::Zero());
524 Frame aux1 = mCamera.frame();
526 aux1.
position = mCamera.viewMatrix().translation();
528 if (duration<0.1) duration = 0.1;
531 aux1 = aux0.
lerp(duration/2,mInitFrame);
535 mCamera.setFrame(aux1);
536 mCamera.setTarget(Vector3f::Zero());
540 aux1.
position = mCamera.viewMatrix().translation();
541 m_timeline[duration] = aux1;
543 m_timeline[2] = mInitFrame;
546 connect(&m_timer, SIGNAL(timeout()),
this, SLOT(animate()));
547 m_timer.start(1000/30);
553 QWidget* panel =
new QWidget();
554 QVBoxLayout* layout =
new QVBoxLayout();
557 QPushButton* but =
new QPushButton(
"reset");
558 but->setToolTip(
"move the camera to initial position (with animation)");
559 layout->addWidget(but);
560 connect(but, SIGNAL(clicked()),
this, SLOT(resetCamera()));
564 QGroupBox* box =
new QGroupBox(
"navigation mode");
565 QVBoxLayout* boxLayout =
new QVBoxLayout;
566 QButtonGroup* group =
new QButtonGroup(panel);
568 but =
new QRadioButton(
"turn around");
569 but->setToolTip(
"look around an object");
570 group->addButton(but, NavTurnAround);
571 boxLayout->addWidget(but);
572 but =
new QRadioButton(
"fly");
573 but->setToolTip(
"free navigation like a spaceship\n(this mode can also be enabled pressing the \"shift\" key)");
574 group->addButton(but, NavFly);
575 boxLayout->addWidget(but);
576 group->button(mNavMode)->setChecked(
true);
577 connect(group, SIGNAL(buttonClicked(
int)),
this, SLOT(setNavMode(
int)));
578 box->setLayout(boxLayout);
579 layout->addWidget(box);
583 QGroupBox* box =
new QGroupBox(
"rotation mode");
584 QVBoxLayout* boxLayout =
new QVBoxLayout;
585 QButtonGroup* group =
new QButtonGroup(panel);
587 but =
new QRadioButton(
"stable trackball");
588 group->addButton(but, RotationStable);
589 boxLayout->addWidget(but);
590 but->setToolTip(
"use the stable trackball implementation mapping\nthe 2D coordinates to 3D points on a sphere");
591 but =
new QRadioButton(
"standard rotation");
592 group->addButton(but, RotationStandard);
593 boxLayout->addWidget(but);
594 but->setToolTip(
"standard approach mapping the x and y displacements\nas rotations around the camera's X and Y axes");
595 group->button(mRotationMode)->setChecked(
true);
596 connect(group, SIGNAL(buttonClicked(
int)),
this, SLOT(setRotationMode(
int)));
597 box->setLayout(boxLayout);
598 layout->addWidget(box);
602 QGroupBox* box =
new QGroupBox(
"spherical interpolation");
603 QVBoxLayout* boxLayout =
new QVBoxLayout;
604 QButtonGroup* group =
new QButtonGroup(panel);
606 but =
new QRadioButton(
"quaternion slerp");
607 group->addButton(but, LerpQuaternion);
608 boxLayout->addWidget(but);
609 but->setToolTip(
"use quaternion spherical interpolation\nto interpolate orientations");
610 but =
new QRadioButton(
"euler angles");
611 group->addButton(but, LerpEulerAngles);
612 boxLayout->addWidget(but);
613 but->setToolTip(
"use Euler angles to interpolate orientations");
614 group->button(mNavMode)->setChecked(
true);
615 connect(group, SIGNAL(buttonClicked(
int)),
this, SLOT(setLerpMode(
int)));
616 box->setLayout(boxLayout);
617 layout->addWidget(box);
619 layout->addItem(
new QSpacerItem(0,0,QSizePolicy::Minimum,QSizePolicy::Expanding));
620 panel->setLayout(layout);
627 setCentralWidget(mRenderingWidget);
629 QDockWidget* panel =
new QDockWidget(
"navigation",
this);
630 panel->setAllowedAreas((QFlags<Qt::DockWidgetArea>)(Qt::RightDockWidgetArea | Qt::LeftDockWidgetArea));
631 addDockWidget(Qt::RightDockWidgetArea, panel);
632 panel->setWidget(mRenderingWidget->createNavigationControlWidget());
635 int main(
int argc,
char *argv[])
637 std::cout <<
"Navigation:\n";
638 std::cout <<
" left button: rotate around the target\n";
639 std::cout <<
" middle button: zoom\n";
640 std::cout <<
" left button + ctrl quake rotate (rotate around camera position)\n";
641 std::cout <<
" middle button + ctrl walk (progress along camera's z direction)\n";
642 std::cout <<
" left button: pan (translate in the XY camera's plane)\n\n";
643 std::cout <<
"R : move the camera to initial position\n";
644 std::cout <<
"A : start/stop animation\n";
645 std::cout <<
"C : clear the animation\n";
646 std::cout <<
"G : add a key frame\n";
648 QApplication app(argc, argv);
650 demo.resize(600,500);
655 #include "quaternion_demo.moc"
EIGEN_DEVICE_FUNC Coefficients & coeffs()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW FancySpheres()
T lerp(float t, const T &a, const T &b)
Frame lerp(float alpha, const Frame &other) const
Matrix< Scalar, 3, 3 > Matrix3
Namespace containing all symbols from the Eigen library.
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
void popMatrix(GLenum matrixTarget)
void pushMatrix(const Matrix< Scalar, 4, 4, _Flags, 4, 4 > &mat, GLenum matrixTarget)
void drawVector(const Vector3f &position, const Vector3f &vec, const Color &color, float aspect=50.)
Translation< float, 3 > Translation3f
Quaternion< Scalar > QuaternionType
EulerAngles & operator=(const QuaternionType &q)
UniformScaling< float > Scaling(float s)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
EIGEN_DEVICE_FUNC Derived & setFromTwoVectors(const MatrixBase< Derived1 > &a, const MatrixBase< Derived2 > &b)
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
static const Line3 l(Rot3(), 1, 1)
EulerAngles(const QuaternionType &q)
static EIGEN_DEVICE_FUNC Matrix< Scalar, 2, 2 > toRotationMatrix(const Scalar &s)
Eigen::Quaternionf orientation
std::vector< float > mRadii
AngleAxis< float > AngleAxisf
EIGEN_DEVICE_FUNC Quaternion< Scalar > inverse() const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Represents a rotation in a 3 dimensional space as three Euler angles.
EIGEN_DEVICE_FUNC const Scalar & q
static Frame lerpFrame(float alpha, const Frame &a, const Frame &b)
AnnoyingScalar atan2(const AnnoyingScalar &y, const AnnoyingScalar &x)
int main(int argc, char *argv[])
The quaternion class used to represent 3D orientations and rotations.
static EIGEN_DEPRECATED const end_t end
EulerAngles & operator=(const Matrix3 &m)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics scale
EIGEN_DEVICE_FUNC Scalar angularDistance(const QuaternionBase< OtherDerived > &other) const
Matrix3 toRotationMatrix(void) const
Jet< T, N > sqrt(const Jet< T, N > &f)
std::vector< Vector3f > mCenters
EIGEN_DEVICE_FUNC Matrix3 toRotationMatrix() const
EulerAngles(Scalar a0, Scalar a1, Scalar a2)
The matrix class, also used for vectors and row-vectors.
const Vector3 & coeffs() const
void multMatrix(const Matrix< Scalar, 4, 4, _Flags, 4, 4 > &mat, GLenum matrixTarget)
EIGEN_DEVICE_FUNC const AsinReturnType asin() const
Matrix< Scalar, 3, 1 > Vector3
EIGEN_DEVICE_FUNC Quaternion< Scalar > slerp(const Scalar &t, const QuaternionBase< OtherDerived > &other) const