From 8e7dfe5a64bc24fd623cd577db8376e51a0a6113 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sat, 28 May 2016 19:19:58 -0700 Subject: [PATCH] Send cal commands only to default component --- src/uas/UAS.cc | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index ddfc7831f..824996f90 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, -- 2.22.0