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
8e51f644
Commit
8e51f644
authored
Feb 17, 2016
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Keep ParameterLoader on first seen dedicated link
parent
4f0562b9
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
8 additions
and
5 deletions
+8
-5
ParameterLoader.cc
src/FactSystem/ParameterLoader.cc
+6
-5
ParameterLoader.h
src/FactSystem/ParameterLoader.h
+2
-0
No files found.
src/FactSystem/ParameterLoader.cc
View file @
8e51f644
...
...
@@ -50,6 +50,7 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, Q
,
_autopilot
(
autopilot
)
,
_vehicle
(
vehicle
)
,
_mavlink
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
())
,
_dedicatedLink
(
_vehicle
->
priorityLink
())
,
_parametersReady
(
false
)
,
_initialLoadComplete
(
false
)
,
_saveRequired
(
false
)
...
...
@@ -329,7 +330,7 @@ void ParameterLoader::refreshAllParameters(uint8_t componentID)
mavlink_message_t
msg
;
mavlink_msg_param_request_list_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
_vehicle
->
id
(),
componentID
);
_vehicle
->
sendMessageOnLink
(
_
vehicle
->
priorityLink
()
,
msg
);
_vehicle
->
sendMessageOnLink
(
_
dedicatedLink
,
msg
);
QString
what
=
(
componentID
==
MAV_COMP_ID_ALL
)
?
"MAV_COMP_ID_ALL"
:
QString
::
number
(
componentID
);
qCDebug
(
ParameterLoaderLog
)
<<
"Request to refresh all parameters for component ID:"
<<
what
;
...
...
@@ -531,7 +532,7 @@ void ParameterLoader::_tryCacheLookup()
mavlink_message_t
msg
;
mavlink_msg_param_request_read_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
_vehicle
->
id
(),
MAV_COMP_ID_ALL
,
"_HASH_CHECK"
,
-
1
);
_vehicle
->
sendMessageOnLink
(
_
vehicle
->
priorityLink
()
,
msg
);
_vehicle
->
sendMessageOnLink
(
_
dedicatedLink
,
msg
);
}
void
ParameterLoader
::
_readParameterRaw
(
int
componentId
,
const
QString
&
paramName
,
int
paramIndex
)
...
...
@@ -547,7 +548,7 @@ void ParameterLoader::_readParameterRaw(int componentId, const QString& paramNam
componentId
,
// Target component id
fixedParamName
,
// Named parameter being requested
paramIndex
);
// Parameter index being requested, -1 for named
_vehicle
->
sendMessageOnLink
(
_
vehicle
->
priorityLink
()
,
msg
);
_vehicle
->
sendMessageOnLink
(
_
dedicatedLink
,
msg
);
}
void
ParameterLoader
::
_writeParameterRaw
(
int
componentId
,
const
QString
&
paramName
,
const
QVariant
&
value
)
...
...
@@ -600,7 +601,7 @@ void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramNa
mavlink_message_t
msg
;
mavlink_msg_param_set_encode
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
msg
,
&
p
);
_vehicle
->
sendMessageOnLink
(
_
vehicle
->
priorityLink
()
,
msg
);
_vehicle
->
sendMessageOnLink
(
_
dedicatedLink
,
msg
);
}
void
ParameterLoader
::
_writeLocalParamCache
()
...
...
@@ -679,7 +680,7 @@ void ParameterLoader::_saveToEEPROM(void)
if
(
_vehicle
->
firmwarePlugin
()
->
isCapable
(
FirmwarePlugin
::
MavCmdPreflightStorageCapability
))
{
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
msg
,
_vehicle
->
id
(),
0
,
MAV_CMD_PREFLIGHT_STORAGE
,
1
,
1
,
-
1
,
-
1
,
-
1
,
0
,
0
,
0
);
_vehicle
->
sendMessageOnLink
(
_
vehicle
->
priorityLink
()
,
msg
);
_vehicle
->
sendMessageOnLink
(
_
dedicatedLink
,
msg
);
qCDebug
(
ParameterLoaderLog
)
<<
"_saveToEEPROM"
;
}
else
{
qCDebug
(
ParameterLoaderLog
)
<<
"_saveToEEPROM skipped due to FirmwarePlugin::isCapable"
;
...
...
src/FactSystem/ParameterLoader.h
View file @
8e51f644
...
...
@@ -127,6 +127,8 @@ private:
FactMetaData
::
ValueType_t
_mavTypeToFactType
(
MAV_PARAM_TYPE
mavType
);
void
_saveToEEPROM
(
void
);
void
_checkInitialLoadComplete
(
void
);
LinkInterface
*
_dedicatedLink
;
///< Parameter protocol stays on this link
/// First mapping is by component id
/// Second mapping is parameter name, to Fact* in QVariant
...
...
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