Commit 32724477 authored by Don Gagne's avatar Don Gagne

Merge pull request #3433 from DonLakeFlyer/CalToDefaultComponentId

PX4: Cal commands to default component
parents ce5ad726 8e7dfe5a
...@@ -903,8 +903,6 @@ void ParameterLoader::_addMetaDataToDefaultComponent(void) ...@@ -903,8 +903,6 @@ void ParameterLoader::_addMetaDataToDefaultComponent(void)
} }
if (_parameterMetaData) { if (_parameterMetaData) {
// This should only be called once
qWarning() << "Internal Error: ParameterLoader::_addMetaDataToAll with _parameterMetaData non NULL";
return; return;
} }
......
...@@ -801,7 +801,7 @@ void UAS::startCalibration(UASInterface::StartCalibrationType calType) ...@@ -801,7 +801,7 @@ void UAS::startCalibration(UASInterface::StartCalibrationType calType)
mavlink->getComponentId(), mavlink->getComponentId(),
&msg, &msg,
uasId, uasId,
0, // target component _vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_CALIBRATION, // command id MAV_CMD_PREFLIGHT_CALIBRATION, // command id
0, // 0=first transmission of command 0, // 0=first transmission of command
gyroCal, // gyro cal gyroCal, // gyro cal
...@@ -825,7 +825,7 @@ void UAS::stopCalibration(void) ...@@ -825,7 +825,7 @@ void UAS::stopCalibration(void)
mavlink->getComponentId(), mavlink->getComponentId(),
&msg, &msg,
uasId, uasId,
0, // target component _vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_CALIBRATION, // command id MAV_CMD_PREFLIGHT_CALIBRATION, // command id
0, // 0=first transmission of command 0, // 0=first transmission of command
0, // gyro cal 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(), mavlink->getComponentId(),
&msg, &msg,
uasId, uasId,
0, // target component _vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id MAV_CMD_PREFLIGHT_UAVCAN, // command id
0, // 0=first transmission of command 0, // 0=first transmission of command
actuatorCal, // actuators actuatorCal, // actuators
0, 0,
...@@ -884,8 +884,8 @@ void UAS::stopBusConfig(void) ...@@ -884,8 +884,8 @@ void UAS::stopBusConfig(void)
mavlink->getComponentId(), mavlink->getComponentId(),
&msg, &msg,
uasId, uasId,
0, // target component _vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id MAV_CMD_PREFLIGHT_UAVCAN, // command id
0, // 0=first transmission of command 0, // 0=first transmission of command
0, 0,
0, 0,
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment