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
9ae72f8b
Commit
9ae72f8b
authored
Sep 17, 2011
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Made HSI a little more robust in interaction
parent
15954fd5
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
16 additions
and
15 deletions
+16
-15
HSIDisplay.cc
src/ui/HSIDisplay.cc
+14
-15
HSIDisplay.h
src/ui/HSIDisplay.h
+2
-0
No files found.
src/ui/HSIDisplay.cc
View file @
9ae72f8b
...
...
@@ -85,7 +85,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
bodyYawSet
(
0.0
f
),
uiXSetCoordinate
(
0.0
f
),
uiYSetCoordinate
(
0.0
f
),
uiZSetCoordinate
(
-
0.
65
f
),
uiZSetCoordinate
(
-
0.
51
f
),
uiYawSet
(
0.0
f
),
metricWidth
(
4.0
),
positionLock
(
false
),
...
...
@@ -130,7 +130,9 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
setStatusTip
(
tr
(
"View from top in body frame. Scroll with mouse wheel to change the horizontal field of view of the widget."
));
connect
(
&
statusClearTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
clearStatusMessage
()));
statusClearTimer
.
start
(
5000
);
statusClearTimer
.
start
(
3000
);
setFocusPolicy
(
Qt
::
StrongFocus
);
}
void
HSIDisplay
::
resetMAVState
()
...
...
@@ -278,7 +280,11 @@ void HSIDisplay::renderOverlay()
float
setPointDist
=
sqrt
(
xSpDiff
*
xSpDiff
+
ySpDiff
*
ySpDiff
+
zSpDiff
*
zSpDiff
);
if
(
userSetPointSet
&&
setPointDist
>
0.05
f
||
dragStarted
)
float
angleDiff
=
uiYawSet
-
bodyYawSet
;
float
normAngleDiff
=
fabs
(
atan2
(
sin
(
angleDiff
),
cos
(
angleDiff
)));
if
(
userSetPointSet
&&
setPointDist
>
0.05
f
||
normAngleDiff
>
0.01
f
||
dragStarted
)
{
QColor
spColor
(
150
,
150
,
150
);
drawSetpointXYZYaw
(
uiXSetCoordinate
,
uiYSetCoordinate
,
uiZSetCoordinate
,
uiYawSet
,
spColor
,
painter
);
...
...
@@ -547,7 +553,7 @@ void HSIDisplay::mouseDoubleClickEvent(QMouseEvent * event)
{
QPointF
p
=
screenToMetricBody
(
event
->
posF
());
setBodySetpointCoordinateXY
(
p
.
x
(),
p
.
y
());
qDebug
()
<<
"Double click at x: "
<<
screenToRefX
(
event
->
x
())
-
xCenterPos
<<
"y:"
<<
screenToRefY
(
event
->
y
())
-
yCenterPos
;
//
qDebug() << "Double click at x: " << screenToRefX(event->x()) - xCenterPos << "y:" << screenToRefY(event->y()) - yCenterPos;
}
}
...
...
@@ -559,9 +565,7 @@ void HSIDisplay::mouseReleaseEvent(QMouseEvent * event)
{
if
(
dragStarted
)
{
qDebug
()
<<
"YAW CHANGED"
<<
uiYawSet
;
setBodySetpointCoordinateYaw
(
uiYawSet
);
setStatusMessage
(
QString
(
"SENT NEW YAW: %1"
).
arg
(
uiYawSet
));
dragStarted
=
false
;
}
}
...
...
@@ -569,10 +573,8 @@ void HSIDisplay::mouseReleaseEvent(QMouseEvent * event)
{
if
(
leftDragStarted
)
{
// qDebug() << "Z CHANGED" << uiZSetCoordinate;
// setStatusMessage(QString("SENT NEW Z: %1").arg(uiZSetCoordinate));
// setBodySetpointCoordinateZ(uiZSetCoordinate);
// leftDragStarted = false;
setBodySetpointCoordinateZ
(
uiZSetCoordinate
);
leftDragStarted
=
false
;
}
}
}
...
...
@@ -588,7 +590,6 @@ void HSIDisplay::mousePressEvent(QMouseEvent * event)
startX
=
event
->
x
();
// Start tracking mouse move
dragStarted
=
true
;
qDebug
()
<<
"DRAG STARTED"
;
}
else
if
(
event
->
button
()
==
Qt
::
LeftButton
)
{
...
...
@@ -608,7 +609,7 @@ void HSIDisplay::mouseMoveEvent(QMouseEvent * event)
if
(
leftDragStarted
)
{
// uiZSetCoordinate -= 0.06f*(startY - event->y()) / this->frameSize().height();
// set
StatusMessage(QString("NEW Z: %1").arg(uiZSetCoordinate)
);
// set
BodySetpointCoordinateZ(uiZSetCoordinate
);
}
if
(
leftDragStarted
||
dragStarted
)
mouseHasMoved
=
true
;
...
...
@@ -617,7 +618,7 @@ void HSIDisplay::mouseMoveEvent(QMouseEvent * event)
void
HSIDisplay
::
keyPressEvent
(
QKeyEvent
*
event
)
{
if
(
event
->
key
()
==
Qt
::
Key_Enter
||
event
->
key
()
==
Qt
::
Key_S
)
if
(
(
event
->
key
()
==
Qt
::
Key_Enter
||
event
->
key
()
==
Qt
::
Key_Return
)
&&
actionPending
)
{
actionPending
=
false
;
statusMessage
=
"SETPOINT SENT"
;
...
...
@@ -723,7 +724,6 @@ void HSIDisplay::setBodySetpointCoordinateXY(double x, double y)
statusMessage
=
"POSITION SET, PRESS <ENTER> TO SEND"
;
actionPending
=
true
;
statusClearTimer
.
start
();
qDebug
()
<<
"Setting new setpoint at x: "
<<
x
<<
"metric y:"
<<
y
;
}
}
...
...
@@ -754,7 +754,6 @@ void HSIDisplay::setBodySetpointCoordinateYaw(double yaw)
userSetPointSet
=
true
;
// Set coordinates and send them out to MAV
uiYawSet
=
atan2
(
sin
(
yaw
),
cos
(
yaw
));
qDebug
()
<<
"YAW IN"
<<
yaw
<<
"YAW OUT"
<<
uiYawSet
;
statusMessage
=
"YAW SET, PRESS <ENTER> TO SEND"
;
statusClearTimer
.
start
();
actionPending
=
true
;
...
...
src/ui/HSIDisplay.h
View file @
9ae72f8b
...
...
@@ -89,6 +89,8 @@ public slots:
void
clearStatusMessage
()
{
statusMessage
=
""
;
if
(
actionPending
)
statusMessage
=
"TIMED OUT, NO ACTION"
;
statusClearTimer
.
start
();
actionPending
=
false
;
}
...
...
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