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
9705cd4e
Commit
9705cd4e
authored
Mar 05, 2016
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Speech changes, plus clearTrajectory
parent
adefe53c
Changes
2
Show whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
23 additions
and
5 deletions
+23
-5
Vehicle.cc
src/Vehicle/Vehicle.cc
+20
-5
Vehicle.h
src/Vehicle/Vehicle.h
+3
-0
No files found.
src/Vehicle/Vehicle.cc
View file @
9705cd4e
...
...
@@ -141,6 +141,7 @@ Vehicle::Vehicle(LinkInterface* link,
connect
(
this
,
&
Vehicle
::
_sendMessageOnThread
,
this
,
&
Vehicle
::
_sendMessage
,
Qt
::
QueuedConnection
);
connect
(
this
,
&
Vehicle
::
_sendMessageOnLinkOnThread
,
this
,
&
Vehicle
::
_sendMessageOnLink
,
Qt
::
QueuedConnection
);
connect
(
this
,
&
Vehicle
::
flightModeChanged
,
this
,
&
Vehicle
::
_announceflightModeChanged
);
connect
(
this
,
&
Vehicle
::
armedChanged
,
this
,
&
Vehicle
::
_announceArmedChanged
);
_uas
=
new
UAS
(
_mavlink
,
this
,
_firmwarePluginManager
);
...
...
@@ -224,6 +225,9 @@ Vehicle::Vehicle(LinkInterface* link,
_batteryFactGroup
.
setVehicle
(
this
);
_windFactGroup
.
setVehicle
(
this
);
_vibrationFactGroup
.
setVehicle
(
this
);
_announceArmedChanged
(
armed
());
_announceflightModeChanged
(
flightMode
());
}
// Disconnected Vehicle
...
...
@@ -467,7 +471,7 @@ void Vehicle::_handleSysStatus(mavlink_message_t& message)
if
(
sysStatus
.
battery_remaining
>
0
&&
sysStatus
.
battery_remaining
<
_batteryFactGroup
.
percentRemainingAnnounce
()
->
rawValue
().
toInt
())
{
if
(
!
_lowBatteryAnnounceTimer
.
isValid
()
||
_lowBatteryAnnounceTimer
.
elapsed
()
>
_lowBatteryAnnounceRepeatMSecs
)
{
_lowBatteryAnnounceTimer
.
restart
();
_say
(
QString
(
"
Low battery on %1
: %2 percent remaining"
).
arg
(
_vehicleIdSpeech
()).
arg
(
sysStatus
.
battery_remaining
));
_say
(
QString
(
"
%1 low battery
: %2 percent remaining"
).
arg
(
_vehicleIdSpeech
()).
arg
(
sysStatus
.
battery_remaining
));
}
}
}
...
...
@@ -1288,7 +1292,7 @@ void Vehicle::_connectionLostTimeout(void)
_connectionLost
=
true
;
_heardFrom
=
false
;
emit
connectionLostChanged
(
true
);
_say
(
QString
(
"
communication lost to %1
"
).
arg
(
_vehicleIdSpeech
()));
_say
(
QString
(
"
%1 communication lost
"
).
arg
(
_vehicleIdSpeech
()));
if
(
_autoDisconnect
)
{
disconnectInactiveVehicle
();
}
...
...
@@ -1301,7 +1305,7 @@ void Vehicle::_connectionActive(void)
if
(
_connectionLost
)
{
_connectionLost
=
false
;
emit
connectionLostChanged
(
false
);
_say
(
QString
(
"
communication regained to %1
"
).
arg
(
_vehicleIdSpeech
()));
_say
(
QString
(
"
% 1 communication regained
"
).
arg
(
_vehicleIdSpeech
()));
}
}
...
...
@@ -1344,15 +1348,26 @@ QString Vehicle::_vehicleIdSpeech(void)
if
(
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
vehicles
()
->
count
()
>
1
)
{
return
QString
(
"vehicle %1"
).
arg
(
id
());
}
else
{
return
QString
Literal
(
"vehicle"
);
return
QString
(
);
}
}
void
Vehicle
::
_announceflightModeChanged
(
const
QString
&
flightMode
)
{
_say
(
QString
(
"%1 is now in %2 flight mode"
).
arg
(
_vehicleIdSpeech
()).
arg
(
flightMode
));
_say
(
QString
(
"%1 %2 flight mode"
).
arg
(
_vehicleIdSpeech
()).
arg
(
flightMode
));
}
void
Vehicle
::
_announceArmedChanged
(
bool
armed
)
{
_say
(
QString
(
"%1 %2"
).
arg
(
_vehicleIdSpeech
()).
arg
(
armed
?
QStringLiteral
(
"armed"
)
:
QStringLiteral
(
"disarmed"
)));
}
void
Vehicle
::
clearTrajectoryPoints
(
void
)
{
_mapTrajectoryList
.
clearAndDeleteContents
();
}
const
char
*
VehicleGPSFactGroup
::
_hdopFactName
=
"hdop"
;
const
char
*
VehicleGPSFactGroup
::
_vdopFactName
=
"vdop"
;
const
char
*
VehicleGPSFactGroup
::
_courseOverGroundFactName
=
"courseOverGround"
;
...
...
src/Vehicle/Vehicle.h
View file @
9705cd4e
...
...
@@ -318,6 +318,8 @@ public:
Q_INVOKABLE
void
virtualTabletJoystickValue
(
double
roll
,
double
pitch
,
double
yaw
,
double
thrust
);
Q_INVOKABLE
void
disconnectInactiveVehicle
(
void
);
Q_INVOKABLE
void
clearTrajectoryPoints
(
void
);
// Property accessors
QGeoCoordinate
coordinate
(
void
)
{
return
_coordinate
;
}
...
...
@@ -524,6 +526,7 @@ private slots:
void
_parametersReady
(
bool
parametersReady
);
void
_remoteControlRSSIChanged
(
uint8_t
rssi
);
void
_announceflightModeChanged
(
const
QString
&
flightMode
);
void
_announceArmedChanged
(
bool
armed
);
void
_handleTextMessage
(
int
newCount
);
void
_handletextMessageReceived
(
UASMessage
*
message
);
...
...
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