Commit 8e7dfe5a authored by Don Gagne's avatar Don Gagne

Send cal commands only to default component

parent 38627f33
......@@ -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,
......
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