Commit 7485b7a7 authored by DonLakeFlyer's avatar DonLakeFlyer

Fix up MockLink and unit tests for correct component id

parent b7d3377f
...@@ -32,7 +32,7 @@ FactPanel { ...@@ -32,7 +32,7 @@ FactPanel {
TextInput { TextInput {
text: fact2.value text: fact2.value
property Fact fact2: controller.getParameterFact(200, "RC_MAP_THROTTLE") property Fact fact2: controller.getParameterFact(1, "RC_MAP_THROTTLE")
onAccepted: fact2.value = text onAccepted: fact2.value = text
} }
......
...@@ -58,8 +58,8 @@ void FactSystemTestBase::_parameter_default_component_id_test(void) ...@@ -58,8 +58,8 @@ void FactSystemTestBase::_parameter_default_component_id_test(void)
void FactSystemTestBase::_parameter_specific_component_id_test(void) void FactSystemTestBase::_parameter_specific_component_id_test(void)
{ {
QVERIFY(_vehicle->parameterManager()->parameterExists(200, "RC_MAP_THROTTLE")); QVERIFY(_vehicle->parameterManager()->parameterExists(MAV_COMP_ID_AUTOPILOT1, "RC_MAP_THROTTLE"));
Fact* fact = _vehicle->parameterManager()->getParameter(200, "RC_MAP_THROTTLE"); Fact* fact = _vehicle->parameterManager()->getParameter(MAV_COMP_ID_AUTOPILOT1, "RC_MAP_THROTTLE");
QVERIFY(fact != NULL); QVERIFY(fact != NULL);
QVariant factValue = fact->rawValue(); QVariant factValue = fact->rawValue();
QCOMPARE(factValue.isValid(), true); QCOMPARE(factValue.isValid(), true);
......
...@@ -51,7 +51,7 @@ MockLink::MockLink(SharedLinkConfigurationPointer& config) ...@@ -51,7 +51,7 @@ MockLink::MockLink(SharedLinkConfigurationPointer& config)
, _connected(false) , _connected(false)
, _mavlinkChannel(0) , _mavlinkChannel(0)
, _vehicleSystemId(_nextVehicleSystemId++) , _vehicleSystemId(_nextVehicleSystemId++)
, _vehicleComponentId(200) , _vehicleComponentId(MAV_COMP_ID_AUTOPILOT1)
, _inNSH(false) , _inNSH(false)
, _mavlinkStarted(true) , _mavlinkStarted(true)
, _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) , _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
......
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