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
773c9bd9
Commit
773c9bd9
authored
Oct 19, 2017
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
String fixups for loc
parent
e842fd7a
Changes
16
Expand all
Show whitespace changes
Inline
Side-by-side
Showing
16 changed files
with
131 additions
and
131 deletions
+131
-131
LogDownloadController.cc
src/AnalyzeView/LogDownloadController.cc
+3
-3
ULogParser.cc
src/AnalyzeView/ULogParser.cc
+18
-18
APMAirframeComponent.cc
src/AutoPilotPlugins/APM/APMAirframeComponent.cc
+1
-1
APMAirframeComponentController.cc
src/AutoPilotPlugins/APM/APMAirframeComponentController.cc
+1
-1
APMCompassCal.cc
src/AutoPilotPlugins/APM/APMCompassCal.cc
+12
-12
APMFlightModesComponentController.cc
...AutoPilotPlugins/APM/APMFlightModesComponentController.cc
+2
-2
APMPowerComponent.cc
src/AutoPilotPlugins/APM/APMPowerComponent.cc
+1
-1
APMRadioComponent.cc
src/AutoPilotPlugins/APM/APMRadioComponent.cc
+6
-6
APMSensorsComponent.cc
src/AutoPilotPlugins/APM/APMSensorsComponent.cc
+6
-6
APMSensorsComponentController.cc
src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
+4
-4
APMTuningComponent.cc
src/AutoPilotPlugins/APM/APMTuningComponent.cc
+1
-1
AutoPilotPlugin.cc
src/AutoPilotPlugins/AutoPilotPlugin.cc
+1
-1
ESP8266ComponentController.cc
src/AutoPilotPlugins/Common/ESP8266ComponentController.cc
+48
-48
RadioComponentController.cc
src/AutoPilotPlugins/Common/RadioComponentController.cc
+6
-6
SyslinkComponentController.cc
src/AutoPilotPlugins/Common/SyslinkComponentController.cc
+19
-19
AirframeComponent.cc
src/AutoPilotPlugins/PX4/AirframeComponent.cc
+2
-2
No files found.
src/AnalyzeView/LogDownloadController.cc
View file @
773c9bd9
...
...
@@ -589,14 +589,14 @@ LogDownloadController::_prepareLogDownload()
bool
result
=
false
;
QString
ftime
;
if
(
entry
->
time
().
date
().
year
()
<
2010
)
{
ftime
=
"UnknownDate"
;
ftime
=
tr
(
"UnknownDate"
)
;
}
else
{
ftime
=
entry
->
time
().
toString
(
"yyyy-M-d-hh-mm-ss"
);
ftime
=
entry
->
time
().
toString
(
QStringLiteral
(
"yyyy-M-d-hh-mm-ss"
)
);
}
_downloadData
=
new
LogDownloadData
(
entry
);
_downloadData
->
filename
=
QString
(
"log_"
)
+
QString
::
number
(
entry
->
id
())
+
"_"
+
ftime
;
if
(
_vehicle
->
firmwareType
()
==
MAV_AUTOPILOT_PX4
)
{
QString
loggerParam
(
"SYS_LOGGER"
);
QString
loggerParam
=
QStringLiteral
(
"SYS_LOGGER"
);
if
(
_vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
loggerParam
)
&&
_vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
loggerParam
)
->
rawValue
().
toInt
()
==
0
)
{
_downloadData
->
filename
+=
".px4log"
;
...
...
src/AnalyzeView/ULogParser.cc
View file @
773c9bd9
...
...
@@ -14,25 +14,25 @@ ULogParser::~ULogParser()
int
ULogParser
::
sizeOfType
(
QString
&
typeName
)
{
if
(
typeName
==
"int8_t"
||
typeName
==
"uint8_t"
)
{
if
(
typeName
==
QLatin1Literal
(
"int8_t"
)
||
typeName
==
QLatin1Literal
(
"uint8_t"
)
)
{
return
1
;
}
else
if
(
typeName
==
"int16_t"
||
typeName
==
"uint16_t"
)
{
}
else
if
(
typeName
==
QLatin1Literal
(
"int16_t"
)
||
typeName
==
QLatin1Literal
(
"uint16_t"
)
)
{
return
2
;
}
else
if
(
typeName
==
"int32_t"
||
typeName
==
"uint32_t"
)
{
}
else
if
(
typeName
==
QLatin1Literal
(
"int32_t"
)
||
typeName
==
QLatin1Literal
(
"uint32_t"
)
)
{
return
4
;
}
else
if
(
typeName
==
"int64_t"
||
typeName
==
"uint64_t"
)
{
}
else
if
(
typeName
==
QLatin1Literal
(
"int64_t"
)
||
typeName
==
QLatin1Literal
(
"uint64_t"
)
)
{
return
8
;
}
else
if
(
typeName
==
"float"
)
{
}
else
if
(
typeName
==
QLatin1Literal
(
"float"
)
)
{
return
4
;
}
else
if
(
typeName
==
"double"
)
{
}
else
if
(
typeName
==
QLatin1Literal
(
"double"
)
)
{
return
8
;
}
else
if
(
typeName
==
"char"
||
typeName
==
"bool"
)
{
}
else
if
(
typeName
==
QLatin1Literal
(
"char"
)
||
typeName
==
QLatin1Literal
(
"bool"
)
)
{
return
1
;
}
...
...
@@ -74,7 +74,7 @@ bool ULogParser::parseFieldFormat(QString& fields)
QString
typeNameFull
=
fields
.
mid
(
prevFieldEnd
,
spacePos
-
prevFieldEnd
);
QString
fieldName
=
fields
.
mid
(
spacePos
+
1
,
fieldEnd
-
spacePos
-
1
);
if
(
!
fieldName
.
contains
(
"_padding"
))
{
if
(
!
fieldName
.
contains
(
QLatin1Literal
(
"_padding"
)
))
{
_cameraCaptureOffsets
.
insert
(
fieldName
,
offset
);
offset
+=
sizeOfFullType
(
typeNameFull
);
}
...
...
@@ -115,7 +115,7 @@ bool ULogParser::getTagsFromLog(QByteArray& log, QList<GeoTagWorker::cameraFeedb
QString
messageName
=
fmt
.
left
(
posSeparator
);
QString
messageFields
=
fmt
.
mid
(
posSeparator
+
1
,
header
.
msgSize
-
posSeparator
-
1
);
if
(
messageName
==
"camera_capture"
)
{
if
(
messageName
==
QLatin1Literal
(
"camera_capture"
)
)
{
parseFieldFormat
(
messageFields
);
}
break
;
...
...
@@ -129,7 +129,7 @@ bool ULogParser::getTagsFromLog(QByteArray& log, QList<GeoTagWorker::cameraFeedb
QString
messageName
(
addLoggedMsg
.
msgName
);
if
(
messageName
.
contains
(
"camera_capture"
))
{
if
(
messageName
.
contains
(
QLatin1Literal
(
"camera_capture"
)
))
{
_cameraCaptureMsgID
=
addLoggedMsg
.
msgID
;
geotagFound
=
true
;
}
...
...
@@ -152,17 +152,17 @@ bool ULogParser::getTagsFromLog(QByteArray& log, QList<GeoTagWorker::cameraFeedb
// Completely dynamic parsing, so that changing/reordering the message format will not break the parser
GeoTagWorker
::
cameraFeedbackPacket
feedback
;
memset
(
&
feedback
,
0
,
sizeof
(
feedback
));
memcpy
(
&
feedback
.
timestamp
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
"timestamp"
),
8
);
memcpy
(
&
feedback
.
timestamp
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
QStringLiteral
(
"timestamp"
)
),
8
);
feedback
.
timestamp
/=
1.0e6
;
// to seconds
memcpy
(
&
feedback
.
timestampUTC
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
"timestamp_utc"
),
8
);
memcpy
(
&
feedback
.
timestampUTC
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
QStringLiteral
(
"timestamp_utc"
)
),
8
);
feedback
.
timestampUTC
/=
1.0e6
;
// to seconds
memcpy
(
&
feedback
.
imageSequence
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
"seq"
),
4
);
memcpy
(
&
feedback
.
latitude
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
"lat"
),
8
);
memcpy
(
&
feedback
.
longitude
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
"lon"
),
8
);
memcpy
(
&
feedback
.
imageSequence
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
QStringLiteral
(
"seq"
)
),
4
);
memcpy
(
&
feedback
.
latitude
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
QStringLiteral
(
"lat"
)
),
8
);
memcpy
(
&
feedback
.
longitude
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
QStringLiteral
(
"lon"
)
),
8
);
feedback
.
longitude
=
fmod
(
180.0
+
feedback
.
longitude
,
360.0
)
-
180.0
;
memcpy
(
&
feedback
.
altitude
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
"alt"
),
4
);
memcpy
(
&
feedback
.
groundDistance
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
"ground_distance"
),
4
);
memcpy
(
&
feedback
.
captureResult
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
"result"
),
1
);
memcpy
(
&
feedback
.
altitude
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
QStringLiteral
(
"alt"
)
),
4
);
memcpy
(
&
feedback
.
groundDistance
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
QStringLiteral
(
"ground_distance"
)
),
4
);
memcpy
(
&
feedback
.
captureResult
,
log
.
data
()
+
index
+
5
+
_cameraCaptureOffsets
.
value
(
QStringLiteral
(
"result"
)
),
1
);
cameraFeedback
.
append
(
feedback
);
...
...
src/AutoPilotPlugins/APM/APMAirframeComponent.cc
View file @
773c9bd9
...
...
@@ -17,7 +17,7 @@ const char* APMAirframeComponent::_newFrameParam = "FRAME_CLASS";
APMAirframeComponent
::
APMAirframeComponent
(
Vehicle
*
vehicle
,
AutoPilotPlugin
*
autopilot
,
QObject
*
parent
)
:
VehicleComponent
(
vehicle
,
autopilot
,
parent
)
,
_requiresFrameSetup
(
false
)
,
_name
(
"Airframe"
)
,
_name
(
tr
(
"Airframe"
)
)
{
if
(
qobject_cast
<
ArduCopterFirmwarePlugin
*>
(
_vehicle
->
firmwarePlugin
())
!=
NULL
)
{
ParameterManager
*
paramMgr
=
_vehicle
->
parameterManager
();
...
...
src/AutoPilotPlugins/APM/APMAirframeComponentController.cc
View file @
773c9bd9
...
...
@@ -237,7 +237,7 @@ void APMAirframeComponentController::_githubJsonDownloadFinished(QString remoteF
QGCFileDownload
*
downloader
=
new
QGCFileDownload
(
this
);
connect
(
downloader
,
&
QGCFileDownload
::
downloadFinished
,
this
,
&
APMAirframeComponentController
::
_paramFileDownloadFinished
);
connect
(
downloader
,
&
QGCFileDownload
::
error
,
this
,
&
APMAirframeComponentController
::
_paramFileDownloadError
);
downloader
->
download
(
json
[
"download_url"
].
toString
());
downloader
->
download
(
json
[
QLatin1Literal
(
"download_url"
)
].
toString
());
}
void
APMAirframeComponentController
::
_githubJsonDownloadError
(
QString
errorMsg
)
...
...
src/AutoPilotPlugins/APM/APMCompassCal.cc
View file @
773c9bd9
...
...
@@ -117,7 +117,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void)
&
sphere_radius
[
cur_mag
]);
if
(
qIsNaN
(
sphere_x
[
cur_mag
])
||
qIsNaN
(
sphere_y
[
cur_mag
])
||
qIsNaN
(
sphere_z
[
cur_mag
]))
{
_emitVehicleTextMessage
(
QString
(
"[cal] ERROR: NaN in sphere fit for mag %1"
).
arg
(
cur_mag
));
_emitVehicleTextMessage
(
QString
Literal
(
"[cal] ERROR: NaN in sphere fit for mag %1"
).
arg
(
cur_mag
));
result
=
calibrate_return_error
;
}
}
...
...
@@ -134,7 +134,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void)
if
(
result
==
calibrate_return_ok
)
{
for
(
unsigned
cur_mag
=
0
;
cur_mag
<
max_mags
;
cur_mag
++
)
{
if
(
rgCompassAvailable
[
cur_mag
])
{
_emitVehicleTextMessage
(
QString
(
"[cal] mag #%1 off: x:%2 y:%3 z:%4"
).
arg
(
cur_mag
).
arg
(
-
sphere_x
[
cur_mag
]).
arg
(
-
sphere_y
[
cur_mag
]).
arg
(
-
sphere_z
[
cur_mag
]));
_emitVehicleTextMessage
(
QString
Literal
(
"[cal] mag #%1 off: x:%2 y:%3 z:%4"
).
arg
(
cur_mag
).
arg
(
-
sphere_x
[
cur_mag
]).
arg
(
-
sphere_y
[
cur_mag
]).
arg
(
-
sphere_z
[
cur_mag
]));
float
sensorId
=
0.0
f
;
if
(
cur_mag
==
0
)
{
...
...
@@ -166,7 +166,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::mag_calibration_worker(detect
mag_worker_data_t
*
worker_data
=
(
mag_worker_data_t
*
)(
data
);
_emitVehicleTextMessage
(
QStringLiteral
(
"[cal] Rotate vehicle around the detected orientation"
));
_emitVehicleTextMessage
(
QString
(
"[cal] Continue rotation for %1 seconds"
).
arg
(
worker_data
->
calibration_interval_perside_seconds
));
_emitVehicleTextMessage
(
QString
Literal
(
"[cal] Continue rotation for %1 seconds"
).
arg
(
worker_data
->
calibration_interval_perside_seconds
));
uint64_t
calibration_deadline
=
QGC
::
groundTimeUsecs
()
+
worker_data
->
calibration_interval_perside_useconds
;
...
...
@@ -212,7 +212,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::mag_calibration_worker(detect
calibration_counter_side
++
;
// Progress indicator for side
_emitVehicleTextMessage
(
QString
(
"[cal] %1 side calibration: progress <%2>"
).
arg
(
detect_orientation_str
(
orientation
)).
arg
(
progress_percentage
(
worker_data
)
+
_emitVehicleTextMessage
(
QString
Literal
(
"[cal] %1 side calibration: progress <%2>"
).
arg
(
detect_orientation_str
(
orientation
)).
arg
(
progress_percentage
(
worker_data
)
+
(
unsigned
)((
100
/
calibration_sides
)
*
((
float
)
calibration_counter_side
/
(
float
)
worker_data
->
calibration_points_perside
))));
}
...
...
@@ -220,10 +220,10 @@ CalWorkerThread::calibrate_return CalWorkerThread::mag_calibration_worker(detect
}
if
(
result
==
calibrate_return_ok
)
{
_emitVehicleTextMessage
(
QString
(
"[cal] %1 side done, rotate to a different side"
).
arg
(
detect_orientation_str
(
orientation
)));
_emitVehicleTextMessage
(
QString
Literal
(
"[cal] %1 side done, rotate to a different side"
).
arg
(
detect_orientation_str
(
orientation
)));
worker_data
->
done_count
++
;
_emitVehicleTextMessage
(
QString
(
"[cal] progress <%1>"
).
arg
(
progress_percentage
(
worker_data
)));
_emitVehicleTextMessage
(
QString
Literal
(
"[cal] progress <%1>"
).
arg
(
progress_percentage
(
worker_data
)));
}
return
result
;
...
...
@@ -268,7 +268,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate_from_orientation(
strcat
(
pendingStr
,
detect_orientation_str
((
enum
detect_orientation_return
)
cur_orientation
));
}
}
_emitVehicleTextMessage
(
QString
(
"[cal] pending:%1"
).
arg
(
pendingStr
));
_emitVehicleTextMessage
(
QString
Literal
(
"[cal] pending:%1"
).
arg
(
pendingStr
));
_emitVehicleTextMessage
(
QStringLiteral
(
"[cal] hold vehicle still on a pending side"
));
enum
detect_orientation_return
orient
=
detect_orientation
();
...
...
@@ -282,12 +282,12 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate_from_orientation(
/* inform user about already handled side */
if
(
side_data_collected
[
orient
])
{
orientation_failures
++
;
_emitVehicleTextMessage
(
QString
(
"%1 side already completed"
).
arg
(
detect_orientation_str
(
orient
)));
_emitVehicleTextMessage
(
QString
Literal
(
"%1 side already completed"
).
arg
(
detect_orientation_str
(
orient
)));
_emitVehicleTextMessage
(
QStringLiteral
(
"rotate to a pending side"
));
continue
;
}
_emitVehicleTextMessage
(
QString
(
"[cal] %1 orientation detected"
).
arg
(
detect_orientation_str
(
orient
)));
_emitVehicleTextMessage
(
QString
Literal
(
"[cal] %1 orientation detected"
).
arg
(
detect_orientation_str
(
orient
)));
orientation_failures
=
0
;
// Call worker routine
...
...
@@ -296,7 +296,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate_from_orientation(
break
;
}
_emitVehicleTextMessage
(
QString
(
"[cal] %1 side done, rotate to a different side"
).
arg
(
detect_orientation_str
(
orient
)));
_emitVehicleTextMessage
(
QString
Literal
(
"[cal] %1 side done, rotate to a different side"
).
arg
(
detect_orientation_str
(
orient
)));
// Note that this side is complete
side_data_collected
[
orient
]
=
true
;
...
...
@@ -607,7 +607,7 @@ void APMCompassCal::startCalibration(void)
connect
(
_vehicle
,
&
Vehicle
::
mavlinkScaledImu3
,
this
,
&
APMCompassCal
::
_handleMavlinkScaledImu3
);
// Simulate a start message
_emitVehicleTextMessage
(
"[cal] calibration started: mag"
);
_emitVehicleTextMessage
(
QStringLiteral
(
"[cal] calibration started: mag"
)
);
_calWorkerThread
=
new
CalWorkerThread
(
_vehicle
);
connect
(
_calWorkerThread
,
&
CalWorkerThread
::
vehicleTextMessage
,
this
,
&
APMCompassCal
::
vehicleTextMessage
);
...
...
@@ -650,7 +650,7 @@ void APMCompassCal::cancelCalibration(void)
}
// Simulate a cancelled message
_emitVehicleTextMessage
(
"[cal] calibration cancelled"
);
_emitVehicleTextMessage
(
QStringLiteral
(
"[cal] calibration cancelled"
)
);
}
void
APMCompassCal
::
_handleMavlinkRawImu
(
mavlink_message_t
message
)
...
...
src/AutoPilotPlugins/APM/APMFlightModesComponentController.cc
View file @
773c9bd9
...
...
@@ -18,8 +18,8 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
:
_activeFlightMode
(
0
)
,
_channelCount
(
Vehicle
::
cMaxRcChannels
)
{
_modeParamPrefix
=
_vehicle
->
rover
()
?
"MODE"
:
"FLTMODE"
;
_modeChannelParam
=
_vehicle
->
rover
()
?
"MODE_CH"
:
"FLTMODE_CH"
;
_modeParamPrefix
=
_vehicle
->
rover
()
?
QStringLiteral
(
"MODE"
)
:
QStringLiteral
(
"FLTMODE"
)
;
_modeChannelParam
=
_vehicle
->
rover
()
?
QStringLiteral
(
"MODE_CH"
)
:
QStringLiteral
(
"FLTMODE_CH"
)
;
QStringList
usedParams
;
for
(
int
i
=
1
;
i
<
7
;
i
++
)
{
...
...
src/AutoPilotPlugins/APM/APMPowerComponent.cc
View file @
773c9bd9
...
...
@@ -15,7 +15,7 @@
APMPowerComponent
::
APMPowerComponent
(
Vehicle
*
vehicle
,
AutoPilotPlugin
*
autopilot
,
QObject
*
parent
)
:
VehicleComponent
(
vehicle
,
autopilot
,
parent
),
_name
(
"Power"
)
_name
(
tr
(
"Power"
)
)
{
}
...
...
src/AutoPilotPlugins/APM/APMRadioComponent.cc
View file @
773c9bd9
...
...
@@ -66,13 +66,13 @@ bool APMRadioComponent::setupComplete(void) const
// Next check RC#_MIN/MAX/TRIM all at defaults
foreach
(
const
QString
&
mapParam
,
_mapParams
)
{
int
channel
=
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
mapParam
)
->
rawValue
().
toInt
();
if
(
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
QString
(
"RC%1_MIN"
).
arg
(
channel
))
->
rawValue
().
toInt
()
!=
1100
)
{
if
(
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
QString
Literal
(
"RC%1_MIN"
).
arg
(
channel
))
->
rawValue
().
toInt
()
!=
1100
)
{
return
true
;
}
if
(
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
QString
(
"RC%1_MAX"
).
arg
(
channel
))
->
rawValue
().
toInt
()
!=
1900
)
{
if
(
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
QString
Literal
(
"RC%1_MAX"
).
arg
(
channel
))
->
rawValue
().
toInt
()
!=
1900
)
{
return
true
;
}
if
(
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
QString
(
"RC%1_TRIM"
).
arg
(
channel
))
->
rawValue
().
toInt
()
!=
1500
)
{
if
(
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
QString
Literal
(
"RC%1_TRIM"
).
arg
(
channel
))
->
rawValue
().
toInt
()
!=
1500
)
{
return
true
;
}
}
...
...
@@ -108,15 +108,15 @@ void APMRadioComponent::_connectSetupTriggers(void)
foreach
(
const
QString
&
mapParam
,
_mapParams
)
{
int
channel
=
_vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
mapParam
)
->
rawValue
().
toInt
();
Fact
*
fact
=
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
QString
(
"RC%1_MIN"
).
arg
(
channel
));
Fact
*
fact
=
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
QString
Literal
(
"RC%1_MIN"
).
arg
(
channel
));
_triggerFacts
<<
fact
;
connect
(
fact
,
&
Fact
::
valueChanged
,
this
,
&
APMRadioComponent
::
_triggerChanged
);
fact
=
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
QString
(
"RC%1_MAX"
).
arg
(
channel
));
fact
=
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
QString
Literal
(
"RC%1_MAX"
).
arg
(
channel
));
_triggerFacts
<<
fact
;
connect
(
fact
,
&
Fact
::
valueChanged
,
this
,
&
APMRadioComponent
::
_triggerChanged
);
fact
=
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
QString
(
"RC%1_TRIM"
).
arg
(
channel
));
fact
=
_vehicle
->
parameterManager
()
->
getParameter
(
-
1
,
QString
Literal
(
"RC%1_TRIM"
).
arg
(
channel
));
_triggerFacts
<<
fact
;
connect
(
fact
,
&
Fact
::
valueChanged
,
this
,
&
APMRadioComponent
::
_triggerChanged
);
}
...
...
src/AutoPilotPlugins/APM/APMSensorsComponent.cc
View file @
773c9bd9
...
...
@@ -53,14 +53,14 @@ QStringList APMSensorsComponent::setupCompleteChangedTriggerList(void) const
QStringList
triggers
;
// Compass triggers
triggers
<<
"COMPASS_DEV_ID"
<<
"COMPASS_DEV_ID2"
<<
"COMPASS_DEV_ID3"
<<
"COMPASS_USE"
<<
"COMPASS_USE2"
<<
"COMPASS_USE3"
<<
"COMPASS_OFS_X"
<<
"COMPASS_OFS_X"
<<
"COMPASS_OFS_X"
<<
"COMPASS_OFS2_X"
<<
"COMPASS_OFS2_X"
<<
"COMPASS_OFS2_X"
<<
"COMPASS_OFS3_X"
<<
"COMPASS_OFS3_X"
<<
"COMPASS_OFS3_X"
;
triggers
<<
QStringLiteral
(
"COMPASS_DEV_ID"
)
<<
QStringLiteral
(
"COMPASS_DEV_ID2"
)
<<
QStringLiteral
(
"COMPASS_DEV_ID3"
)
<<
QStringLiteral
(
"COMPASS_USE"
)
<<
QStringLiteral
(
"COMPASS_USE2"
)
<<
QStringLiteral
(
"COMPASS_USE3"
)
<<
QStringLiteral
(
"COMPASS_OFS_X"
)
<<
QStringLiteral
(
"COMPASS_OFS_X"
)
<<
QStringLiteral
(
"COMPASS_OFS_X"
)
<<
QStringLiteral
(
"COMPASS_OFS2_X"
)
<<
QStringLiteral
(
"COMPASS_OFS2_X"
)
<<
QStringLiteral
(
"COMPASS_OFS2_X"
)
<<
QStringLiteral
(
"COMPASS_OFS3_X"
)
<<
QStringLiteral
(
"COMPASS_OFS3_X"
)
<<
QStringLiteral
(
"COMPASS_OFS3_X"
)
;
// Accelerometer triggers
triggers
<<
"INS_ACCOFFS_X"
<<
"INS_ACCOFFS_Y"
<<
"INS_ACCOFFS_Z"
;
triggers
<<
QStringLiteral
(
"INS_ACCOFFS_X"
)
<<
QStringLiteral
(
"INS_ACCOFFS_Y"
)
<<
QStringLiteral
(
"INS_ACCOFFS_Z"
)
;
return
triggers
;
}
...
...
src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
View file @
773c9bd9
...
...
@@ -179,7 +179,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll
switch
(
code
)
{
case
StopCalibrationSuccess
:
_orientationCalAreaHelpText
->
setProperty
(
"text"
,
"Calibration complete"
);
_orientationCalAreaHelpText
->
setProperty
(
"text"
,
tr
(
"Calibration complete"
)
);
emit
resetStatusTextArea
();
emit
calibrationComplete
(
_calTypeInProgress
);
break
;
...
...
@@ -226,7 +226,7 @@ void APMSensorsComponentController::_mavCommandResult(int vehicleId, int compone
_startLogCalibration
();
uint8_t
compassBits
=
0
;
if
(
getParameterFact
(
FactSystem
::
defaultComponentId
,
"COMPASS_DEV_ID"
)
->
rawValue
().
toInt
()
>
0
)
{
if
(
getParameterFact
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"COMPASS_DEV_ID"
)
)
->
rawValue
().
toInt
()
>
0
)
{
compassBits
|=
1
<<
0
;
qCDebug
(
APMSensorsComponentControllerLog
)
<<
"Performing onboard compass cal for compass 1"
;
}
else
{
...
...
@@ -234,7 +234,7 @@ void APMSensorsComponentController::_mavCommandResult(int vehicleId, int compone
_rgCompassCalSucceeded
[
0
]
=
true
;
_rgCompassCalFitness
[
0
]
=
0
;
}
if
(
getParameterFact
(
FactSystem
::
defaultComponentId
,
"COMPASS_DEV_ID2"
)
->
rawValue
().
toInt
()
>
0
)
{
if
(
getParameterFact
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"COMPASS_DEV_ID2"
)
)
->
rawValue
().
toInt
()
>
0
)
{
compassBits
|=
1
<<
1
;
qCDebug
(
APMSensorsComponentControllerLog
)
<<
"Performing onboard compass cal for compass 2"
;
}
else
{
...
...
@@ -242,7 +242,7 @@ void APMSensorsComponentController::_mavCommandResult(int vehicleId, int compone
_rgCompassCalSucceeded
[
1
]
=
true
;
_rgCompassCalFitness
[
1
]
=
0
;
}
if
(
getParameterFact
(
FactSystem
::
defaultComponentId
,
"COMPASS_DEV_ID3"
)
->
rawValue
().
toInt
()
>
0
)
{
if
(
getParameterFact
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"COMPASS_DEV_ID3"
)
)
->
rawValue
().
toInt
()
>
0
)
{
compassBits
|=
1
<<
2
;
qCDebug
(
APMSensorsComponentControllerLog
)
<<
"Performing onboard compass cal for compass 3"
;
}
else
{
...
...
src/AutoPilotPlugins/APM/APMTuningComponent.cc
View file @
773c9bd9
...
...
@@ -15,7 +15,7 @@
APMTuningComponent
::
APMTuningComponent
(
Vehicle
*
vehicle
,
AutoPilotPlugin
*
autopilot
,
QObject
*
parent
)
:
VehicleComponent
(
vehicle
,
autopilot
,
parent
)
,
_name
(
"Tuning"
)
,
_name
(
tr
(
"Tuning"
)
)
{
}
...
...
src/AutoPilotPlugins/AutoPilotPlugin.cc
View file @
773c9bd9
...
...
@@ -62,7 +62,7 @@ void AutoPilotPlugin::parametersReadyPreChecks(void)
{
_recalcSetupComplete
();
if
(
!
_setupComplete
)
{
qgcApp
()
->
showMessage
(
"One or more vehicle components require setup prior to flight."
);
qgcApp
()
->
showMessage
(
tr
(
"One or more vehicle components require setup prior to flight."
)
);
// Take the user to Vehicle Summary
qgcApp
()
->
showSetupView
();
...
...
src/AutoPilotPlugins/Common/ESP8266ComponentController.cc
View file @
773c9bd9
This diff is collapsed.
Click to expand it.
src/AutoPilotPlugins/Common/RadioComponentController.cc
View file @
773c9bd9
...
...
@@ -791,8 +791,8 @@ void RadioComponentController::_writeCalibration(void)
if
(
_px4Vehicle
())
{
// If the RC_CHAN_COUNT parameter is available write the channel count
if
(
parameterExists
(
FactSystem
::
defaultComponentId
,
"RC_CHAN_CNT"
))
{
getParameterFact
(
FactSystem
::
defaultComponentId
,
"RC_CHAN_CNT"
)
->
setRawValue
(
_chanCount
);
if
(
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"RC_CHAN_CNT"
)
))
{
getParameterFact
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"RC_CHAN_CNT"
)
)
->
setRawValue
(
_chanCount
);
}
}
...
...
@@ -815,7 +815,7 @@ void RadioComponentController::_startCalibration(void)
_uas
->
startCalibration
(
UASInterface
::
StartCalibrationRadio
);
}
_nextButton
->
setProperty
(
"text"
,
"Next"
);
_nextButton
->
setProperty
(
"text"
,
tr
(
"Next"
)
);
_cancelButton
->
setEnabled
(
true
);
_currentStep
=
0
;
...
...
@@ -838,7 +838,7 @@ void RadioComponentController::_stopCalibration(void)
_statusText
->
setProperty
(
"text"
,
""
);
_nextButton
->
setProperty
(
"text"
,
"Calibrate"
);
_nextButton
->
setProperty
(
"text"
,
tr
(
"Calibrate"
)
);
_nextButton
->
setEnabled
(
true
);
_cancelButton
->
setEnabled
(
false
);
_skipButton
->
setEnabled
(
false
);
...
...
@@ -861,8 +861,8 @@ void RadioComponentController::_rcCalSave(void)
_rcCalState
=
rcCalStateSave
;
_statusText
->
setProperty
(
"text"
,
"The current calibration settings are now displayed for each channel on screen.
\n\n
"
"Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values."
);
tr
(
"The current calibration settings are now displayed for each channel on screen.
\n\n
"
"Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values."
)
)
;
_nextButton
->
setEnabled
(
true
);
_skipButton
->
setEnabled
(
false
);
...
...
src/AutoPilotPlugins/Common/SyslinkComponentController.cc
View file @
773c9bd9
...
...
@@ -20,17 +20,17 @@ QGC_LOGGING_CATEGORY(SyslinkComponentControllerLog, "SyslinkComponentControllerL
//-----------------------------------------------------------------------------
SyslinkComponentController
::
SyslinkComponentController
()
{
_dataRates
.
append
(
"750Kb/s"
);
_dataRates
.
append
(
"1Mb/s"
);
_dataRates
.
append
(
"2Mb/s"
);
_dataRates
.
append
(
QStringLiteral
(
"750Kb/s"
)
);
_dataRates
.
append
(
QStringLiteral
(
"1Mb/s"
)
);
_dataRates
.
append
(
QStringLiteral
(
"2Mb/s"
)
);
Fact
*
chan
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_CHAN"
);
Fact
*
chan
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_CHAN"
)
);
connect
(
chan
,
&
Fact
::
valueChanged
,
this
,
&
SyslinkComponentController
::
_channelChanged
);
Fact
*
rate
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_RATE"
);
Fact
*
rate
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_RATE"
)
);
connect
(
rate
,
&
Fact
::
valueChanged
,
this
,
&
SyslinkComponentController
::
_rateChanged
);
Fact
*
addr1
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_ADDR1"
);
Fact
*
addr1
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_ADDR1"
)
);
connect
(
addr1
,
&
Fact
::
valueChanged
,
this
,
&
SyslinkComponentController
::
_addressChanged
);
Fact
*
addr2
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_ADDR2"
);
Fact
*
addr2
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_ADDR2"
)
);
connect
(
addr2
,
&
Fact
::
valueChanged
,
this
,
&
SyslinkComponentController
::
_addressChanged
);
}
...
...
@@ -44,14 +44,14 @@ SyslinkComponentController::~SyslinkComponentController()
int
SyslinkComponentController
::
radioChannel
()
{
return
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_CHAN"
)
->
rawValue
().
toUInt
();
return
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_CHAN"
)
)
->
rawValue
().
toUInt
();
}
//-----------------------------------------------------------------------------
void
SyslinkComponentController
::
setRadioChannel
(
int
num
)
{
Fact
*
f
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_CHAN"
);
Fact
*
f
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_CHAN"
)
);
f
->
setRawValue
(
QVariant
(
num
));
}
...
...
@@ -59,8 +59,8 @@ SyslinkComponentController::setRadioChannel(int num)
QString
SyslinkComponentController
::
radioAddress
()
{
uint32_t
val_uh
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_ADDR1"
)
->
rawValue
().
toUInt
();
uint32_t
val_lh
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_ADDR2"
)
->
rawValue
().
toUInt
();
uint32_t
val_uh
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_ADDR1"
)
)
->
rawValue
().
toUInt
();
uint32_t
val_lh
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_ADDR2"
)
)
->
rawValue
().
toUInt
();
uint64_t
val
=
(((
uint64_t
)
val_uh
)
<<
32
)
|
((
uint64_t
)
val_lh
);
return
QString
().
number
(
val
,
16
);
...
...
@@ -70,8 +70,8 @@ SyslinkComponentController::radioAddress()
void
SyslinkComponentController
::
setRadioAddress
(
QString
str
)
{
Fact
*
uh
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_ADDR1"
);
Fact
*
lh
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_ADDR2"
);
Fact
*
uh
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_ADDR1"
)
);
Fact
*
lh
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_ADDR2"
)
);
uint64_t
val
=
str
.
toULongLong
(
0
,
16
);
...
...
@@ -86,7 +86,7 @@ SyslinkComponentController::setRadioAddress(QString str)
int
SyslinkComponentController
::
radioRate
()
{
return
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_RATE"
)
->
rawValue
().
toInt
();
return
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_RATE"
)
)
->
rawValue
().
toInt
();
}
//-----------------------------------------------------------------------------
...
...
@@ -94,7 +94,7 @@ void
SyslinkComponentController
::
setRadioRate
(
int
idx
)
{
if
(
idx
>=
0
&&
idx
<=
2
&&
idx
!=
radioRate
())
{
Fact
*
r
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_RATE"
);
Fact
*
r
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_RATE"
)
);
r
->
setRawValue
(
idx
);
}
}
...
...
@@ -103,10 +103,10 @@ SyslinkComponentController::setRadioRate(int idx)
void
SyslinkComponentController
::
resetDefaults
()
{
Fact
*
chan
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_CHAN"
);
Fact
*
rate
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_RATE"
);
Fact
*
addr1
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_ADDR1"
);
Fact
*
addr2
=
getParameterFact
(
_vehicle
->
id
(),
"SLNK_RADIO_ADDR2"
);
Fact
*
chan
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_CHAN"
)
);
Fact
*
rate
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_RATE"
)
);
Fact
*
addr1
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_ADDR1"
)
);
Fact
*
addr2
=
getParameterFact
(
_vehicle
->
id
(),
QStringLiteral
(
"SLNK_RADIO_ADDR2"
)
);
chan
->
setRawValue
(
chan
->
rawDefaultValue
());
rate
->
setRawValue
(
rate
->
rawDefaultValue
());
...
...
src/AutoPilotPlugins/PX4/AirframeComponent.cc
View file @
773c9bd9
...
...
@@ -45,12 +45,12 @@ bool AirframeComponent::requiresSetup(void) const
bool
AirframeComponent
::
setupComplete
(
void
)
const
{
return
_vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
"SYS_AUTOSTART"
)
->
rawValue
().
toInt
()
!=
0
;
return
_vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"SYS_AUTOSTART"
)
)
->
rawValue
().
toInt
()
!=
0
;
}
QStringList
AirframeComponent
::
setupCompleteChangedTriggerList
(
void
)
const
{
return
QStringList
(
"SYS_AUTOSTART"
);
return
QStringList
(
QStringLiteral
(
"SYS_AUTOSTART"
)
);
}
QUrl
AirframeComponent
::
setupSource
(
void
)
const
...
...
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