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
c74d545b
Commit
c74d545b
authored
Apr 09, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Switch to FactSystem for parameters
parent
4c8b3f0f
Changes
9
Hide whitespace changes
Inline
Side-by-side
Showing
9 changed files
with
19 additions
and
60 deletions
+19
-60
AirframeComponent.cc
src/AutoPilotPlugins/PX4/AirframeComponent.cc
+1
-7
FlightModesComponent.cc
src/AutoPilotPlugins/PX4/FlightModesComponent.cc
+1
-7
PX4Component.cc
src/AutoPilotPlugins/PX4/PX4Component.cc
+6
-0
PX4Component.h
src/AutoPilotPlugins/PX4/PX4Component.h
+3
-0
PowerComponent.cc
src/AutoPilotPlugins/PX4/PowerComponent.cc
+3
-9
RadioComponent.cc
src/AutoPilotPlugins/PX4/RadioComponent.cc
+4
-25
SensorsComponent.cc
src/AutoPilotPlugins/PX4/SensorsComponent.cc
+1
-8
VehicleComponent.cc
src/VehicleSetup/VehicleComponent.cc
+0
-3
VehicleComponent.h
src/VehicleSetup/VehicleComponent.h
+0
-1
No files found.
src/AutoPilotPlugins/PX4/AirframeComponent.cc
View file @
c74d545b
...
...
@@ -142,13 +142,7 @@ bool AirframeComponent::requiresSetup(void) const
bool
AirframeComponent
::
setupComplete
(
void
)
const
{
QVariant
value
;
if
(
_paramMgr
->
getParameterValue
(
_paramMgr
->
getDefaultComponentId
(),
"SYS_AUTOSTART"
,
value
))
{
return
value
.
toInt
()
!=
0
;
}
else
{
Q_ASSERT
(
false
);
return
false
;
}
return
_autopilot
->
getParameterFact
(
"SYS_AUTOSTART"
)
->
value
().
toInt
()
!=
0
;
}
QString
AirframeComponent
::
setupStateDescription
(
void
)
const
...
...
src/AutoPilotPlugins/PX4/FlightModesComponent.cc
View file @
c74d545b
...
...
@@ -72,13 +72,7 @@ bool FlightModesComponent::requiresSetup(void) const
bool
FlightModesComponent
::
setupComplete
(
void
)
const
{
QVariant
value
;
if
(
_paramMgr
->
getParameterValue
(
_paramMgr
->
getDefaultComponentId
(),
"RC_MAP_MODE_SW"
,
value
))
{
return
value
.
toInt
()
!=
0
;
}
else
{
Q_ASSERT
(
false
);
return
false
;
}
return
_autopilot
->
getParameterFact
(
"RC_MAP_MODE_SW"
)
->
value
().
toInt
()
!=
0
;
}
QString
FlightModesComponent
::
setupStateDescription
(
void
)
const
...
...
src/AutoPilotPlugins/PX4/PX4Component.cc
View file @
c74d545b
...
...
@@ -29,6 +29,12 @@
PX4Component
::
PX4Component
(
UASInterface
*
uas
,
AutoPilotPlugin
*
autopilot
,
QObject
*
parent
)
:
VehicleComponent
(
uas
,
autopilot
,
parent
)
{
Q_ASSERT
(
uas
);
Q_ASSERT
(
autopilot
);
_paramMgr
=
_uas
->
getParamManager
();
Q_ASSERT
(
_paramMgr
);
bool
fSuccess
=
connect
(
_paramMgr
,
SIGNAL
(
parameterUpdated
(
int
,
QString
,
QVariant
)),
this
,
SLOT
(
_parameterUpdated
(
int
,
QString
,
QVariant
)));
Q_ASSERT
(
fSuccess
);
Q_UNUSED
(
fSuccess
);
...
...
src/AutoPilotPlugins/PX4/PX4Component.h
View file @
c74d545b
...
...
@@ -47,6 +47,9 @@ private slots:
/// @brief Connected to QGCUASParamManagerInterface::parameterUpdated signal in order to signal
/// setupCompleteChanged at appropriate times.
void
_parameterUpdated
(
int
compId
,
QString
paramName
,
QVariant
value
);
private:
QGCUASParamManagerInterface
*
_paramMgr
;
};
#endif
src/AutoPilotPlugins/PX4/PowerComponent.cc
View file @
c74d545b
...
...
@@ -58,15 +58,9 @@ bool PowerComponent::requiresSetup(void) const
bool
PowerComponent
::
setupComplete
(
void
)
const
{
QVariant
cvalue
,
evalue
,
nvalue
;
if
(
_paramMgr
->
getParameterValue
(
_paramMgr
->
getDefaultComponentId
(),
"BAT_V_CHARGED"
,
cvalue
))
{
if
(
_paramMgr
->
getParameterValue
(
_paramMgr
->
getDefaultComponentId
(),
"BAT_V_EMPTY"
,
evalue
))
{
if
(
_paramMgr
->
getParameterValue
(
_paramMgr
->
getDefaultComponentId
(),
"BAT_N_CELLS"
,
nvalue
))
{
return
(
cvalue
.
toFloat
()
>
0.1
f
)
&&
(
evalue
.
toFloat
()
>
0.1
f
)
&&
(
nvalue
.
toInt
()
>
0
);
}
}
}
Q_ASSERT
(
false
);
return
false
;
return
_autopilot
->
getParameterFact
(
"BAT_V_CHARGED"
)
->
value
().
toFloat
()
!=
0.0
f
&&
_autopilot
->
getParameterFact
(
"BAT_V_EMPTY"
)
->
value
().
toFloat
()
!=
0.0
f
&&
_autopilot
->
getParameterFact
(
"BAT_N_CELLS"
)
->
value
().
toInt
()
!=
0
;
}
QString
PowerComponent
::
setupStateDescription
(
void
)
const
...
...
src/AutoPilotPlugins/PX4/RadioComponent.cc
View file @
c74d545b
...
...
@@ -62,13 +62,7 @@ bool RadioComponent::setupComplete(void) const
QStringList
attitudeMappings
;
attitudeMappings
<<
"RC_MAP_ROLL"
<<
"RC_MAP_PITCH"
<<
"RC_MAP_YAW"
<<
"RC_MAP_THROTTLE"
;
foreach
(
QString
mapParam
,
attitudeMappings
)
{
QVariant
value
;
if
(
_paramMgr
->
getParameterValue
(
_paramMgr
->
getDefaultComponentId
(),
mapParam
,
value
))
{
if
(
value
.
toInt
()
==
0
)
{
return
false
;
}
}
else
{
Q_ASSERT
(
false
);
if
(
_autopilot
->
getParameterFact
(
mapParam
)
->
value
().
toInt
()
==
0
)
{
return
false
;
}
}
...
...
@@ -86,28 +80,13 @@ bool RadioComponent::setupComplete(void) const
QString
param
;
param
=
QString
(
"RC%1_MIN"
).
arg
(
i
);
if
(
_paramMgr
->
getParameterValue
(
_paramMgr
->
getDefaultComponentId
(),
param
,
value
))
{
rcMin
=
value
.
toInt
();
}
else
{
Q_ASSERT
(
false
);
return
false
;
}
rcMin
=
_autopilot
->
getParameterFact
(
param
)
->
value
().
toInt
();
param
=
QString
(
"RC%1_MAX"
).
arg
(
i
);
if
(
_paramMgr
->
getParameterValue
(
_paramMgr
->
getDefaultComponentId
(),
param
,
value
))
{
rcMax
=
value
.
toInt
();
}
else
{
Q_ASSERT
(
false
);
return
false
;
}
rcMax
=
_autopilot
->
getParameterFact
(
param
)
->
value
().
toInt
();
param
=
QString
(
"RC%1_TRIM"
).
arg
(
i
);
if
(
_paramMgr
->
getParameterValue
(
_paramMgr
->
getDefaultComponentId
(),
param
,
value
))
{
rcTrim
=
value
.
toInt
();
}
else
{
Q_ASSERT
(
false
);
return
false
;
}
rcTrim
=
_autopilot
->
getParameterFact
(
param
)
->
value
().
toInt
();
if
(
rcMin
==
rcMinDefault
&&
rcMax
==
rcMaxDefault
&&
rcTrim
==
rcTrimDefault
)
{
return
false
;
...
...
src/AutoPilotPlugins/PX4/SensorsComponent.cc
View file @
c74d545b
...
...
@@ -62,14 +62,7 @@ bool SensorsComponent::requiresSetup(void) const
bool
SensorsComponent
::
setupComplete
(
void
)
const
{
foreach
(
QString
triggerParam
,
setupCompleteChangedTriggerList
())
{
QVariant
value
;
if
(
!
_paramMgr
->
getParameterValue
(
_paramMgr
->
getDefaultComponentId
(),
triggerParam
,
value
))
{
Q_ASSERT
(
false
);
return
false
;
}
if
(
value
.
toFloat
()
==
0.0
f
)
{
if
(
_autopilot
->
getParameterFact
(
triggerParam
)
->
value
().
toFloat
()
==
0.0
f
)
{
return
false
;
}
}
...
...
src/VehicleSetup/VehicleComponent.cc
View file @
c74d545b
...
...
@@ -34,9 +34,6 @@ VehicleComponent::VehicleComponent(UASInterface* uas, AutoPilotPlugin* autopilot
{
Q_ASSERT
(
uas
);
Q_ASSERT
(
autopilot
);
_paramMgr
=
_uas
->
getParamManager
();
Q_ASSERT
(
_paramMgr
);
}
VehicleComponent
::~
VehicleComponent
()
...
...
src/VehicleSetup/VehicleComponent.h
View file @
c74d545b
...
...
@@ -75,7 +75,6 @@ signals:
protected:
UASInterface
*
_uas
;
AutoPilotPlugin
*
_autopilot
;
QGCUASParamManagerInterface
*
_paramMgr
;
};
#endif
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