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
0303f53a
Commit
0303f53a
authored
Oct 27, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Support correct parameter set for APM
parent
d44fcde4
Changes
9
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
9 changed files
with
1276 additions
and
53 deletions
+1276
-53
qgroundcontrol.qrc
qgroundcontrol.qrc
+3
-1
APMArduCopterMockLink.params
src/comm/APMArduCopterMockLink.params
+506
-0
APMArduPlaneMockLink.params
src/comm/APMArduPlaneMockLink.params
+587
-0
MockLink.cc
src/comm/MockLink.cc
+119
-48
MockLink.h
src/comm/MockLink.h
+8
-2
PX4MockLink.params
src/comm/PX4MockLink.params
+0
-0
MockLinkConfiguration.cc
src/ui/MockLinkConfiguration.cc
+26
-0
MockLinkConfiguration.h
src/ui/MockLinkConfiguration.h
+2
-0
MockLinkConfiguration.ui
src/ui/MockLinkConfiguration.ui
+25
-2
No files found.
qgroundcontrol.qrc
View file @
0303f53a
<RCC>
<qresource prefix="/unittest">
<file alias="MockLink.params">src/comm/MockLink.params</file>
<file alias="PX4MockLink.params">src/comm/PX4MockLink.params</file>
<file alias="APMArduCopterMockLink.params">src/comm/APMArduCopterMockLink.params</file>
<file alias="APMArduPlaneMockLink.params">src/comm/APMArduPlaneMockLink.params</file>
<file alias="FactSystemTest.qml">src/FactSystem/FactSystemTest.qml</file>
</qresource>
<qresource prefix="/qml">
...
...
src/comm/APMArduCopterMockLink.params
0 → 100644
View file @
0303f53a
This diff is collapsed.
Click to expand it.
src/comm/APMArduPlaneMockLink.params
0 → 100644
View file @
0303f53a
This diff is collapsed.
Click to expand it.
src/comm/MockLink.cc
View file @
0303f53a
...
...
@@ -72,6 +72,7 @@ float MockLink::_vehicleLongitude = -122.08794f;
float
MockLink
::
_vehicleAltitude
=
2.5
f
;
const
char
*
MockConfiguration
::
_firmwareTypeKey
=
"FirmwareType"
;
const
char
*
MockConfiguration
::
_vehicleTypeKey
=
"VehicleType"
;
const
char
*
MockConfiguration
::
_sendStatusTextKey
=
"SendStatusText"
;
MockLink
::
MockLink
(
MockConfiguration
*
config
)
...
...
@@ -85,6 +86,7 @@ MockLink::MockLink(MockConfiguration* config)
,
_mavBaseMode
(
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
|
MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
)
,
_mavState
(
MAV_STATE_STANDBY
)
,
_firmwareType
(
MAV_AUTOPILOT_PX4
)
,
_vehicleType
(
MAV_TYPE_QUADROTOR
)
,
_fileServer
(
NULL
)
,
_sendStatusText
(
false
)
,
_apmSendHomePositionOnEmptyList
(
false
)
...
...
@@ -93,6 +95,7 @@ MockLink::MockLink(MockConfiguration* config)
_config
=
config
;
if
(
_config
)
{
_firmwareType
=
config
->
firmwareType
();
_vehicleType
=
config
->
vehicleType
();
_sendStatusText
=
config
->
sendStatusText
();
}
...
...
@@ -113,7 +116,6 @@ MockLink::MockLink(MockConfiguration* config)
MockLink
::~
MockLink
(
void
)
{
qDebug
()
<<
"MockLink destructor"
;
_disconnect
();
}
...
...
@@ -200,7 +202,18 @@ void MockLink::_run50HzTasks(void)
void
MockLink
::
_loadParams
(
void
)
{
QFile
paramFile
(
":/unittest/MockLink.params"
);
QFile
paramFile
;
if
(
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
if
(
_vehicleType
==
MAV_TYPE_FIXED_WING
)
{
paramFile
.
setFileName
(
":/unittest/APMArduPlaneMockLink.params"
);
}
else
{
paramFile
.
setFileName
(
":/unittest/APMArduCopterMockLink.params"
);
}
}
else
{
paramFile
.
setFileName
(
":/unittest/PX4MockLink.params"
);
}
bool
success
=
paramFile
.
open
(
QFile
::
ReadOnly
);
Q_UNUSED
(
success
);
...
...
@@ -234,11 +247,21 @@ void MockLink::_loadParams(void)
case
MAV_PARAM_TYPE_INT32
:
paramValue
=
QVariant
(
valStr
.
toInt
());
break
;
case
MAV_PARAM_TYPE_UINT16
:
paramValue
=
QVariant
((
quint16
)
valStr
.
toUInt
());
break
;
case
MAV_PARAM_TYPE_INT16
:
paramValue
=
QVariant
((
qint16
)
valStr
.
toInt
());
break
;
case
MAV_PARAM_TYPE_UINT8
:
paramValue
=
QVariant
((
quint8
)
valStr
.
toUInt
());
break
;
case
MAV_PARAM_TYPE_INT8
:
paramValue
=
QVariant
((
unsigned
char
)
valStr
.
toUInt
());
paramValue
=
QVariant
((
qint8
)
valStr
.
toUInt
());
break
;
default:
Q_ASSERT
(
false
);
qCritical
()
<<
"Unknown type"
<<
paramType
;
paramValue
=
QVariant
(
valStr
.
toInt
());
break
;
}
...
...
@@ -405,24 +428,38 @@ void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramN
QVariant
paramVariant
;
switch
(
paramType
)
{
case
MAV_PARAM_TYPE_INT8
:
paramVariant
=
QVariant
::
fromValue
(
valueUnion
.
param_int8
);
break
;
case
MAV_PARAM_TYPE_INT32
:
paramVariant
=
QVariant
::
fromValue
(
valueUnion
.
param_int32
);
break
;
case
MAV_PARAM_TYPE_UINT32
:
paramVariant
=
QVariant
::
fromValue
(
valueUnion
.
param_uint32
);
break
;
case
MAV_PARAM_TYPE_REAL32
:
paramVariant
=
QVariant
::
fromValue
(
valueUnion
.
param_float
);
break
;
default:
qCritical
()
<<
"Invalid parameter type"
<<
paramType
;
case
MAV_PARAM_TYPE_REAL32
:
paramVariant
=
QVariant
::
fromValue
(
valueUnion
.
param_float
);
break
;
case
MAV_PARAM_TYPE_UINT32
:
paramVariant
=
QVariant
::
fromValue
(
valueUnion
.
param_uint32
);
break
;
case
MAV_PARAM_TYPE_INT32
:
paramVariant
=
QVariant
::
fromValue
(
valueUnion
.
param_int32
);
break
;
case
MAV_PARAM_TYPE_UINT16
:
paramVariant
=
QVariant
::
fromValue
(
valueUnion
.
param_uint16
);
break
;
case
MAV_PARAM_TYPE_INT16
:
paramVariant
=
QVariant
::
fromValue
(
valueUnion
.
param_int16
);
break
;
case
MAV_PARAM_TYPE_UINT8
:
paramVariant
=
QVariant
::
fromValue
(
valueUnion
.
param_uint8
);
break
;
case
MAV_PARAM_TYPE_INT8
:
paramVariant
=
QVariant
::
fromValue
(
valueUnion
.
param_int8
);
break
;
default:
qCritical
()
<<
"Invalid parameter type"
<<
paramType
;
paramVariant
=
QVariant
::
fromValue
(
valueUnion
.
param_int32
);
break
;
}
qCDebug
(
MockLinkLog
)
<<
"_setParamFloatUnionIntoMap"
<<
paramName
<<
paramVariant
;
...
...
@@ -442,36 +479,65 @@ float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
QVariant
paramVar
=
_mapParamName2Value
[
componentId
][
paramName
];
switch
(
paramType
)
{
case
MAV_PARAM_TYPE_INT8
:
if
(
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
valueUnion
.
param_float
=
(
unsigned
char
)
paramVar
.
toChar
().
toLatin1
();
}
else
{
valueUnion
.
param_int8
=
(
unsigned
char
)
paramVar
.
toChar
().
toLatin1
();
}
break
;
case
MAV_PARAM_TYPE_REAL32
:
valueUnion
.
param_float
=
paramVar
.
toFloat
();
break
;
case
MAV_PARAM_TYPE_
INT32
:
if
(
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
valueUnion
.
param_float
=
paramVar
.
to
Int
();
}
else
{
valueUnion
.
param_int32
=
paramVar
.
to
Int
();
}
break
;
case
MAV_PARAM_TYPE_U
INT32
:
if
(
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
valueUnion
.
param_float
=
paramVar
.
toU
Int
();
}
else
{
valueUnion
.
param_uint32
=
paramVar
.
toU
Int
();
}
break
;
case
MAV_PARAM_TYPE_U
INT32
:
if
(
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
valueUnion
.
param_float
=
paramVar
.
toU
Int
();
}
else
{
valueUnion
.
param_uint32
=
paramVar
.
toU
Int
();
}
break
;
case
MAV_PARAM_TYPE_
INT32
:
if
(
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
valueUnion
.
param_float
=
paramVar
.
to
Int
();
}
else
{
valueUnion
.
param_int32
=
paramVar
.
to
Int
();
}
break
;
case
MAV_PARAM_TYPE_REAL32
:
valueUnion
.
param_float
=
paramVar
.
toFloat
();
break
;
case
MAV_PARAM_TYPE_UINT16
:
if
(
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
valueUnion
.
param_float
=
paramVar
.
toUInt
();
}
else
{
valueUnion
.
param_uint16
=
paramVar
.
toUInt
();
}
break
;
default:
qCritical
()
<<
"Invalid parameter type"
<<
paramType
;
case
MAV_PARAM_TYPE_INT16
:
if
(
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
valueUnion
.
param_float
=
paramVar
.
toInt
();
}
else
{
valueUnion
.
param_int16
=
paramVar
.
toInt
();
}
break
;
case
MAV_PARAM_TYPE_UINT8
:
if
(
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
valueUnion
.
param_float
=
paramVar
.
toUInt
();
}
else
{
valueUnion
.
param_uint8
=
paramVar
.
toUInt
();
}
break
;
case
MAV_PARAM_TYPE_INT8
:
if
(
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
valueUnion
.
param_float
=
(
unsigned
char
)
paramVar
.
toChar
().
toLatin1
();
}
else
{
valueUnion
.
param_int8
=
(
unsigned
char
)
paramVar
.
toChar
().
toLatin1
();
}
break
;
default:
if
(
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
valueUnion
.
param_float
=
paramVar
.
toInt
();
}
else
{
valueUnion
.
param_int32
=
paramVar
.
toInt
();
}
qCritical
()
<<
"Invalid parameter type"
<<
paramType
;
}
return
valueUnion
.
param_float
;
...
...
@@ -801,6 +867,7 @@ void MockLink::_sendStatusTextMessages(void)
MockConfiguration
::
MockConfiguration
(
const
QString
&
name
)
:
LinkConfiguration
(
name
)
,
_firmwareType
(
MAV_AUTOPILOT_PX4
)
,
_vehicleType
(
MAV_TYPE_QUADROTOR
)
,
_sendStatusText
(
false
)
{
...
...
@@ -810,6 +877,7 @@ MockConfiguration::MockConfiguration(MockConfiguration* source)
:
LinkConfiguration
(
source
)
{
_firmwareType
=
source
->
_firmwareType
;
_vehicleType
=
source
->
_vehicleType
;
_sendStatusText
=
source
->
_sendStatusText
;
}
...
...
@@ -824,6 +892,7 @@ void MockConfiguration::copyFrom(LinkConfiguration *source)
}
_firmwareType
=
usource
->
_firmwareType
;
_vehicleType
=
usource
->
_vehicleType
;
_sendStatusText
=
usource
->
_sendStatusText
;
}
...
...
@@ -831,6 +900,7 @@ void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
settings
.
beginGroup
(
root
);
settings
.
setValue
(
_firmwareTypeKey
,
(
int
)
_firmwareType
);
settings
.
setValue
(
_vehicleTypeKey
,
(
int
)
_vehicleType
);
settings
.
setValue
(
_sendStatusTextKey
,
_sendStatusText
);
settings
.
sync
();
settings
.
endGroup
();
...
...
@@ -840,6 +910,7 @@ void MockConfiguration::loadSettings(QSettings& settings, const QString& root)
{
settings
.
beginGroup
(
root
);
_firmwareType
=
(
MAV_AUTOPILOT
)
settings
.
value
(
_firmwareTypeKey
,
(
int
)
MAV_AUTOPILOT_PX4
).
toInt
();
_vehicleType
=
(
MAV_TYPE
)
settings
.
value
(
_vehicleTypeKey
,
(
int
)
MAV_TYPE_QUADROTOR
).
toInt
();
_sendStatusText
=
settings
.
value
(
_sendStatusTextKey
,
false
).
toBool
();
settings
.
endGroup
();
}
...
...
src/comm/MockLink.h
View file @
0303f53a
...
...
@@ -44,6 +44,9 @@ public:
MAV_AUTOPILOT
firmwareType
(
void
)
{
return
_firmwareType
;
}
void
setFirmwareType
(
MAV_AUTOPILOT
firmwareType
)
{
_firmwareType
=
firmwareType
;
}
MAV_TYPE
vehicleType
(
void
)
{
return
_vehicleType
;
}
void
setVehicleType
(
MAV_TYPE
vehicleType
)
{
_vehicleType
=
vehicleType
;
}
/// @param sendStatusText true: mavlink status text messages will be sent for each severity, as well as voice output info message
void
setSendStatusText
(
bool
sendStatusText
)
{
_sendStatusText
=
sendStatusText
;
}
bool
sendStatusText
(
void
)
{
return
_sendStatusText
;
}
...
...
@@ -57,9 +60,11 @@ public:
private:
MAV_AUTOPILOT
_firmwareType
;
MAV_TYPE
_vehicleType
;
bool
_sendStatusText
;
static
const
char
*
_firmwareTypeKey
;
static
const
char
*
_vehicleTypeKey
;
static
const
char
*
_sendStatusTextKey
;
};
...
...
@@ -183,8 +188,9 @@ private:
uint32_t
_mavCustomMode
;
uint8_t
_mavState
;
MockConfiguration
*
_config
;
MAV_AUTOPILOT
_firmwareType
;
MockConfiguration
*
_config
;
MAV_AUTOPILOT
_firmwareType
;
MAV_TYPE
_vehicleType
;
MockLinkFileServer
*
_fileServer
;
...
...
src/comm/MockLink.params
→
src/comm/
PX4
MockLink.params
View file @
0303f53a
File moved
src/ui/MockLinkConfiguration.cc
View file @
0303f53a
...
...
@@ -43,11 +43,23 @@ MockLinkConfiguration::MockLinkConfiguration(MockConfiguration *config, QWidget
break
;
}
switch
(
config
->
vehicleType
())
{
case
MAV_TYPE_FIXED_WING
:
_ui
->
apmArduPlaneRadio
->
setChecked
(
true
);
break
;
default:
_ui
->
apmArduCopterRadio
->
setChecked
(
true
);
break
;
}
_ui
->
sendStatusTextCheckBox
->
setChecked
(
config
->
sendStatusText
());
connect
(
_ui
->
px4Radio
,
&
QRadioButton
::
clicked
,
this
,
&
MockLinkConfiguration
::
_px4RadioClicked
);
connect
(
_ui
->
apmRadio
,
&
QRadioButton
::
clicked
,
this
,
&
MockLinkConfiguration
::
_apmRadioClicked
);
connect
(
_ui
->
genericRadio
,
&
QRadioButton
::
clicked
,
this
,
&
MockLinkConfiguration
::
_genericRadioClicked
);
connect
(
_ui
->
apmArduCopterRadio
,
&
QRadioButton
::
clicked
,
this
,
&
MockLinkConfiguration
::
_apmArduCopterRadioClicked
);
connect
(
_ui
->
apmArduPlaneRadio
,
&
QRadioButton
::
clicked
,
this
,
&
MockLinkConfiguration
::
_apmArduPlaneRadioClicked
);
connect
(
_ui
->
genericRadio
,
&
QRadioButton
::
clicked
,
this
,
&
MockLinkConfiguration
::
_genericRadioClicked
);
connect
(
_ui
->
sendStatusTextCheckBox
,
&
QCheckBox
::
clicked
,
this
,
&
MockLinkConfiguration
::
_sendStatusTextClicked
);
}
...
...
@@ -77,6 +89,20 @@ void MockLinkConfiguration::_genericRadioClicked(bool checked)
}
}
void
MockLinkConfiguration
::
_apmArduCopterRadioClicked
(
bool
checked
)
{
if
(
checked
)
{
_config
->
setVehicleType
(
MAV_TYPE_QUADROTOR
);
}
}
void
MockLinkConfiguration
::
_apmArduPlaneRadioClicked
(
bool
checked
)
{
if
(
checked
)
{
_config
->
setVehicleType
(
MAV_TYPE_FIXED_WING
);
}
}
void
MockLinkConfiguration
::
_sendStatusTextClicked
(
bool
checked
)
{
_config
->
setSendStatusText
(
checked
);
...
...
src/ui/MockLinkConfiguration.h
View file @
0303f53a
...
...
@@ -44,6 +44,8 @@ private slots:
void
_px4RadioClicked
(
bool
checked
);
void
_apmRadioClicked
(
bool
checked
);
void
_genericRadioClicked
(
bool
checked
);
void
_apmArduCopterRadioClicked
(
bool
checked
);
void
_apmArduPlaneRadioClicked
(
bool
checked
);
void
_sendStatusTextClicked
(
bool
checked
);
private:
...
...
src/ui/MockLinkConfiguration.ui
View file @
0303f53a
...
...
@@ -6,8 +6,8 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
187
</width>
<height>
1
16
</height>
<width>
238
</width>
<height>
1
88
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
...
...
@@ -42,6 +42,29 @@
</property>
</widget>
</item>
<item>
<widget
class=
"QGroupBox"
name=
"groupBox"
>
<property
name=
"title"
>
<string>
APM vehicle type
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout"
>
<item>
<widget
class=
"QRadioButton"
name=
"apmArduCopterRadio"
>
<property
name=
"text"
>
<string>
ArduCopter
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QRadioButton"
name=
"apmArduPlaneRadio"
>
<property
name=
"text"
>
<string>
ArduPlane
</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
<resources/>
...
...
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