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
800b2236
Unverified
Commit
800b2236
authored
Jul 27, 2019
by
Gus Grubba
Committed by
GitHub
Jul 27, 2019
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #7624 from mavlink/JoystickTweaks
Keep track of gimbal position locally.
parents
33fbd552
eb30a3a7
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
34 additions
and
5 deletions
+34
-5
Joystick.cc
src/Joystick/Joystick.cc
+27
-5
Joystick.h
src/Joystick/Joystick.h
+7
-0
No files found.
src/Joystick/Joystick.cc
View file @
800b2236
...
...
@@ -680,6 +680,7 @@ void Joystick::startPolling(Vehicle* vehicle)
disconnect
(
this
,
&
Joystick
::
gimbalPitchStep
,
_activeVehicle
,
&
Vehicle
::
gimbalPitchStep
);
disconnect
(
this
,
&
Joystick
::
gimbalYawStep
,
_activeVehicle
,
&
Vehicle
::
gimbalYawStep
);
disconnect
(
this
,
&
Joystick
::
centerGimbal
,
_activeVehicle
,
&
Vehicle
::
centerGimbal
);
disconnect
(
this
,
&
Joystick
::
gimbalControlValue
,
_activeVehicle
,
&
Vehicle
::
gimbalControlValue
);
}
// Always set up the new vehicle
_activeVehicle
=
vehicle
;
...
...
@@ -700,6 +701,7 @@ void Joystick::startPolling(Vehicle* vehicle)
connect
(
this
,
&
Joystick
::
gimbalPitchStep
,
_activeVehicle
,
&
Vehicle
::
gimbalPitchStep
);
connect
(
this
,
&
Joystick
::
gimbalYawStep
,
_activeVehicle
,
&
Vehicle
::
gimbalYawStep
);
connect
(
this
,
&
Joystick
::
centerGimbal
,
_activeVehicle
,
&
Vehicle
::
centerGimbal
);
connect
(
this
,
&
Joystick
::
gimbalControlValue
,
_activeVehicle
,
&
Vehicle
::
gimbalControlValue
);
// FIXME: ****
//connect(this, &Joystick::buttonActionTriggered, uas, &UAS::triggerAction);
}
...
...
@@ -724,6 +726,7 @@ void Joystick::stopPolling(void)
disconnect
(
this
,
&
Joystick
::
gimbalPitchStep
,
_activeVehicle
,
&
Vehicle
::
gimbalPitchStep
);
disconnect
(
this
,
&
Joystick
::
gimbalYawStep
,
_activeVehicle
,
&
Vehicle
::
gimbalYawStep
);
disconnect
(
this
,
&
Joystick
::
centerGimbal
,
_activeVehicle
,
&
Vehicle
::
centerGimbal
);
disconnect
(
this
,
&
Joystick
::
gimbalControlValue
,
_activeVehicle
,
&
Vehicle
::
gimbalControlValue
);
}
// FIXME: ****
//disconnect(this, &Joystick::buttonActionTriggered, uas, &UAS::triggerAction);
...
...
@@ -1003,20 +1006,39 @@ void Joystick::_executeButtonAction(const QString& action)
}
else
if
(
action
==
_buttonActionToggleVideoRecord
)
{
emit
toggleVideoRecord
();
}
else
if
(
action
==
_buttonActionGimbalUp
)
{
emit
gimbalP
itchStep
(
1
);
_p
itchStep
(
1
);
}
else
if
(
action
==
_buttonActionGimbalDown
)
{
emit
gimbalP
itchStep
(
-
1
);
_p
itchStep
(
-
1
);
}
else
if
(
action
==
_buttonActionGimbalLeft
)
{
emit
gimbalY
awStep
(
-
1
);
_y
awStep
(
-
1
);
}
else
if
(
action
==
_buttonActionGimbalRight
)
{
emit
gimbalY
awStep
(
1
);
_y
awStep
(
1
);
}
else
if
(
action
==
_buttonActionGimbalCenter
)
{
emit
centerGimbal
();
_localPitch
=
0.0
;
_localYaw
=
0.0
;
emit
gimbalControlValue
(
0.0
,
0.0
);
}
else
{
qCDebug
(
JoystickLog
)
<<
"_buttonAction unknown action:"
<<
action
;
}
}
void
Joystick
::
_pitchStep
(
int
direction
)
{
_localPitch
+=
static_cast
<
double
>
(
direction
);
//-- Arbitrary range
if
(
_localPitch
<
-
90.0
)
_localPitch
=
-
90.0
;
if
(
_localPitch
>
35.0
)
_localPitch
=
35.0
;
emit
gimbalControlValue
(
_localPitch
,
_localYaw
);
}
void
Joystick
::
_yawStep
(
int
direction
)
{
_localYaw
+=
static_cast
<
double
>
(
direction
);
if
(
_localYaw
<
-
180.0
)
_localYaw
=
-
180.0
;
if
(
_localYaw
>
180.0
)
_localYaw
=
180.0
;
emit
gimbalControlValue
(
_localPitch
,
_localYaw
);
}
bool
Joystick
::
_validAxis
(
int
axis
)
{
if
(
axis
>=
0
&&
axis
<
_axisCount
)
{
...
...
src/Joystick/Joystick.h
View file @
800b2236
...
...
@@ -213,6 +213,7 @@ signals:
void
gimbalPitchStep
(
int
direction
);
void
gimbalYawStep
(
int
direction
);
void
centerGimbal
();
void
gimbalControlValue
(
double
pitch
,
double
yaw
);
void
setArmed
(
bool
arm
);
void
setVtolInFwdFlight
(
bool
set
);
void
setFlightMode
(
const
QString
&
flightMode
);
...
...
@@ -230,6 +231,11 @@ protected:
void
_handleAxis
();
void
_handleButtons
();
void
_pitchStep
(
int
direction
);
void
_yawStep
(
int
direction
);
double
_localYaw
=
0
.
0
;
double
_localPitch
=
0
.
0
;
private:
virtual
bool
_open
()
=
0
;
virtual
void
_close
()
=
0
;
...
...
@@ -290,6 +296,7 @@ protected:
QStringList
_availableActionTitles
;
MultiVehicleManager
*
_multiVehicleManager
=
nullptr
;
private:
static
const
char
*
_rgFunctionSettingsKey
[
maxFunction
];
...
...
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