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
4f8deb49
Commit
4f8deb49
authored
May 07, 2018
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Start possible Solo video
parent
535ff2ab
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
8 additions
and
4 deletions
+8
-4
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+7
-3
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+1
-1
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
4f8deb49
...
...
@@ -366,6 +366,8 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess
supportedMinorNumber
=
4
;
break
;
case
MAV_TYPE_QUADROTOR
:
// Start TCP video handshake with ARTOO in case it's a Solo running ArduPilot firmware
_soloVideoHandshake
(
vehicle
,
false
/* originalSoloFirmware */
);
case
MAV_TYPE_COAXIAL
:
case
MAV_TYPE_HELICOPTER
:
case
MAV_TYPE_SUBMARINE
:
...
...
@@ -420,7 +422,7 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess
_setInfoSeverity
(
message
);
// Start TCP video handshake with ARTOO
_soloVideoHandshake
(
vehicle
);
_soloVideoHandshake
(
vehicle
,
true
/* originalSoloFirmware */
);
}
else
if
(
messageText
.
contains
(
APM_FRAME_REXP
))
{
// We need to parse the Frame: message in order to determine whether the motors are coaxial or not
QRegExp
frameTypeRegex
(
"^Frame: (
\\
S*)"
);
...
...
@@ -750,14 +752,16 @@ bool APMFirmwarePlugin::isGuidedMode(const Vehicle* vehicle) const
return
vehicle
->
flightMode
()
==
"Guided"
;
}
void
APMFirmwarePlugin
::
_soloVideoHandshake
(
Vehicle
*
vehicle
)
void
APMFirmwarePlugin
::
_soloVideoHandshake
(
Vehicle
*
vehicle
,
bool
originalSoloFirmware
)
{
Q_UNUSED
(
vehicle
);
QTcpSocket
*
socket
=
new
QTcpSocket
();
socket
->
connectToHost
(
_artooIP
,
_artooVideoHandshakePort
);
QObject
::
connect
(
socket
,
static_cast
<
void
(
QTcpSocket
::*
)(
QAbstractSocket
::
SocketError
)
>
(
&
QTcpSocket
::
error
),
this
,
&
APMFirmwarePlugin
::
_artooSocketError
);
if
(
originalSoloFirmware
)
{
QObject
::
connect
(
socket
,
static_cast
<
void
(
QTcpSocket
::*
)(
QAbstractSocket
::
SocketError
)
>
(
&
QTcpSocket
::
error
),
this
,
&
APMFirmwarePlugin
::
_artooSocketError
);
}
}
void
APMFirmwarePlugin
::
_artooSocketError
(
QAbstractSocket
::
SocketError
socketError
)
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
4f8deb49
...
...
@@ -125,7 +125,7 @@ private:
bool
_handleIncomingStatusText
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handleIncomingHeartbeat
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handleOutgoingParamSet
(
Vehicle
*
vehicle
,
LinkInterface
*
outgoingLink
,
mavlink_message_t
*
message
);
void
_soloVideoHandshake
(
Vehicle
*
vehicle
);
void
_soloVideoHandshake
(
Vehicle
*
vehicle
,
bool
originalSoloFirmware
);
bool
_guidedModeTakeoff
(
Vehicle
*
vehicle
,
double
altitudeRel
);
// Any instance data here must be global to all vehicles
...
...
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