diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index f6541ba..a774fa9 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -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; } diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index ddfc783..824996f 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -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) 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) 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) 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,