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
d1f6bed3
Commit
d1f6bed3
authored
Nov 19, 2012
by
Matthias Krebs
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
3DMouse button mapping to separate translations and rotations (Both WINDOWS and LINUX)
parent
1d898067
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
174 additions
and
23 deletions
+174
-23
Mouse6dofInput.cpp
src/input/Mouse6dofInput.cpp
+146
-21
Mouse6dofInput.h
src/input/Mouse6dofInput.h
+25
-1
MainWindow.cc
src/ui/MainWindow.cc
+3
-1
No files found.
src/input/Mouse6dofInput.cpp
View file @
d1f6bed3
...
...
@@ -10,10 +10,13 @@
#include "UAS.h"
#include "UASManager.h"
#include "QMessageBox"
#ifdef MOUSE_ENABLED_LINUX
#include <QX11Info>
#include <X11/Xlib.h>
#ifdef Success
#undef Success // Eigen library doesn't work if Success is defined
#endif //Success
extern
"C"
{
#include "xdrvlib.h"
...
...
@@ -26,6 +29,8 @@ Mouse6dofInput::Mouse6dofInput(Mouse3DInput* mouseInput) :
uas
(
NULL
),
done
(
false
),
mouseActive
(
false
),
translationActive
(
true
),
rotationActive
(
true
),
xValue
(
0.0
),
yValue
(
0.0
),
zValue
(
0.0
),
...
...
@@ -36,19 +41,20 @@ Mouse6dofInput::Mouse6dofInput(Mouse3DInput* mouseInput) :
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
setActiveUAS
(
UASInterface
*
)));
// Connect 3DxWare SDK MotionEvent
connect
(
mouseInput
,
SIGNAL
(
Move3d
(
std
::
vector
<
float
>&
)),
this
,
SLOT
(
motion3DMouse
(
std
::
vector
<
float
>&
)));
// TODO: Connect button mapping
//connect(mouseInput, SIGNAL(On3dmouseKeyDown(int)), this, SLOT);
//connect(mouseInput, SIGNAL(On3dmouseKeyUp(int)), this, SLOT);
connect
(
mouseInput
,
SIGNAL
(
On3dmouseKeyDown
(
int
)),
this
,
SLOT
(
button3DMouseDown
(
int
)));
//connect(mouseInput, SIGNAL(On3dmouseKeyUp(int)), this, SLOT(FUNCTION(int)));
}
#endif //MOUSE_ENABLED_WIN
#ifdef MOUSE_ENABLED_LINUX
Mouse6dofInput
::
Mouse6dofInput
(
QWidget
*
parent
)
:
mouse3DMax
(
0.075
),
// TODO: check maximum value fot plugged device
Mouse6dofInput
::
Mouse6dofInput
(
QWidget
*
parent
)
:
mouse3DMax
(
350.0
),
// TODO: check maximum value fot plugged device
uas
(
NULL
),
done
(
false
),
mouseActive
(
false
),
translationActive
(
true
),
rotationActive
(
true
),
xValue
(
0.0
),
yValue
(
0.0
),
zValue
(
0.0
),
...
...
@@ -56,14 +62,8 @@ Mouse6dofInput::Mouse6dofInput(QWidget *parent) :
bValue
(
0.0
),
cValue
(
0.0
)
{
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
setActiveUAS
(
UASInterface
*
)));
}
#endif //MOUSE_ENABLED_LINUX
#ifdef MOUSE_ENABLED_LINUX
void
Mouse6dofInput
::
init3dMouse
(
QWidget
*
parent
)
{
if
(
!
mouseActive
)
{
// // man visudo --> then you can omit giving password (success not guarantied..)
...
...
@@ -84,12 +84,12 @@ void Mouse6dofInput::init3dMouse(QWidget* parent)
{
qDebug
()
<<
"Cannot open display!"
<<
endl
;
}
if
(
!
MagellanInit
(
display
,
winId
()
)
)
if
(
!
MagellanInit
(
display
,
parent
->
winId
()
)
)
{
QMessageBox
msgBox
;
msgBox
.
setIcon
(
QMessageBox
::
Information
);
msgBox
.
setText
(
tr
(
"No 3DxWare driver is running."
));
msgBox
.
setInformativeText
(
tr
(
"Enter in Terminal 'sudo /etc/3DxWare/daemon/3dxsrv -d usb'"
));
msgBox
.
setInformativeText
(
tr
(
"Enter in Terminal 'sudo /etc/3DxWare/daemon/3dxsrv -d usb'
and then restart QGroundControl.
"
));
msgBox
.
setStandardButtons
(
QMessageBox
::
Ok
);
msgBox
.
setDefaultButton
(
QMessageBox
::
Ok
);
msgBox
.
exec
();
...
...
@@ -107,9 +107,11 @@ void Mouse6dofInput::init3dMouse(QWidget* parent)
{
qDebug
()
<<
"3dMouse already initialized.."
;
}
}
#endif //MOUSE_ENABLED_LINUX
Mouse6dofInput
::~
Mouse6dofInput
()
{
done
=
true
;
...
...
@@ -134,7 +136,7 @@ void Mouse6dofInput::setActiveUAS(UASInterface* uas)
tmp
=
dynamic_cast
<
UAS
*>
(
this
->
uas
);
if
(
tmp
)
{
connect
(
this
,
SIGNAL
(
mouse6dofChanged
(
double
,
double
,
double
,
double
,
double
,
double
)),
tmp
,
SLOT
(
setManual6DOFControlCommands
(
double
,
double
,
double
,
double
,
double
,
double
)));
// Todo:
dis
connect button mapping
// Todo: connect button mapping
}
if
(
!
isRunning
())
{
...
...
@@ -189,17 +191,140 @@ void Mouse6dofInput::run()
}
}
#ifdef MOUSE_ENABLED_WIN
void
Mouse6dofInput
::
motion3DMouse
(
std
::
vector
<
float
>
&
motionData
)
{
if
(
motionData
.
size
()
<
6
)
return
;
mouseActive
=
true
;
xValue
=
(
double
)
1.0e2
f
*
motionData
[
1
]
/
mouse3DMax
;
yValue
=
(
double
)
1.0e2
f
*
motionData
[
0
]
/
mouse3DMax
;
zValue
=
(
double
)
1.0e2
f
*
motionData
[
2
]
/
mouse3DMax
;
aValue
=
(
double
)
1.0e2
f
*
motionData
[
4
]
/
mouse3DMax
;
bValue
=
(
double
)
1.0e2
f
*
motionData
[
3
]
/
mouse3DMax
;
cValue
=
(
double
)
1.0e2
f
*
motionData
[
5
]
/
mouse3DMax
;
if
(
translationActive
)
{
xValue
=
(
double
)
1.0e2
f
*
motionData
[
1
]
/
mouse3DMax
;
yValue
=
(
double
)
1.0e2
f
*
motionData
[
0
]
/
mouse3DMax
;
zValue
=
(
double
)
1.0e2
f
*
motionData
[
2
]
/
mouse3DMax
;
}
else
{
xValue
=
0
;
yValue
=
0
;
zValue
=
0
;
}
if
(
rotationActive
)
{
aValue
=
(
double
)
1.0e2
f
*
motionData
[
4
]
/
mouse3DMax
;
bValue
=
(
double
)
1.0e2
f
*
motionData
[
3
]
/
mouse3DMax
;
cValue
=
(
double
)
1.0e2
f
*
motionData
[
5
]
/
mouse3DMax
;
}
else
{
aValue
=
0
;
bValue
=
0
;
cValue
=
0
;
}
//qDebug() << "NEW 3D MOUSE VALUES -- X" << xValue << " -- Y" << yValue << " -- Z" << zValue << " -- A" << aValue << " -- B" << bValue << " -- C" << cValue;
}
#endif //MOUSE_ENABLED_WIN
#ifdef MOUSE_ENABLED_WIN
void
Mouse6dofInput
::
button3DMouseDown
(
int
button
)
{
switch
(
button
)
{
case
1
:
{
rotationActive
=
!
rotationActive
;
emit
mouseRotationActiveChanged
(
rotationActive
);
qDebug
()
<<
"Changed 3DMouse Rotation to "
<<
(
bool
)
rotationActive
;
break
;
}
case
2
:
{
translationActive
=
!
translationActive
;
emit
mouseTranslationEnabledChanged
(
translationActive
);
qDebug
()
<<
"Changed 3DMouse Translation to"
<<
(
bool
)
translationActive
;
break
;
}
default:
break
;
}
}
#endif //MOUSE_ENABLED_WIN
#ifdef MOUSE_ENABLED_LINUX
void
Mouse6dofInput
::
handleX11Event
(
XEvent
*
event
)
{
//qDebug("XEvent occured...");
if
(
!
mouseActive
)
{
qDebug
()
<<
"3dMouse not initialized. Cancelled handling X11event for 3dMouse"
;
return
;
}
MagellanFloatEvent
MagellanEvent
;
Display
*
display
=
QX11Info
::
display
();
if
(
!
display
)
{
qDebug
()
<<
"Cannot open display!"
<<
endl
;
}
switch
(
event
->
type
)
{
case
ClientMessage
:
switch
(
MagellanTranslateEvent
(
display
,
event
,
&
MagellanEvent
,
1.0
,
1.0
)
)
{
case
MagellanInputMotionEvent
:
MagellanRemoveMotionEvents
(
display
);
for
(
int
i
=
0
;
i
<
6
;
i
++
)
{
// Saturation
MagellanEvent
.
MagellanData
[
i
]
=
(
abs
(
MagellanEvent
.
MagellanData
[
i
])
<
mouse3DMax
)
?
MagellanEvent
.
MagellanData
[
i
]
:
(
mouse3DMax
*
MagellanEvent
.
MagellanData
[
i
]
/
abs
(
MagellanEvent
.
MagellanData
[
i
]));
}
// Check whether translational motions are enabled
if
(
translationActive
)
{
xValue
=
MagellanEvent
.
MagellanData
[
MagellanZ
]
/
mouse3DMax
;
yValue
=
MagellanEvent
.
MagellanData
[
MagellanX
]
/
mouse3DMax
;
zValue
=
-
MagellanEvent
.
MagellanData
[
MagellanY
]
/
mouse3DMax
;
}
else
{
xValue
=
0
;
yValue
=
0
;
zValue
=
0
;
}
// Check whether rotational motions are enabled
if
(
rotationActive
)
{
aValue
=
MagellanEvent
.
MagellanData
[
MagellanC
]
/
mouse3DMax
;
bValue
=
MagellanEvent
.
MagellanData
[
MagellanA
]
/
mouse3DMax
;
cValue
=
-
MagellanEvent
.
MagellanData
[
MagellanB
]
/
mouse3DMax
;
}
else
{
aValue
=
0
;
bValue
=
0
;
cValue
=
0
;
}
//qDebug() << "NEW 3D MOUSE VALUES -- X" << xValue << " -- Y" << yValue << " -- Z" << zValue << " -- A" << aValue << " -- B" << bValue << " -- C" << cValue;
break
;
case
MagellanInputButtonPressEvent
:
qDebug
()
<<
"MagellanInputButtonPressEvent called with button "
<<
MagellanEvent
.
MagellanButton
;
switch
(
MagellanEvent
.
MagellanButton
)
{
case
1
:
{
rotationActive
=
!
rotationActive
;
emit
mouseRotationActiveChanged
(
rotationActive
);
qDebug
()
<<
"Changed 3DMouse Rotation to "
<<
(
bool
)
rotationActive
;
break
;
}
case
2
:
{
translationActive
=
!
translationActive
;
emit
mouseTranslationActiveChanged
(
translationActive
);
qDebug
()
<<
"Changed 3DMouse Translation to"
<<
(
bool
)
translationActive
;
break
;
}
default:
break
;
}
default:
break
;
}
}
}
#endif //MOUSE_ENABLED_LINUX
src/input/Mouse6dofInput.h
View file @
d1f6bed3
...
...
@@ -10,6 +10,7 @@
#define MOUSE6DOFINPUT_H
#include <QThread>
#ifdef MOUSE_ENABLED_WIN
#include "Mouse3DInput.h"
#endif //MOUSE_ENABLED_WIN
...
...
@@ -26,7 +27,6 @@ public:
#endif //MOUSE_ENABLED_WIN
#ifdef MOUSE_ENABLED_LINUX
Mouse6dofInput
(
QWidget
*
parent
);
void
init3dMouse
(
QWidget
*
parent
);
#endif //MOUSE_ENABLED_LINUX
~
Mouse6dofInput
();
...
...
@@ -40,6 +40,8 @@ protected:
UASInterface
*
uas
;
bool
done
;
bool
mouseActive
;
bool
translationActive
;
bool
rotationActive
;
double
xValue
;
double
yValue
;
...
...
@@ -48,6 +50,7 @@ protected:
double
bValue
;
double
cValue
;
signals:
/**
* @brief Input of the 3d mouse has changed
...
...
@@ -61,9 +64,30 @@ signals:
*/
void
mouse6dofChanged
(
double
x
,
double
y
,
double
z
,
double
a
,
double
b
,
double
c
);
/**
* @brief Activity of translational 3DMouse inputs changed
* @param translationEnable, true: translational inputs active; false: translational inputs ingored
*/
void
mouseTranslationActiveChanged
(
bool
translationEnable
);
/**
* @brief Activity of rotational 3DMouse inputs changed
* @param rotationEnable, true: rotational inputs active; false: rotational inputs ingored
*/
void
mouseRotationActiveChanged
(
bool
rotationEnable
);
public
slots
:
void
setActiveUAS
(
UASInterface
*
uas
);
#ifdef MOUSE_ENABLED_WIN
/** @brief Get a motion input from 3DMouse */
void
motion3DMouse
(
std
::
vector
<
float
>
&
motionData
);
/** @brief Get a button input from 3DMouse */
void
button3DMouseDown
(
int
button
);
#endif //MOUSE_ENABLED_WIN
#ifdef MOUSE_ENABLED_LINUX
/** @brief Get an XEvent to check it for an 3DMouse event (motion or button) */
void
handleX11Event
(
XEvent
*
event
);
#endif //MOUSE_ENABLED_LINUX
};
...
...
src/ui/MainWindow.cc
View file @
d1f6bed3
...
...
@@ -193,6 +193,7 @@ MainWindow::MainWindow(QWidget *parent):
emit
initStatusChanged
(
"Initializing 3D mouse interface."
);
mouse
=
new
Mouse6dofInput
(
this
);
connect
(
this
,
SIGNAL
(
x11EventOccured
(
XEvent
*
)),
mouse
,
SLOT
(
handleX11Event
(
XEvent
*
)));
#endif //MOUSE_ENABLED_LINUX
// Connect link
...
...
@@ -1737,6 +1738,7 @@ QList<QAction*> MainWindow::listLinkMenuActions(void)
bool
MainWindow
::
x11Event
(
XEvent
*
event
)
{
emit
x11EventOccured
(
event
);
qDebug
(
"XEvent occured..."
);
//qDebug("XEvent occured...");
return
false
;
}
#endif // MOUSE_ENABLED_LINUX
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