Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
8b414e7d
Commit
8b414e7d
authored
Sep 22, 2010
by
Lionel Heng
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Added some functionality to 3D View --Lionel
parent
5e22d5a8
Changes
4
Show whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
619 additions
and
409 deletions
+619
-409
Q3DWidget.cc
src/ui/map3D/Q3DWidget.cc
+255
-245
Q3DWidget.h
src/ui/map3D/Q3DWidget.h
+123
-120
QMap3DWidget.cc
src/ui/map3D/QMap3DWidget.cc
+218
-43
QMap3DWidget.h
src/ui/map3D/QMap3DWidget.h
+23
-1
No files found.
src/ui/map3D/Q3DWidget.cc
View file @
8b414e7d
...
@@ -28,6 +28,7 @@ Q3DWidget::Q3DWidget(QWidget* parent)
...
@@ -28,6 +28,7 @@ Q3DWidget::Q3DWidget(QWidget* parent)
,
_forceRedraw
(
false
)
,
_forceRedraw
(
false
)
,
allow2DRotation
(
true
)
,
allow2DRotation
(
true
)
,
limitCamera
(
false
)
,
limitCamera
(
false
)
,
lockCamera
(
false
)
,
timerFunc
(
NULL
)
,
timerFunc
(
NULL
)
,
timerFuncData
(
NULL
)
,
timerFuncData
(
NULL
)
{
{
...
@@ -104,6 +105,12 @@ Q3DWidget::setCameraLimit(bool onoff)
...
@@ -104,6 +105,12 @@ Q3DWidget::setCameraLimit(bool onoff)
limitCamera
=
onoff
;
limitCamera
=
onoff
;
}
}
void
Q3DWidget
::
setCameraLock
(
bool
onoff
)
{
lockCamera
=
onoff
;
}
void
void
Q3DWidget
::
set2DCameraParams
(
float
zoomSensitivity2D
,
Q3DWidget
::
set2DCameraParams
(
float
zoomSensitivity2D
,
float
rotateSensitivity2D
,
float
rotateSensitivity2D
,
...
@@ -269,11 +276,11 @@ Q3DWidget::getPositionIn3DMode(int32_t mouseX, int32_t mouseY)
...
@@ -269,11 +276,11 @@ Q3DWidget::getPositionIn3DMode(int32_t mouseX, int32_t mouseY)
float
py
=
-
(
mouseY
-
cy
)
*
d
/
(
cosf
(
tilt
)
*
f
+
sinf
(
tilt
)
*
mouseY
float
py
=
-
(
mouseY
-
cy
)
*
d
/
(
cosf
(
tilt
)
*
f
+
sinf
(
tilt
)
*
mouseY
-
sinf
(
tilt
)
*
cy
);
-
sinf
(
tilt
)
*
cy
);
std
::
pair
<
float
,
float
>
scene_c
oords
;
std
::
pair
<
float
,
float
>
sceneC
oords
;
scene_c
oords
.
first
=
px
*
cosf
(
pan
)
+
py
*
sinf
(
pan
)
+
cameraPose
.
xOffset
;
sceneC
oords
.
first
=
px
*
cosf
(
pan
)
+
py
*
sinf
(
pan
)
+
cameraPose
.
xOffset
;
scene_c
oords
.
second
=
-
px
*
sinf
(
pan
)
+
py
*
cosf
(
pan
)
+
cameraPose
.
yOffset
;
sceneC
oords
.
second
=
-
px
*
sinf
(
pan
)
+
py
*
cosf
(
pan
)
+
cameraPose
.
yOffset
;
return
scene_c
oords
;
return
sceneC
oords
;
}
}
std
::
pair
<
float
,
float
>
std
::
pair
<
float
,
float
>
...
@@ -331,6 +338,8 @@ Q3DWidget::getMouseY(void)
...
@@ -331,6 +338,8 @@ Q3DWidget::getMouseY(void)
void
void
Q3DWidget
::
rotateCamera
(
float
dx
,
float
dy
)
Q3DWidget
::
rotateCamera
(
float
dx
,
float
dy
)
{
{
if
(
!
lockCamera
)
{
cameraPose
.
pan
+=
dx
*
cameraParams
.
rotateSensitivity
;
cameraPose
.
pan
+=
dx
*
cameraParams
.
rotateSensitivity
;
cameraPose
.
tilt
+=
dy
*
cameraParams
.
rotateSensitivity
;
cameraPose
.
tilt
+=
dy
*
cameraParams
.
rotateSensitivity
;
if
(
limitCamera
)
if
(
limitCamera
)
...
@@ -344,6 +353,7 @@ Q3DWidget::rotateCamera(float dx, float dy)
...
@@ -344,6 +353,7 @@ Q3DWidget::rotateCamera(float dx, float dy)
cameraPose
.
tilt
=
269.5
f
;
cameraPose
.
tilt
=
269.5
f
;
}
}
}
}
}
}
}
void
void
...
...
src/ui/map3D/Q3DWidget.h
View file @
8b414e7d
...
@@ -63,10 +63,11 @@ public:
...
@@ -63,10 +63,11 @@ public:
void
setCameraParams
(
float
zoomSensitivity
,
float
rotateSensitivity
,
void
setCameraParams
(
float
zoomSensitivity
,
float
rotateSensitivity
,
float
moveSensitivity
,
float
minZoomRange
,
float
moveSensitivity
,
float
minZoomRange
,
float
camera_f
ov
,
float
minClipRange
,
float
cameraF
ov
,
float
minClipRange
,
float
maxClipRange
);
float
maxClipRange
);
void
setCameraLimit
(
bool
onoff
);
void
setCameraLimit
(
bool
onoff
);
void
setCameraLock
(
bool
onoff
);
void
set2DCameraParams
(
float
zoomSensitivity
,
void
set2DCameraParams
(
float
zoomSensitivity
,
float
rotateSensitivity
,
float
rotateSensitivity
,
...
@@ -116,7 +117,7 @@ public:
...
@@ -116,7 +117,7 @@ public:
private
Q_SLOTS
:
private
Q_SLOTS
:
void
userTimer
(
void
);
void
userTimer
(
void
);
pr
ivate
:
pr
otected
:
void
rotateCamera
(
float
dx
,
float
dy
);
void
rotateCamera
(
float
dx
,
float
dy
);
void
zoomCamera
(
float
dy
);
void
zoomCamera
(
float
dy
);
void
moveCamera
(
float
dx
,
float
dy
);
void
moveCamera
(
float
dx
,
float
dy
);
...
@@ -130,6 +131,7 @@ private:
...
@@ -130,6 +131,7 @@ private:
float
r2d
(
float
angle
);
float
r2d
(
float
angle
);
float
d2r
(
float
angle
);
float
d2r
(
float
angle
);
private:
// QGLWidget events
// QGLWidget events
void
initializeGL
(
void
);
void
initializeGL
(
void
);
void
paintGL
(
void
);
void
paintGL
(
void
);
...
@@ -164,6 +166,7 @@ private:
...
@@ -164,6 +166,7 @@ private:
bool
_forceRedraw
;
bool
_forceRedraw
;
bool
allow2DRotation
;
bool
allow2DRotation
;
bool
limitCamera
;
bool
limitCamera
;
bool
lockCamera
;
CameraParams
cameraParams
;
CameraParams
cameraParams
;
...
...
src/ui/map3D/QMap3DWidget.cc
View file @
8b414e7d
#include "QMap3DWidget.h"
#include "QMap3DWidget.h"
#include <FTGL/ftgl.h>
#include <FTGL/ftgl.h>
#include <Q
PushButton
>
#include <Q
CheckBox
>
#include <sys/time.h>
#include <sys/time.h>
#include "CheetahModel.h"
#include "CheetahModel.h"
...
@@ -12,30 +12,19 @@ QMap3DWidget::QMap3DWidget(QWidget* parent)
...
@@ -12,30 +12,19 @@ QMap3DWidget::QMap3DWidget(QWidget* parent)
:
Q3DWidget
(
parent
)
:
Q3DWidget
(
parent
)
,
uas
(
NULL
)
,
uas
(
NULL
)
,
lastRedrawTime
(
0.0
)
,
lastRedrawTime
(
0.0
)
,
displayGrid
(
false
)
,
displayTrail
(
false
)
,
lockCamera
(
false
)
{
{
setFocusPolicy
(
Qt
::
StrongFocus
);
setFocusPolicy
(
Qt
::
StrongFocus
);
initialize
(
10
,
10
,
1000
,
900
,
10.0
f
);
initialize
(
10
,
10
,
1000
,
900
,
10.0
f
);
setCameraParams
(
0.05
f
,
0.5
f
,
0.0
0
1
f
,
0.5
f
,
30.0
f
,
0.01
f
,
400.0
f
);
setCameraParams
(
0.05
f
,
0.5
f
,
0.01
f
,
0.5
f
,
30.0
f
,
0.01
f
,
400.0
f
);
setDisplayFunc
(
display
,
this
);
setDisplayFunc
(
display
,
this
);
addTimerFunc
(
100
,
timer
,
this
);
addTimerFunc
(
100
,
timer
,
this
);
QPushButton
*
mapButton
=
new
QPushButton
(
this
);
buildLayout
();
mapButton
->
setText
(
"Grid"
);
// display the MapControl in the application
QGridLayout
*
layout
=
new
QGridLayout
(
this
);
layout
->
setMargin
(
0
);
layout
->
setSpacing
(
2
);
//layout->addWidget(mc, 0, 0, 1, 2);
layout
->
addWidget
(
mapButton
,
1
,
0
);
layout
->
addItem
(
new
QSpacerItem
(
0
,
0
,
QSizePolicy
::
Expanding
,
QSizePolicy
::
Expanding
),
1
,
1
);
layout
->
setRowStretch
(
0
,
100
);
layout
->
setRowStretch
(
1
,
1
);
layout
->
setColumnStretch
(
0
,
1
);
layout
->
setColumnStretch
(
1
,
50
);
setLayout
(
layout
);
font
.
reset
(
new
FTTextureFont
(
"images/Vera.ttf"
));
font
.
reset
(
new
FTTextureFont
(
"images/Vera.ttf"
));
...
@@ -49,9 +38,44 @@ QMap3DWidget::~QMap3DWidget()
...
@@ -49,9 +38,44 @@ QMap3DWidget::~QMap3DWidget()
}
}
void
void
QMap3DWidget
::
ini
t
(
void
)
QMap3DWidget
::
buildLayou
t
(
void
)
{
{
QCheckBox
*
gridCheckBox
=
new
QCheckBox
(
this
);
gridCheckBox
->
setText
(
"Grid"
);
gridCheckBox
->
setChecked
(
displayGrid
);
QCheckBox
*
trailCheckBox
=
new
QCheckBox
(
this
);
trailCheckBox
->
setText
(
"Trail"
);
trailCheckBox
->
setChecked
(
displayTrail
);
QPushButton
*
recenterButton
=
new
QPushButton
(
this
);
recenterButton
->
setText
(
"Recenter Camera"
);
QCheckBox
*
lockCameraCheckBox
=
new
QCheckBox
(
this
);
lockCameraCheckBox
->
setText
(
"Lock Camera"
);
lockCameraCheckBox
->
setChecked
(
lockCamera
);
QGridLayout
*
layout
=
new
QGridLayout
(
this
);
layout
->
setMargin
(
0
);
layout
->
setSpacing
(
2
);
//layout->addWidget(mc, 0, 0, 1, 2);
layout
->
addWidget
(
gridCheckBox
,
1
,
0
);
layout
->
addWidget
(
trailCheckBox
,
1
,
1
);
layout
->
addWidget
(
recenterButton
,
1
,
2
);
layout
->
addWidget
(
lockCameraCheckBox
,
1
,
3
);
layout
->
setRowStretch
(
0
,
100
);
layout
->
setRowStretch
(
1
,
1
);
layout
->
setColumnStretch
(
0
,
1
);
layout
->
setColumnStretch
(
1
,
50
);
setLayout
(
layout
);
connect
(
gridCheckBox
,
SIGNAL
(
stateChanged
(
int
)),
this
,
SLOT
(
showGrid
(
int
)));
connect
(
trailCheckBox
,
SIGNAL
(
stateChanged
(
int
)),
this
,
SLOT
(
showTrail
(
int
)));
connect
(
recenterButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
recenterCamera
()));
connect
(
lockCameraCheckBox
,
SIGNAL
(
stateChanged
(
int
)),
this
,
SLOT
(
toggleLockCamera
(
int
)));
}
}
void
void
...
@@ -70,11 +94,20 @@ QMap3DWidget::displayHandler(void)
...
@@ -70,11 +94,20 @@ QMap3DWidget::displayHandler(void)
cheetahModel
->
init
(
1.0
f
,
1.0
f
,
1.0
f
);
cheetahModel
->
init
(
1.0
f
,
1.0
f
,
1.0
f
);
}
}
if
(
uas
==
NULL
)
float
robotX
=
0.0
f
,
robotY
=
0.0
f
,
robotZ
=
0.0
f
;
float
robotRoll
=
0.0
f
,
robotPitch
=
0.0
f
,
robotYaw
=
0.0
f
;
if
(
uas
!=
NULL
)
{
{
return
;
robotX
=
uas
->
getLocalX
();
robotY
=
uas
->
getLocalY
();
robotZ
=
uas
->
getLocalZ
();
robotRoll
=
uas
->
getRoll
();
robotPitch
=
uas
->
getPitch
();
robotYaw
=
uas
->
getYaw
();
}
}
setCameraLock
(
lockCamera
);
// turn on smooth lines
// turn on smooth lines
glEnable
(
GL_LINE_SMOOTH
);
glEnable
(
GL_LINE_SMOOTH
);
glHint
(
GL_LINE_SMOOTH_HINT
,
GL_NICEST
);
glHint
(
GL_LINE_SMOOTH_HINT
,
GL_NICEST
);
...
@@ -86,48 +119,44 @@ QMap3DWidget::displayHandler(void)
...
@@ -86,48 +119,44 @@ QMap3DWidget::displayHandler(void)
glClear
(
GL_COLOR_BUFFER_BIT
);
glClear
(
GL_COLOR_BUFFER_BIT
);
// draw Cheetah model
// draw Cheetah model
glPushMatrix
();
drawPlatform
(
robotRoll
,
robotPitch
,
robotYaw
);
glRotatef
(
uas
->
getYaw
(),
0.0
f
,
0.0
f
,
1.0
f
);
glRotatef
(
uas
->
getPitch
(),
0.0
f
,
1.0
f
,
0.0
f
);
glRotatef
(
uas
->
getRoll
(),
1.0
f
,
0.0
f
,
0.0
f
);
glLineWidth
(
3.0
f
);
if
(
displayGrid
)
glColor3f
(
0.0
f
,
1.0
f
,
0.0
f
);
{
glBegin
(
GL_LINES
);
drawGrid
();
glVertex3f
(
0.0
f
,
0.0
f
,
0.0
f
);
}
glVertex3f
(
0.3
f
,
0.0
f
,
0.0
f
);
glEnd
();
cheetahModel
->
draw
();
glPopMatrix
();
if
(
displayTrail
)
{
drawTrail
(
robotX
,
robotY
,
robotZ
);
}
// switch to 2D
setDisplayMode2D
();
setDisplayMode2D
();
// display pose information
// display pose information
glColor4f
(
0.0
f
,
0.0
f
,
0.0
f
,
0.5
f
);
glColor4f
(
0.0
f
,
0.0
f
,
0.0
f
,
0.5
f
);
glBegin
(
GL_POLYGON
);
glBegin
(
GL_POLYGON
);
glVertex2f
(
0.0
f
,
0.0
f
);
glVertex2f
(
0.0
f
,
0.0
f
);
glVertex2f
(
0.0
f
,
20
.0
f
);
glVertex2f
(
0.0
f
,
45
.0
f
);
glVertex2f
(
getWindowWidth
(),
20
.0
f
);
glVertex2f
(
getWindowWidth
(),
45
.0
f
);
glVertex2f
(
getWindowWidth
(),
0.0
f
);
glVertex2f
(
getWindowWidth
(),
0.0
f
);
glEnd
();
glEnd
();
char
buffer
[
6
][
255
];
char
buffer
[
6
][
255
];
sprintf
(
buffer
[
0
],
"x = %.2f"
,
uas
->
getLocalX
()
);
sprintf
(
buffer
[
0
],
"x = %.2f"
,
robotX
);
sprintf
(
buffer
[
1
],
"y = %.2f"
,
uas
->
getLocalY
()
);
sprintf
(
buffer
[
1
],
"y = %.2f"
,
robotY
);
sprintf
(
buffer
[
2
],
"z = %.2f"
,
uas
->
getLocalZ
()
);
sprintf
(
buffer
[
2
],
"z = %.2f"
,
robotZ
);
sprintf
(
buffer
[
3
],
"r = %.2f"
,
uas
->
getRoll
()
);
sprintf
(
buffer
[
3
],
"r = %.2f"
,
robotRoll
);
sprintf
(
buffer
[
4
],
"p = %.2f"
,
uas
->
getPitch
()
);
sprintf
(
buffer
[
4
],
"p = %.2f"
,
robotPitch
);
sprintf
(
buffer
[
5
],
"y = %.2f"
,
uas
->
getYaw
()
);
sprintf
(
buffer
[
5
],
"y = %.2f"
,
robotYaw
);
font
->
FaceSize
(
10
);
font
->
FaceSize
(
10
);
glColor3f
(
1.0
f
,
1.0
f
,
1.0
f
);
glColor3f
(
1.0
f
,
1.0
f
,
1.0
f
);
glPushMatrix
();
glPushMatrix
();
glTranslatef
(
0.0
f
,
5
.0
f
,
0.0
f
);
glTranslatef
(
0.0
f
,
30
.0
f
,
0.0
f
);
for
(
int32_t
i
=
0
;
i
<
6
;
++
i
)
for
(
int32_t
i
=
0
;
i
<
6
;
++
i
)
{
{
glTranslatef
(
60.0
f
,
0.0
f
,
0.0
f
);
glTranslatef
(
60.0
f
,
0.0
f
,
0.0
f
);
...
@@ -180,3 +209,149 @@ QMap3DWidget::getTime(void) const
...
@@ -180,3 +209,149 @@ QMap3DWidget::getTime(void) const
return
static_cast
<
double
>
(
tv
.
tv_sec
)
+
return
static_cast
<
double
>
(
tv
.
tv_sec
)
+
static_cast
<
double
>
(
tv
.
tv_usec
)
/
1000000.0
;
static_cast
<
double
>
(
tv
.
tv_usec
)
/
1000000.0
;
}
}
void
QMap3DWidget
::
showGrid
(
int32_t
state
)
{
if
(
state
==
Qt
::
Checked
)
{
displayGrid
=
true
;
}
else
{
displayGrid
=
false
;
}
}
void
QMap3DWidget
::
showTrail
(
int32_t
state
)
{
if
(
state
==
Qt
::
Checked
)
{
if
(
!
displayTrail
)
{
trail
.
clear
();
}
displayTrail
=
true
;
}
else
{
displayTrail
=
false
;
}
}
void
QMap3DWidget
::
recenterCamera
(
void
)
{
recenter
();
}
void
QMap3DWidget
::
toggleLockCamera
(
int32_t
state
)
{
if
(
state
==
Qt
::
Checked
)
{
lockCamera
=
true
;
}
else
{
lockCamera
=
false
;
}
}
void
QMap3DWidget
::
drawPlatform
(
float
roll
,
float
pitch
,
float
yaw
)
{
glPushMatrix
();
glRotatef
(
yaw
,
0.0
f
,
0.0
f
,
1.0
f
);
glRotatef
(
pitch
,
0.0
f
,
1.0
f
,
0.0
f
);
glRotatef
(
roll
,
1.0
f
,
0.0
f
,
0.0
f
);
glLineWidth
(
3.0
f
);
glColor3f
(
0.0
f
,
1.0
f
,
0.0
f
);
glBegin
(
GL_LINES
);
glVertex3f
(
0.0
f
,
0.0
f
,
0.0
f
);
glVertex3f
(
0.3
f
,
0.0
f
,
0.0
f
);
glEnd
();
cheetahModel
->
draw
();
glPopMatrix
();
}
void
QMap3DWidget
::
drawGrid
(
void
)
{
float
radius
=
10.0
f
;
float
resolution
=
0.25
f
;
glPushMatrix
();
// draw a 20m x 20m grid with 0.25m resolution
glColor3f
(
0.5
f
,
0.5
f
,
0.5
f
);
for
(
float
i
=
-
radius
;
i
<=
radius
;
i
+=
resolution
)
{
if
(
fabsf
(
i
-
roundf
(
i
))
<
0.01
f
)
{
glLineWidth
(
2.0
f
);
}
else
{
glLineWidth
(
0.25
f
);
}
glBegin
(
GL_LINES
);
glVertex3f
(
i
,
-
radius
,
0.0
f
);
glVertex3f
(
i
,
radius
,
0.0
f
);
glVertex3f
(
-
radius
,
i
,
0.0
f
);
glVertex3f
(
radius
,
i
,
0.0
f
);
glEnd
();
}
glPopMatrix
();
}
void
QMap3DWidget
::
drawTrail
(
float
x
,
float
y
,
float
z
)
{
bool
addToTrail
=
false
;
if
(
trail
.
size
()
>
0
)
{
if
(
fabsf
(
x
-
trail
[
trail
.
size
()
-
1
].
x
)
>
0.01
f
||
fabsf
(
y
-
trail
[
trail
.
size
()
-
1
].
y
)
>
0.01
f
||
fabsf
(
z
-
trail
[
trail
.
size
()
-
1
].
z
)
>
0.01
f
)
{
addToTrail
=
true
;
}
}
else
{
addToTrail
=
true
;
}
if
(
addToTrail
)
{
Pose3D
p
=
{
x
,
y
,
z
};
if
(
trail
.
size
()
==
trail
.
capacity
())
{
memcpy
(
trail
.
data
(),
trail
.
data
()
+
1
,
(
trail
.
size
()
-
1
)
*
sizeof
(
Pose3D
));
trail
[
trail
.
size
()
-
1
]
=
p
;
}
else
{
trail
.
append
(
p
);
}
}
glColor3f
(
1.0
f
,
0.0
f
,
0.0
f
);
glLineWidth
(
1.0
f
);
glBegin
(
GL_LINE_STRIP
);
for
(
int32_t
i
=
0
;
i
<
trail
.
size
();
++
i
)
{
glVertex3f
(
trail
[
i
].
x
-
x
,
trail
[
i
].
y
-
y
,
trail
[
i
].
z
-
z
);
}
glEnd
();
}
src/ui/map3D/QMap3DWidget.h
View file @
8b414e7d
...
@@ -15,7 +15,7 @@ public:
...
@@ -15,7 +15,7 @@ public:
explicit
QMap3DWidget
(
QWidget
*
parent
);
explicit
QMap3DWidget
(
QWidget
*
parent
);
~
QMap3DWidget
();
~
QMap3DWidget
();
void
ini
t
(
void
);
void
buildLayou
t
(
void
);
static
void
display
(
void
*
clientData
);
static
void
display
(
void
*
clientData
);
void
displayHandler
(
void
);
void
displayHandler
(
void
);
...
@@ -28,12 +28,34 @@ public:
...
@@ -28,12 +28,34 @@ public:
public
slots
:
public
slots
:
void
setActiveUAS
(
UASInterface
*
uas
);
void
setActiveUAS
(
UASInterface
*
uas
);
private
slots
:
void
showGrid
(
int
state
);
void
showTrail
(
int
state
);
void
recenterCamera
(
void
);
void
toggleLockCamera
(
int
state
);
protected:
protected:
UASInterface
*
uas
;
UASInterface
*
uas
;
private:
private:
void
drawPlatform
(
float
roll
,
float
pitch
,
float
yaw
);
void
drawGrid
(
void
);
void
drawTrail
(
float
x
,
float
y
,
float
z
);
double
lastRedrawTime
;
double
lastRedrawTime
;
bool
displayGrid
;
bool
displayTrail
;
bool
lockCamera
;
typedef
struct
{
float
x
;
float
y
;
float
z
;
}
Pose3D
;
QVarLengthArray
<
Pose3D
,
10000
>
trail
;
QScopedPointer
<
CheetahModel
>
cheetahModel
;
QScopedPointer
<
CheetahModel
>
cheetahModel
;
QScopedPointer
<
FTTextureFont
>
font
;
QScopedPointer
<
FTTextureFont
>
font
;
};
};
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment