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
ec091ecc
Commit
ec091ecc
authored
Feb 13, 2017
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Changed default component id discovery
Use component id from heartbeat
parent
1a2ce057
Changes
13
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
13 changed files
with
54 additions
and
113 deletions
+54
-113
ParameterManager.cc
src/FactSystem/ParameterManager.cc
+16
-80
ParameterManager.h
src/FactSystem/ParameterManager.h
+1
-6
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+0
-1
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+0
-3
PX4FirmwarePlugin.h
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
+0
-1
GeoFenceController.cc
src/MissionManager/GeoFenceController.cc
+1
-1
ParameterEditorController.cc
src/QmlControls/ParameterEditorController.cc
+4
-1
MultiVehicleManager.cc
src/Vehicle/MultiVehicleManager.cc
+4
-3
MultiVehicleManager.h
src/Vehicle/MultiVehicleManager.h
+1
-1
Vehicle.cc
src/Vehicle/Vehicle.cc
+19
-13
Vehicle.h
src/Vehicle/Vehicle.h
+6
-1
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+1
-1
MAVLinkProtocol.h
src/comm/MAVLinkProtocol.h
+1
-1
No files found.
src/FactSystem/ParameterManager.cc
View file @
ec091ecc
This diff is collapsed.
Click to expand it.
src/FactSystem/ParameterManager.h
View file @
ec091ecc
...
...
@@ -104,8 +104,6 @@ public:
/// If this file is newer than anything in the cache, cache it as the latest version
static
void
cacheMetaDataFile
(
const
QString
&
metaDataFile
,
MAV_AUTOPILOT
firmwareType
);
int
defaultComponentId
(
void
)
{
return
_defaultComponentId
;
}
/// Saves the specified param set to the json object.
/// @param componentId Component id which contains params, MAV_COMP_ID_ALL to save all components
/// @param paramsToSave List of params names to save, empty to save all for component
...
...
@@ -139,7 +137,6 @@ protected:
private:
static
QVariant
_stringToTypedVariant
(
const
QString
&
string
,
FactMetaData
::
ValueType_t
type
,
bool
failOk
=
false
);
int
_actualComponentId
(
int
componentId
);
void
_determineDefaultComponentId
(
void
);
void
_setupGroupMap
(
void
);
void
_readParameterRaw
(
int
componentId
,
const
QString
&
paramName
,
int
paramIndex
);
void
_writeParameterRaw
(
int
componentId
,
const
QString
&
paramName
,
const
QVariant
&
value
);
...
...
@@ -154,7 +151,7 @@ private:
MAV_PARAM_TYPE
_factTypeToMavType
(
FactMetaData
::
ValueType_t
factType
);
FactMetaData
::
ValueType_t
_mavTypeToFactType
(
MAV_PARAM_TYPE
mavType
);
void
_saveToEEPROM
(
void
);
void
_checkInitialLoadComplete
(
bool
failIfNoDefaultComponent
);
void
_checkInitialLoadComplete
(
void
);
/// First mapping is by component id
/// Second mapping is parameter name, to Fact* in QVariant
...
...
@@ -172,8 +169,6 @@ private:
bool
_initialLoadComplete
;
///< true: Initial load of all parameters complete, whether successful or not
bool
_waitingForDefaultComponent
;
///< true: last chance wait for default component params
bool
_saveRequired
;
///< true: _saveToEEPROM should be called
int
_defaultComponentId
;
QString
_defaultComponentIdParam
;
///< Parameter which identifies default component
QString
_versionParam
;
///< Parameter which contains parameter set version
int
_parameterSetMajorVersion
;
///< Version for parameter set, -1 if not known
QObject
*
_parameterMetaData
;
///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
ec091ecc
...
...
@@ -88,7 +88,6 @@ public:
void
initializeVehicle
(
Vehicle
*
vehicle
)
final
;
bool
sendHomePositionToVehicle
(
void
)
final
;
void
addMetaDataToFact
(
QObject
*
parameterMetaData
,
Fact
*
fact
,
MAV_TYPE
vehicleType
)
final
;
QString
getDefaultComponentIdParam
(
void
)
const
final
{
return
QString
(
"SYSID_SW_TYPE"
);
}
QString
missionCommandOverrides
(
MAV_TYPE
vehicleType
)
const
;
QString
getVersionParam
(
void
)
final
{
return
QStringLiteral
(
"SYSID_SW_MREV"
);
}
QString
internalParameterMetaDataFile
(
Vehicle
*
vehicle
)
final
;
...
...
src/FirmwarePlugin/FirmwarePlugin.h
View file @
ec091ecc
...
...
@@ -187,9 +187,6 @@ public:
/// false: Do not send first item to vehicle, sequence numbers must be adjusted
virtual
bool
sendHomePositionToVehicle
(
void
);
/// Returns the parameter that is used to identify the default component
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
();
}
/// Returns the parameter which is used to identify the version number of parameter set
virtual
QString
getVersionParam
(
void
)
{
return
QString
();
}
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
View file @
ec091ecc
...
...
@@ -50,7 +50,6 @@ public:
void
initializeVehicle
(
Vehicle
*
vehicle
)
final
;
bool
sendHomePositionToVehicle
(
void
)
final
;
void
addMetaDataToFact
(
QObject
*
parameterMetaData
,
Fact
*
fact
,
MAV_TYPE
vehicleType
)
final
;
QString
getDefaultComponentIdParam
(
void
)
const
final
{
return
QString
(
"SYS_AUTOSTART"
);
}
QString
missionCommandOverrides
(
MAV_TYPE
vehicleType
)
const
final
;
QString
getVersionParam
(
void
)
final
{
return
QString
(
"SYS_PARAM_VER"
);
}
QString
internalParameterMetaDataFile
(
Vehicle
*
vehicle
)
final
{
Q_UNUSED
(
vehicle
);
return
QString
(
":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"
);
}
...
...
src/MissionManager/GeoFenceController.cc
View file @
ec091ecc
...
...
@@ -279,7 +279,7 @@ void GeoFenceController::saveToFile(const QString& filename)
paramNames
.
append
(
params
[
i
].
value
<
Fact
*>
()
->
name
());
}
if
(
paramNames
.
count
()
>
0
)
{
paramMgr
->
saveToJson
(
paramMgr
->
defaultComponentId
(),
paramNames
,
fenceFileObject
);
paramMgr
->
saveToJson
(
_activeVehicle
->
defaultComponentId
(),
paramNames
,
fenceFileObject
);
}
if
(
breachReturnEnabled
())
{
...
...
src/QmlControls/ParameterEditorController.cc
View file @
ec091ecc
...
...
@@ -33,7 +33,10 @@ ParameterEditorController::ParameterEditorController(void)
_componentIds
+=
QString
(
"%1"
).
arg
(
componentId
);
}
_currentGroup
=
groupMap
[
_currentComponentId
].
keys
()[
0
];
// Be careful about no parameters
if
(
groupMap
.
contains
(
_currentComponentId
)
&&
groupMap
[
_currentComponentId
].
size
()
!=
0
)
{
_currentGroup
=
groupMap
[
_currentComponentId
].
keys
()[
0
];
}
_updateParameters
();
connect
(
this
,
&
ParameterEditorController
::
searchTextChanged
,
this
,
&
ParameterEditorController
::
_updateParameters
);
...
...
src/Vehicle/MultiVehicleManager.cc
View file @
ec091ecc
...
...
@@ -68,7 +68,7 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
this
);
}
void
MultiVehicleManager
::
_vehicleHeartbeatInfo
(
LinkInterface
*
link
,
int
vehicleId
,
int
vehicleMavlinkVersion
,
int
vehicleFirmwareType
,
int
vehicleType
)
void
MultiVehicleManager
::
_vehicleHeartbeatInfo
(
LinkInterface
*
link
,
int
vehicleId
,
int
componentId
,
int
vehicleMavlinkVersion
,
int
vehicleFirmwareType
,
int
vehicleType
)
{
if
(
_ignoreVehicleIds
.
contains
(
vehicleId
)
||
getVehicleById
(
vehicleId
)
||
vehicleId
==
0
)
{
return
;
...
...
@@ -86,9 +86,10 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle
break
;
}
qCDebug
(
MultiVehicleManagerLog
())
<<
"Adding new vehicle link:vehicleId:vehicleMavlinkVersion:vehicleFirmwareType:vehicleType "
qCDebug
(
MultiVehicleManagerLog
())
<<
"Adding new vehicle link:vehicleId:
componentId:
vehicleMavlinkVersion:vehicleFirmwareType:vehicleType "
<<
link
->
getName
()
<<
vehicleId
<<
componentId
<<
vehicleMavlinkVersion
<<
vehicleFirmwareType
<<
vehicleType
;
...
...
@@ -107,7 +108,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle
// return;
// }
Vehicle
*
vehicle
=
new
Vehicle
(
link
,
vehicleId
,
(
MAV_AUTOPILOT
)
vehicleFirmwareType
,
(
MAV_TYPE
)
vehicleType
,
_firmwarePluginManager
,
_joystickManager
);
Vehicle
*
vehicle
=
new
Vehicle
(
link
,
vehicleId
,
componentId
,
(
MAV_AUTOPILOT
)
vehicleFirmwareType
,
(
MAV_TYPE
)
vehicleType
,
_firmwarePluginManager
,
_joystickManager
);
connect
(
vehicle
,
&
Vehicle
::
allLinksInactive
,
this
,
&
MultiVehicleManager
::
_deleteVehiclePhase1
);
connect
(
vehicle
->
parameterManager
(),
&
ParameterManager
::
parametersReadyChanged
,
this
,
&
MultiVehicleManager
::
_vehicleParametersReadyChanged
);
...
...
src/Vehicle/MultiVehicleManager.h
View file @
ec091ecc
...
...
@@ -94,7 +94,7 @@ private slots:
void
_setActiveVehiclePhase2
(
void
);
void
_vehicleParametersReadyChanged
(
bool
parametersReady
);
void
_sendGCSHeartbeat
(
void
);
void
_vehicleHeartbeatInfo
(
LinkInterface
*
link
,
int
vehicleId
,
int
vehicleMavlinkVersion
,
int
vehicleFirmwareType
,
int
vehicleType
);
void
_vehicleHeartbeatInfo
(
LinkInterface
*
link
,
int
vehicleId
,
int
componentId
,
int
vehicleMavlinkVersion
,
int
vehicleFirmwareType
,
int
vehicleType
);
private:
bool
_vehicleExists
(
int
vehicleId
);
...
...
src/Vehicle/Vehicle.cc
View file @
ec091ecc
...
...
@@ -58,12 +58,14 @@ const int Vehicle::_lowBatteryAnnounceRepeatMSecs = 30 * 1000;
Vehicle
::
Vehicle
(
LinkInterface
*
link
,
int
vehicleId
,
int
defaultComponentId
,
MAV_AUTOPILOT
firmwareType
,
MAV_TYPE
vehicleType
,
FirmwarePluginManager
*
firmwarePluginManager
,
JoystickManager
*
joystickManager
)
:
FactGroup
(
_vehicleUIUpdateRateMSecs
,
":/json/Vehicle/VehicleFact.json"
)
,
_id
(
vehicleId
)
,
_defaultComponentId
(
defaultComponentId
)
,
_active
(
false
)
,
_offlineEditingVehicle
(
false
)
,
_firmwareType
(
firmwareType
)
...
...
@@ -211,6 +213,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
QObject
*
parent
)
:
FactGroup
(
_vehicleUIUpdateRateMSecs
,
":/json/Vehicle/VehicleFact.json"
,
parent
)
,
_id
(
0
)
,
_defaultComponentId
(
MAV_COMP_ID_ALL
)
,
_active
(
false
)
,
_offlineEditingVehicle
(
true
)
,
_firmwareType
(
firmwareType
)
...
...
@@ -1347,7 +1350,7 @@ QGeoCoordinate Vehicle::homePosition(void)
void
Vehicle
::
setArmed
(
bool
armed
)
{
// We specifically use COMMAND_LONG:MAV_CMD_COMPONENT_ARM_DISARM since it is supported by more flight stacks.
sendMavCommand
(
defaultComponentId
()
,
sendMavCommand
(
_defaultComponentId
,
MAV_CMD_COMPONENT_ARM_DISARM
,
true
,
// show error if fails
armed
?
1.0
f
:
0.0
f
);
...
...
@@ -1428,7 +1431,7 @@ void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool send
dataStream
.
req_message_rate
=
rate
;
dataStream
.
start_stop
=
1
;
// start
dataStream
.
target_system
=
id
();
dataStream
.
target_component
=
defaultComponentId
()
;
dataStream
.
target_component
=
_defaultComponentId
;
mavlink_msg_request_data_stream_encode_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
...
...
@@ -1850,7 +1853,7 @@ void Vehicle::setGuidedMode(bool guidedMode)
void
Vehicle
::
emergencyStop
(
void
)
{
sendMavCommand
(
defaultComponentId
()
,
sendMavCommand
(
_defaultComponentId
,
MAV_CMD_COMPONENT_ARM_DISARM
,
true
,
// show error if fails
0.0
f
,
...
...
@@ -2019,12 +2022,7 @@ QString Vehicle::firmwareVersionTypeString(void) const
void
Vehicle
::
rebootVehicle
()
{
sendMavCommand
(
defaultComponentId
(),
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN
,
true
,
1.0
f
);
}
int
Vehicle
::
defaultComponentId
(
void
)
{
return
_parameterManager
->
defaultComponentId
();
sendMavCommand
(
_defaultComponentId
,
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN
,
true
,
1.0
f
);
}
void
Vehicle
::
setSoloFirmware
(
bool
soloFirmware
)
...
...
@@ -2039,7 +2037,7 @@ void Vehicle::setSoloFirmware(bool soloFirmware)
// Temporarily removed, waiting for new command implementation
void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
{
doCommandLongUnverified(
defaultComponentId()
, MAV_CMD_DO_MOTOR_TEST, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs);
doCommandLongUnverified(
_defaultComponentId
, MAV_CMD_DO_MOTOR_TEST, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs);
}
#endif
...
...
@@ -2113,6 +2111,14 @@ QStringList Vehicle::unhealthySensors(void) const
return
sensorList
;
}
void
Vehicle
::
setOfflineEditingDefaultComponentId
(
int
defaultComponentId
)
{
if
(
_offlineEditingVehicle
)
{
_defaultComponentId
=
defaultComponentId
;
}
else
{
qWarning
()
<<
"Call to Vehicle::setOfflineEditingDefaultComponentId on vehicle which is not offline"
;
}
}
const
char
*
VehicleGPSFactGroup
::
_hdopFactName
=
"hdop"
;
const
char
*
VehicleGPSFactGroup
::
_vdopFactName
=
"vdop"
;
...
...
@@ -2141,12 +2147,12 @@ VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent)
void
Vehicle
::
startMavlinkLog
()
{
sendMavCommand
(
defaultComponentId
()
,
MAV_CMD_LOGGING_START
,
false
/* showError */
);
sendMavCommand
(
_defaultComponentId
,
MAV_CMD_LOGGING_START
,
false
/* showError */
);
}
void
Vehicle
::
stopMavlinkLog
()
{
sendMavCommand
(
defaultComponentId
()
,
MAV_CMD_LOGGING_STOP
,
false
/* showError */
);
sendMavCommand
(
_defaultComponentId
,
MAV_CMD_LOGGING_STOP
,
false
/* showError */
);
}
void
Vehicle
::
_ackMavlinkLogData
(
uint16_t
sequence
)
...
...
@@ -2154,7 +2160,7 @@ void Vehicle::_ackMavlinkLogData(uint16_t sequence)
mavlink_message_t
msg
;
mavlink_logging_ack_t
ack
;
ack
.
sequence
=
sequence
;
ack
.
target_component
=
defaultComponentId
()
;
ack
.
target_component
=
_defaultComponentId
;
ack
.
target_system
=
id
();
mavlink_msg_logging_ack_encode_chan
(
_mavlink
->
getSystemId
(),
...
...
src/Vehicle/Vehicle.h
View file @
ec091ecc
...
...
@@ -191,6 +191,7 @@ class Vehicle : public FactGroup
public:
Vehicle
(
LinkInterface
*
link
,
int
vehicleId
,
int
defaultComponentId
,
MAV_AUTOPILOT
firmwareType
,
MAV_TYPE
vehicleType
,
FirmwarePluginManager
*
firmwarePluginManager
,
...
...
@@ -567,7 +568,10 @@ public:
bool
soloFirmware
(
void
)
const
{
return
_soloFirmware
;
}
void
setSoloFirmware
(
bool
soloFirmware
);
int
defaultComponentId
(
void
);
int
defaultComponentId
(
void
)
{
return
_defaultComponentId
;
}
/// Sets the default component id for an offline editing vehicle
void
setOfflineEditingDefaultComponentId
(
int
defaultComponentId
);
/// @return -1 = Unknown, Number of motors on vehicle
int
motorCount
(
void
);
...
...
@@ -736,6 +740,7 @@ private:
void
_commonInit
(
void
);
int
_id
;
///< Mavlink system id
int
_defaultComponentId
;
bool
_active
;
bool
_offlineEditingVehicle
;
///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
...
...
src/comm/MAVLinkProtocol.cc
View file @
ec091ecc
...
...
@@ -283,7 +283,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
mavlink_heartbeat_t
heartbeat
;
mavlink_msg_heartbeat_decode
(
&
message
,
&
heartbeat
);
emit
vehicleHeartbeatInfo
(
link
,
message
.
sysid
,
heartbeat
.
mavlink_version
,
heartbeat
.
autopilot
,
heartbeat
.
type
);
emit
vehicleHeartbeatInfo
(
link
,
message
.
sysid
,
message
.
compid
,
heartbeat
.
mavlink_version
,
heartbeat
.
autopilot
,
heartbeat
.
type
);
}
// Increase receive counter
...
...
src/comm/MAVLinkProtocol.h
View file @
ec091ecc
...
...
@@ -130,7 +130,7 @@ protected:
signals:
/// Heartbeat received on link
void
vehicleHeartbeatInfo
(
LinkInterface
*
link
,
int
vehicleId
,
int
vehicleMavlinkVersion
,
int
vehicleFirmwareType
,
int
vehicleType
);
void
vehicleHeartbeatInfo
(
LinkInterface
*
link
,
int
vehicleId
,
int
componentId
,
int
vehicleMavlinkVersion
,
int
vehicleFirmwareType
,
int
vehicleType
);
/** @brief Message received and directly copied via signal */
void
messageReceived
(
LinkInterface
*
link
,
mavlink_message_t
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