Browse Source

Send cal commands only to default component

QGC4.4
Don Gagne 9 years ago
parent
commit
8e7dfe5a64
  1. 8
      src/uas/UAS.cc

8
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,7 +860,7 @@ void UAS::startBusConfig(UASInterface::StartBusConfigType calType) @@ -860,7 +860,7 @@ void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
mavlink->getComponentId(),
&msg,
uasId,
0, // target component
_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
0, // 0=first transmission of command
actuatorCal, // actuators
@ -884,7 +884,7 @@ void UAS::stopBusConfig(void) @@ -884,7 +884,7 @@ void UAS::stopBusConfig(void)
mavlink->getComponentId(),
&msg,
uasId,
0, // target component
_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
0, // 0=first transmission of command
0,

Loading…
Cancel
Save