Commit 0bcea01b authored by Don Gagne's avatar Don Gagne

Use specific component id

parent 437959f9
...@@ -157,7 +157,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void) ...@@ -157,7 +157,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void)
sensorId = 6.0f; sensorId = 6.0f;
} }
if (sensorId != 0.0f) { if (sensorId != 0.0f) {
_vehicle->doCommandLong(0, MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS, sensorId, -sphere_x[cur_mag], -sphere_y[cur_mag], -sphere_z[cur_mag]); _vehicle->doCommandLong(_vehicle->defaultComponentId(), MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS, sensorId, -sphere_x[cur_mag], -sphere_y[cur_mag], -sphere_z[cur_mag]);
} }
} }
} }
......
...@@ -103,6 +103,8 @@ public: ...@@ -103,6 +103,8 @@ public:
/// If this file is newer than anything in the cache, cache it as the latest version /// If this file is newer than anything in the cache, cache it as the latest version
static void cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType); static void cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType);
int defaultComponenentId(void) { return _defaultComponentId; }
signals: signals:
/// Signalled when the full set of facts are ready /// Signalled when the full set of facts are ready
......
...@@ -210,7 +210,7 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -210,7 +210,7 @@ Vehicle::Vehicle(LinkInterface* link,
connect(_parameterLoader, &ParameterLoader::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress); connect(_parameterLoader, &ParameterLoader::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress);
// Ask the vehicle for firmware version info // Ask the vehicle for firmware version info
doCommandLong(MAV_COMP_ID_ALL, MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES, 1 /* request firmware version */); doCommandLong(defaultComponentId(), MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES, 1 /* request firmware version */);
_firmwarePlugin->initializeVehicle(this); _firmwarePlugin->initializeVehicle(this);
...@@ -1691,12 +1691,16 @@ QString Vehicle::firmwareVersionTypeString(void) const ...@@ -1691,12 +1691,16 @@ QString Vehicle::firmwareVersionTypeString(void) const
} }
} }
void Vehicle::rebootVehicle() void Vehicle::rebootVehicle()
{ {
doCommandLong(id(), MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f); doCommandLong(id(), MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f);
} }
int Vehicle::defaultComponentId(void)
{
return _parameterLoader->defaultComponenentId();
}
const char* VehicleGPSFactGroup::_hdopFactName = "hdop"; const char* VehicleGPSFactGroup::_hdopFactName = "hdop";
const char* VehicleGPSFactGroup::_vdopFactName = "vdop"; const char* VehicleGPSFactGroup::_vdopFactName = "vdop";
const char* VehicleGPSFactGroup::_courseOverGroundFactName = "courseOverGround"; const char* VehicleGPSFactGroup::_courseOverGroundFactName = "courseOverGround";
......
...@@ -541,6 +541,8 @@ public: ...@@ -541,6 +541,8 @@ public:
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL); void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
static const int versionNotSetValue = -1; static const int versionNotSetValue = -1;
int defaultComponentId(void);
public slots: public slots:
void setLatitude(double latitude); void setLatitude(double latitude);
void setLongitude(double longitude); void setLongitude(double longitude);
......
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