Browse Source

Merge pull request #3433 from DonLakeFlyer/CalToDefaultComponentId

PX4: Cal commands to default component
QGC4.4
Don Gagne 9 years ago
parent
commit
32724477c6
  1. 2
      src/FactSystem/ParameterLoader.cc
  2. 12
      src/uas/UAS.cc

2
src/FactSystem/ParameterLoader.cc

@ -903,8 +903,6 @@ void ParameterLoader::_addMetaDataToDefaultComponent(void) @@ -903,8 +903,6 @@ void ParameterLoader::_addMetaDataToDefaultComponent(void)
}
if (_parameterMetaData) {
// This should only be called once
qWarning() << "Internal Error: ParameterLoader::_addMetaDataToAll with _parameterMetaData non NULL";
return;
}

12
src/uas/UAS.cc

@ -801,7 +801,7 @@ void UAS::startCalibration(UASInterface::StartCalibrationType calType) @@ -801,7 +801,7 @@ void UAS::startCalibration(UASInterface::StartCalibrationType calType)
mavlink->getComponentId(),
&msg,
uasId,
0, // target component
_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_CALIBRATION, // command id
0, // 0=first transmission of command
gyroCal, // gyro cal
@ -825,7 +825,7 @@ void UAS::stopCalibration(void) @@ -825,7 +825,7 @@ void UAS::stopCalibration(void)
mavlink->getComponentId(),
&msg,
uasId,
0, // target component
_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_CALIBRATION, // command id
0, // 0=first transmission of command
0, // gyro cal
@ -860,8 +860,8 @@ void UAS::startBusConfig(UASInterface::StartBusConfigType calType) @@ -860,8 +860,8 @@ void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
mavlink->getComponentId(),
&msg,
uasId,
0, // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
0, // 0=first transmission of command
actuatorCal, // actuators
0,
@ -884,8 +884,8 @@ void UAS::stopBusConfig(void) @@ -884,8 +884,8 @@ void UAS::stopBusConfig(void)
mavlink->getComponentId(),
&msg,
uasId,
0, // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
0, // 0=first transmission of command
0,
0,

Loading…
Cancel
Save