Newer
Older
QString Vehicle::gotoFlightMode() const
{
return _firmwarePlugin->gotoFlightMode();
}
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
}
void Vehicle::guidedModeLand(void)
{
if (!guidedModeSupported()) {
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
return;
}
_firmwarePlugin->guidedModeLand(this);
}
void Vehicle::guidedModeTakeoff(double altitudeRelative)
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
_firmwarePlugin->guidedModeTakeoff(this, altitudeRelative);
double Vehicle::minimumTakeoffAltitude(void)
{
return _firmwarePlugin->minimumTakeoffAltitude(this);
}
void Vehicle::startMission(void)
{
_firmwarePlugin->startMission(this);
}
void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord)
{
if (!guidedModeSupported()) {
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
if (!coordinate().isValid()) {
return;
}
double maxDistance = _settingsManager->flyViewSettings()->maxGoToLocationDistance()->rawValue().toDouble();
if (coordinate().distanceTo(gotoCoord) > maxDistance) {
qgcApp()->showMessage(QString("New location is too far. Must be less than %1 %2.").arg(qRound(FactMetaData::metersToAppSettingsDistanceUnits(maxDistance).toDouble())).arg(FactMetaData::appSettingsDistanceUnitsString()));
_firmwarePlugin->guidedModeGotoLocation(this, gotoCoord);
}
void Vehicle::guidedModeChangeAltitude(double altitudeChange)
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
_firmwarePlugin->guidedModeChangeAltitude(this, altitudeChange);
void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude)
if (!orbitModeSupported()) {
qgcApp()->showMessage(QStringLiteral("Orbit mode not supported by Vehicle."));
sendMavCommandInt(
defaultComponentId(),
MAV_CMD_DO_ORBIT,
MAV_FRAME_GLOBAL,
true, // show error if fails
static_cast<float>(radius),
static_cast<float>(qQNaN()), // Use default velocity
0, // Vehicle points to center
static_cast<float>(qQNaN()), // reserved
centerCoord.latitude(), centerCoord.longitude(), static_cast<float>(amslAltitude));
sendMavCommand(
defaultComponentId(),
MAV_CMD_DO_ORBIT,
true, // show error if fails
static_cast<float>(radius),
static_cast<float>(qQNaN()), // Use default velocity
0, // Vehicle points to center
static_cast<float>(qQNaN()), // reserved
static_cast<float>(centerCoord.latitude()),
static_cast<float>(centerCoord.longitude()),
static_cast<float>(amslAltitude));
void Vehicle::guidedModeROI(const QGeoCoordinate& centerCoord)
{
if (!roiModeSupported()) {
qgcApp()->showMessage(QStringLiteral("ROI mode not supported by Vehicle."));
return;
}
if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
sendMavCommandInt(
defaultComponentId(),
MAV_CMD_DO_SET_ROI_LOCATION,
MAV_FRAME_GLOBAL,
true, // show error if fails
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
centerCoord.latitude(),
centerCoord.longitude(),
static_cast<float>(centerCoord.altitude()));
} else {
sendMavCommand(
defaultComponentId(),
MAV_CMD_DO_SET_ROI_LOCATION,
true, // show error if fails
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(centerCoord.latitude()),
static_cast<float>(centerCoord.longitude()),
static_cast<float>(centerCoord.altitude()));
}
}
void Vehicle::pauseVehicle(void)
{
if (!pauseVehicleSupported()) {
qgcApp()->showMessage(QStringLiteral("Pause not supported by vehicle."));
return;
}
_firmwarePlugin->pauseVehicle(this);
}
Danny Schrader
committed
void Vehicle::abortLanding(double climbOutAltitude)
{
sendMavCommand(
defaultComponentId(),
MAV_CMD_DO_GO_AROUND,
true, // show error if fails
static_cast<float>(climbOutAltitude));
}
bool Vehicle::guidedMode(void) const
{
return _firmwarePlugin->isGuidedMode(this);
}
void Vehicle::setGuidedMode(bool guidedMode)
{
return _firmwarePlugin->setGuidedMode(this, guidedMode);
}
void Vehicle::emergencyStop(void)
{
sendMavCommand(
_defaultComponentId,
MAV_CMD_COMPONENT_ARM_DISARM,
true, // show error if fails
0.0f,
21196.0f); // Magic number for emergency stop
void Vehicle::setCurrentMissionSequence(int seq)
{
if (!_firmwarePlugin->sendHomePositionToVehicle()) {
seq--;
}
mavlink_message_t msg;
mavlink_msg_mission_set_current_pack_chan(
static_cast<uint8_t>(_mavlink->getSystemId()),
static_cast<uint8_t>(_mavlink->getComponentId()),
priorityLink()->mavlinkChannel(),
&msg,
static_cast<uint8_t>(id()),
_compID,
static_cast<uint8_t>(seq));
sendMessageOnLink(priorityLink(), msg);
void Vehicle::sendMavCommand(int component, MAV_CMD command, bool showError, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
MavCommandQueueEntry_t entry;
entry.component = component;
entry.command = command;
entry.showError = showError;
entry.rgParam[0] = static_cast<double>(param1);
entry.rgParam[1] = static_cast<double>(param2);
entry.rgParam[2] = static_cast<double>(param3);
entry.rgParam[3] = static_cast<double>(param4);
entry.rgParam[4] = static_cast<double>(param5);
entry.rgParam[5] = static_cast<double>(param6);
entry.rgParam[6] = static_cast<double>(param7);
_mavCommandQueue.append(entry);
if (_mavCommandQueue.count() == 1) {
_mavCommandRetryCount = 0;
_sendMavCommandAgain();
}
}
void Vehicle::sendMavCommandInt(int component, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
{
MavCommandQueueEntry_t entry;
entry.commandInt = true;
entry.component = component;
entry.command = command;
entry.showError = showError;
entry.rgParam[0] = static_cast<double>(param1);
entry.rgParam[1] = static_cast<double>(param2);
entry.rgParam[2] = static_cast<double>(param3);
entry.rgParam[3] = static_cast<double>(param4);
entry.rgParam[4] = param5;
entry.rgParam[5] = param6;
_mavCommandQueue.append(entry);
if (_mavCommandQueue.count() == 1) {
_mavCommandRetryCount = 0;
_sendMavCommandAgain();
}
}
void Vehicle::_sendMavCommandAgain(void)
{
Gus Grubba
committed
if(!_mavCommandQueue.size()) {
qWarning() << "Command resend with no commands in queue";
_mavCommandAckTimer.stop();
return;
}
MavCommandQueueEntry_t& queuedCommand = _mavCommandQueue[0];
if (_mavCommandRetryCount++ > _mavCommandMaxRetryCount) {
if (queuedCommand.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES.";
_handleUnsupportedRequestAutopilotCapabilities();
if (queuedCommand.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) {
qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_PROTOCOL_VERSION.";
_handleUnsupportedRequestProtocolVersion();
emit mavCommandResult(_id, queuedCommand.component, queuedCommand.command, MAV_RESULT_FAILED, true /* noResponsefromVehicle */);
if (queuedCommand.showError) {
qgcApp()->showMessage(tr("Vehicle did not respond to command: %1").arg(_toolbox->missionCommandTree()->friendlyName(queuedCommand.command)));
}
_mavCommandQueue.removeFirst();
_sendNextQueuedMavCommand();
return;
}
if (!px4Firmware() && queuedCommand.command == MAV_CMD_START_RX_PAIR) {
// The implementation of this command comes from the IO layer and is shared across stacks. So for other firmwares
// we aren't really sure whether they are correct or not.
return;
qCDebug(VehicleLog) << "Vehicle::_sendMavCommandAgain retrying command:_mavCommandRetryCount" << queuedCommand.command << _mavCommandRetryCount;
_mavCommandAckTimer.start();
3282
3283
3284
3285
3286
3287
3288
3289
3290
3291
3292
3293
3294
3295
3296
3297
3298
3299
3300
3301
3302
3303
3304
3305
3306
3307
3308
3309
3310
3311
3312
3313
3314
3315
3316
3317
3318
3319
3320
3321
3322
if (queuedCommand.commandInt) {
mavlink_command_int_t cmd;
memset(&cmd, 0, sizeof(cmd));
cmd.target_system = _id;
cmd.target_component = queuedCommand.component;
cmd.command = queuedCommand.command;
cmd.frame = queuedCommand.frame;
cmd.param1 = queuedCommand.rgParam[0];
cmd.param2 = queuedCommand.rgParam[1];
cmd.param3 = queuedCommand.rgParam[2];
cmd.param4 = queuedCommand.rgParam[3];
cmd.x = queuedCommand.rgParam[4] * qPow(10.0, 7.0);
cmd.y = queuedCommand.rgParam[5] * qPow(10.0, 7.0);
cmd.z = queuedCommand.rgParam[6];
mavlink_msg_command_int_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&cmd);
} else {
mavlink_command_long_t cmd;
memset(&cmd, 0, sizeof(cmd));
cmd.target_system = _id;
cmd.target_component = queuedCommand.component;
cmd.command = queuedCommand.command;
cmd.confirmation = 0;
cmd.param1 = queuedCommand.rgParam[0];
cmd.param2 = queuedCommand.rgParam[1];
cmd.param3 = queuedCommand.rgParam[2];
cmd.param4 = queuedCommand.rgParam[3];
cmd.param5 = queuedCommand.rgParam[4];
cmd.param6 = queuedCommand.rgParam[5];
cmd.param7 = queuedCommand.rgParam[6];
mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&cmd);
}
sendMessageOnLink(priorityLink(), msg);
void Vehicle::_sendNextQueuedMavCommand(void)
{
if (_mavCommandQueue.count()) {
_mavCommandRetryCount = 0;
_sendMavCommandAgain();
}
}
3335
3336
3337
3338
3339
3340
3341
3342
3343
3344
3345
3346
3347
3348
3349
3350
3351
3352
3353
3354
3355
3356
3357
3358
3359
3360
void Vehicle::_handleUnsupportedRequestProtocolVersion(void)
{
// We end up here if either the vehicle does not support the MAV_CMD_REQUEST_PROTOCOL_VERSION command or if
// we never received an Ack back for the command.
// If the link isn't already running Mavlink V2 fall back to the capability bits to determine whether to use Mavlink V2 or not.
if (_maxProtoVersion == 0) {
if (capabilitiesKnown()) {
unsigned vehicleMaxProtoVersion = capabilityBits() & MAV_PROTOCOL_CAPABILITY_MAVLINK2 ? 200 : 100;
qCDebug(VehicleLog) << QStringLiteral("Setting _maxProtoVersion to %1 based on capabilitity bits since not yet set.").arg(vehicleMaxProtoVersion);
_setMaxProtoVersion(vehicleMaxProtoVersion);
} else {
qCDebug(VehicleLog) << "Waiting for capabilities to be known to set _maxProtoVersion";
}
} else {
qCDebug(VehicleLog) << "Leaving _maxProtoVersion at current value" << _maxProtoVersion;
}
_mavlinkProtocolRequestComplete = true;
// Determining protocol version is one of the triggers to possibly start downloading the plan
_startPlanRequest();
}
void Vehicle::_protocolVersionTimeOut(void)
{
// The PROTOCOL_VERSION message didn't make it through the pipe from Vehicle->QGC.
// This means although the vehicle may support mavlink 2, the pipe does not.
qCDebug(VehicleLog) << QStringLiteral("Setting _maxProtoVersion to 100 due to timeout on receiving PROTOCOL_VERSION message.");
_setMaxProtoVersion(100);
_mavlinkProtocolRequestComplete = true;
_startPlanRequest();
}
void Vehicle::_handleUnsupportedRequestAutopilotCapabilities(void)
{
// We end up here if either the vehicle does not support the MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES command or if
// we never received an Ack back for the command.
_setCapabilities(0);
// Determining vehicle capabilities is one of the triggers to possibly start downloading the plan
_startPlanRequest();
}
void Vehicle::_handleCommandAck(mavlink_message_t& message)
{
bool showError = false;
mavlink_command_ack_t ack;
mavlink_msg_command_ack_decode(&message, &ack);
if (ack.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES && ack.result != MAV_RESULT_ACCEPTED) {
qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities.").arg(ack.result);
_handleUnsupportedRequestAutopilotCapabilities();
if (ack.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) {
if (ack.result == MAV_RESULT_ACCEPTED) {
// The vehicle should be sending a PROTOCOL_VERSION message in a mavlink 2 packet. This may or may not make it through the pipe.
// So we wait for it to come and timeout if it doesn't.
if (!_mavlinkProtocolRequestComplete) {
QTimer::singleShot(1000, this, &Vehicle::_protocolVersionTimeOut);
}
qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_PROTOCOL_VERSION with error(%1).").arg(ack.result);
_handleUnsupportedRequestProtocolVersion();
if (ack.command == MAV_CMD_FLASH_BOOTLOADER && ack.result == MAV_RESULT_ACCEPTED) {
qgcApp()->showMessage(tr("Bootloader flash succeeded"));
}
if (_mavCommandQueue.count() && ack.command == _mavCommandQueue[0].command) {
_mavCommandAckTimer.stop();
showError = _mavCommandQueue[0].showError;
_mavCommandQueue.removeFirst();
}
emit mavCommandResult(_id, message.compid, ack.command, ack.result, false /* noResponsefromVehicle */);
if (showError) {
QString commandName = _toolbox->missionCommandTree()->friendlyName(static_cast<MAV_CMD>(ack.command));
3420
3421
3422
3423
3424
3425
3426
3427
3428
3429
3430
3431
3432
3433
3434
3435
3436
3437
3438
3439
3440
3441
switch (ack.result) {
case MAV_RESULT_TEMPORARILY_REJECTED:
qgcApp()->showMessage(tr("%1 command temporarily rejected").arg(commandName));
break;
case MAV_RESULT_DENIED:
qgcApp()->showMessage(tr("%1 command denied").arg(commandName));
break;
case MAV_RESULT_UNSUPPORTED:
qgcApp()->showMessage(tr("%1 command not supported").arg(commandName));
break;
case MAV_RESULT_FAILED:
qgcApp()->showMessage(tr("%1 command failed").arg(commandName));
break;
default:
// Do nothing
break;
}
}
_sendNextQueuedMavCommand();
}
void Vehicle::setPrearmError(const QString& prearmError)
{
_prearmError = prearmError;
emit prearmErrorChanged(_prearmError);
if (!_prearmError.isEmpty()) {
_prearmErrorTimer.start();
}
}
void Vehicle::_prearmErrorTimeout(void)
{
setPrearmError(QString());
}
void Vehicle::setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType)
{
_firmwareMajorVersion = majorVersion;
_firmwareMinorVersion = minorVersion;
_firmwarePatchVersion = patchVersion;
_firmwareVersionType = versionType;
emit firmwareVersionChanged();
}
void Vehicle::setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion)
{
_firmwareCustomMajorVersion = majorVersion;
_firmwareCustomMinorVersion = minorVersion;
_firmwareCustomPatchVersion = patchVersion;
emit firmwareCustomVersionChanged();
}
QString Vehicle::firmwareVersionTypeString(void) const
{
switch (_firmwareVersionType) {
case FIRMWARE_VERSION_TYPE_DEV:
return QStringLiteral("dev");
case FIRMWARE_VERSION_TYPE_ALPHA:
return QStringLiteral("alpha");
case FIRMWARE_VERSION_TYPE_BETA:
return QStringLiteral("beta");
case FIRMWARE_VERSION_TYPE_RC:
return QStringLiteral("rc");
case FIRMWARE_VERSION_TYPE_OFFICIAL:
default:
return QStringLiteral("");
}
mavlink_message_t msg;
mavlink_command_long_t cmd;
memset(&cmd, 0, sizeof(cmd));
cmd.target_system = _id;
cmd.target_component = _defaultComponentId;
cmd.command = MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN;
cmd.confirmation = 0;
cmd.param1 = 1;
cmd.param2 = cmd.param3 = cmd.param4 = cmd.param5 = cmd.param6 = cmd.param7 = 0;
mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&cmd);
sendMessageOnLink(priorityLink(), msg);
void Vehicle::setSoloFirmware(bool soloFirmware)
{
if (soloFirmware != _soloFirmware) {
_soloFirmware = soloFirmware;
emit soloFirmwareChanged(soloFirmware);
}
}
sendMavCommand(_defaultComponentId, MAV_CMD_DO_MOTOR_TEST, true, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs, 0, MOTOR_TEST_ORDER_BOARD);
QString Vehicle::brandImageIndoor(void) const
return _firmwarePlugin->brandImageIndoor(this);
}
QString Vehicle::brandImageOutdoor(void) const
{
return _firmwarePlugin->brandImageOutdoor(this);
3535
3536
3537
3538
3539
3540
3541
3542
3543
3544
3545
3546
3547
3548
3549
3550
3551
3552
3553
3554
3555
3556
3557
3558
3559
3560
3561
3562
3563
3564
3565
3566
3567
3568
3569
QStringList Vehicle::unhealthySensors(void) const
{
QStringList sensorList;
struct sensorInfo_s {
uint32_t bit;
const char* sensorName;
};
static const sensorInfo_s rgSensorInfo[] = {
{ MAV_SYS_STATUS_SENSOR_3D_GYRO, "Gyro" },
{ MAV_SYS_STATUS_SENSOR_3D_ACCEL, "Accelerometer" },
{ MAV_SYS_STATUS_SENSOR_3D_MAG, "Magnetometer" },
{ MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE, "Absolute pressure" },
{ MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE, "Differential pressure" },
{ MAV_SYS_STATUS_SENSOR_GPS, "GPS" },
{ MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, "Optical flow" },
{ MAV_SYS_STATUS_SENSOR_VISION_POSITION, "Computer vision position" },
{ MAV_SYS_STATUS_SENSOR_LASER_POSITION, "Laser based position" },
{ MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH, "External ground truth" },
{ MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL, "Angular rate control" },
{ MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION, "Attitude stabilization" },
{ MAV_SYS_STATUS_SENSOR_YAW_POSITION, "Yaw position" },
{ MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL, "Z/altitude control" },
{ MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL, "X/Y position control" },
{ MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS, "Motor outputs / control" },
{ MAV_SYS_STATUS_SENSOR_RC_RECEIVER, "RC receiver" },
{ MAV_SYS_STATUS_SENSOR_3D_GYRO2, "Gyro 2" },
{ MAV_SYS_STATUS_SENSOR_3D_ACCEL2, "Accelerometer 2" },
{ MAV_SYS_STATUS_SENSOR_3D_MAG2, "Magnetometer 2" },
{ MAV_SYS_STATUS_GEOFENCE, "GeoFence" },
{ MAV_SYS_STATUS_AHRS, "AHRS" },
{ MAV_SYS_STATUS_TERRAIN, "Terrain" },
{ MAV_SYS_STATUS_REVERSE_MOTOR, "Motors reversed" },
{ MAV_SYS_STATUS_LOGGING, "Logging" },
{ MAV_SYS_STATUS_SENSOR_BATTERY, "Battery" },
};
for (size_t i=0; i<sizeof(rgSensorInfo)/sizeof(sensorInfo_s); i++) {
const sensorInfo_s* pSensorInfo = &rgSensorInfo[i];
if ((_onboardControlSensorsEnabled & pSensorInfo->bit) && !(_onboardControlSensorsHealth & pSensorInfo->bit)) {
sensorList << pSensorInfo->sensorName;
}
}
return sensorList;
}
void Vehicle::setOfflineEditingDefaultComponentId(int defaultComponentId)
{
if (_offlineEditingVehicle) {
_defaultComponentId = defaultComponentId;
} else {
qWarning() << "Call to Vehicle::setOfflineEditingDefaultComponentId on vehicle which is not offline";
}
}
MAV_CMD_DO_DIGICAM_CONTROL,
true, // show errors
0.0, 0.0, 0.0, 0.0, // param 1-4 unused
1.0, // trigger camera
0.0, // param 6 unused
1.0); // test shot flag
void Vehicle::setVtolInFwdFlight(bool vtolInFwdFlight)
{
if (_vtolInFwdFlight != vtolInFwdFlight) {
sendMavCommand(_defaultComponentId,
MAV_CMD_DO_VTOL_TRANSITION,
true, // show errors
vtolInFwdFlight ? MAV_VTOL_STATE_FW : MAV_VTOL_STATE_MC, // transition state
0, 0, 0, 0, 0, 0); // param 2-7 unused
const char* VehicleGPSFactGroup::_latFactName = "lat";
const char* VehicleGPSFactGroup::_lonFactName = "lon";
const char* VehicleGPSFactGroup::_mgrsFactName = "mgrs";
const char* VehicleGPSFactGroup::_hdopFactName = "hdop";
const char* VehicleGPSFactGroup::_vdopFactName = "vdop";
const char* VehicleGPSFactGroup::_courseOverGroundFactName = "courseOverGround";
const char* VehicleGPSFactGroup::_countFactName = "count";
const char* VehicleGPSFactGroup::_lockFactName = "lock";
VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/GPSFact.json", parent)
, _latFact (0, _latFactName, FactMetaData::valueTypeDouble)
, _lonFact (0, _lonFactName, FactMetaData::valueTypeDouble)
, _mgrsFact (0, _mgrsFactName, FactMetaData::valueTypeString)
, _hdopFact (0, _hdopFactName, FactMetaData::valueTypeDouble)
, _vdopFact (0, _vdopFactName, FactMetaData::valueTypeDouble)
, _courseOverGroundFact (0, _courseOverGroundFactName, FactMetaData::valueTypeDouble)
, _countFact (0, _countFactName, FactMetaData::valueTypeInt32)
, _lockFact (0, _lockFactName, FactMetaData::valueTypeInt32)
{
_addFact(&_latFact, _latFactName);
_addFact(&_lonFact, _lonFactName);
_addFact(&_hdopFact, _hdopFactName);
_addFact(&_vdopFact, _vdopFactName);
_addFact(&_courseOverGroundFact, _courseOverGroundFactName);
_addFact(&_lockFact, _lockFactName);
_addFact(&_countFact, _countFactName);
_latFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
_lonFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
_hdopFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
_vdopFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
_courseOverGroundFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
void Vehicle::startMavlinkLog()
sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_START, false /* showError */);
sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_STOP, false /* showError */);
void Vehicle::_ackMavlinkLogData(uint16_t sequence)
{
mavlink_message_t msg;
mavlink_logging_ack_t ack;
ack.sequence = sequence;
ack.target_component = _defaultComponentId;
ack.target_system = id();
mavlink_msg_logging_ack_encode_chan(
_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&ack);
sendMessageOnLink(priorityLink(), msg);
}
void Vehicle::_handleMavlinkLoggingData(mavlink_message_t& message)
{
mavlink_logging_data_t log;
mavlink_msg_logging_data_decode(&message, &log);
emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
log.first_message_offset, QByteArray((const char*)log.data, log.length), false);
void Vehicle::_handleMavlinkLoggingDataAcked(mavlink_message_t& message)
Beat Küng
committed
mavlink_logging_data_acked_t log;
mavlink_msg_logging_data_acked_decode(&message, &log);
_ackMavlinkLogData(log.sequence);
emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
log.first_message_offset, QByteArray((const char*)log.data, log.length), true);
void Vehicle::setFirmwarePluginInstanceData(QObject* firmwarePluginInstanceData)
{
firmwarePluginInstanceData->setParent(this);
_firmwarePluginInstanceData = firmwarePluginInstanceData;
}
QString Vehicle::missionFlightMode(void) const
{
return _firmwarePlugin->missionFlightMode();
}
QString Vehicle::pauseFlightMode(void) const
{
return _firmwarePlugin->pauseFlightMode();
}
QString Vehicle::rtlFlightMode(void) const
{
return _firmwarePlugin->rtlFlightMode();
}
QString Vehicle::smartRTLFlightMode(void) const
{
return _firmwarePlugin->smartRTLFlightMode();
}
bool Vehicle::supportsSmartRTL(void) const
{
return _firmwarePlugin->supportsSmartRTL();
}
QString Vehicle::landFlightMode(void) const
{
return _firmwarePlugin->landFlightMode();
}
QString Vehicle::takeControlFlightMode(void) const
{
return _firmwarePlugin->takeControlFlightMode();
}
QString Vehicle::followFlightMode(void) const
{
return _firmwarePlugin->followFlightMode();
}
3741
3742
3743
3744
3745
3746
3747
3748
3749
3750
3751
3752
3753
3754
3755
3756
3757
3758
3759
3760
3761
3762
3763
3764
QString Vehicle::vehicleImageOpaque() const
{
if(_firmwarePlugin)
return _firmwarePlugin->vehicleImageOpaque(this);
else
return QString();
}
QString Vehicle::vehicleImageOutline() const
{
if(_firmwarePlugin)
return _firmwarePlugin->vehicleImageOutline(this);
else
return QString();
}
QString Vehicle::vehicleImageCompass() const
{
if(_firmwarePlugin)
return _firmwarePlugin->vehicleImageCompass(this);
else
return QString();
}
const QVariantList& Vehicle::toolBarIndicators()
{
if(_firmwarePlugin) {
return _firmwarePlugin->toolBarIndicators(this);
}
static QVariantList emptyList;
return emptyList;
}
const QVariantList& Vehicle::staticCameraList(void) const
{
if (_firmwarePlugin) {
return _firmwarePlugin->cameraList(this);
}
static QVariantList emptyList;
return emptyList;
}
bool Vehicle::vehicleYawsToNextWaypointInMission(void) const
{
return _firmwarePlugin->vehicleYawsToNextWaypointInMission(this);
}
3788
3789
3790
3791
3792
3793
3794
3795
3796
3797
3798
3799
3800
3801
3802
3803
3804
3805
3806
3807
3808
3809
3810
void Vehicle::_setupAutoDisarmSignalling(void)
{
QString param = _firmwarePlugin->autoDisarmParameter(this);
if (!param.isEmpty() && _parameterManager->parameterExists(FactSystem::defaultComponentId, param)) {
Fact* fact = _parameterManager->getParameter(FactSystem::defaultComponentId,param);
connect(fact, &Fact::rawValueChanged, this, &Vehicle::autoDisarmChanged);
emit autoDisarmChanged();
}
}
bool Vehicle::autoDisarm(void)
{
QString param = _firmwarePlugin->autoDisarmParameter(this);
if (!param.isEmpty() && _parameterManager->parameterExists(FactSystem::defaultComponentId, param)) {
Fact* fact = _parameterManager->getParameter(FactSystem::defaultComponentId,param);
return fact->rawValue().toDouble() > 0;
}
return false;
}
void Vehicle::_handleADSBVehicle(const mavlink_message_t& message)
{
mavlink_msg_adsb_vehicle_decode(&message, &adsbVehicleMsg);
if (adsbVehicleMsg.flags | ADSB_FLAGS_VALID_COORDS && adsbVehicleMsg.tslc <= maxTimeSinceLastSeen) {
ADSBVehicle::VehicleInfo_t vehicleInfo;
vehicleInfo.availableFlags = 0;
vehicleInfo.location.setLatitude(adsbVehicleMsg.lat / 1e7);
vehicleInfo.location.setLatitude(adsbVehicleMsg.lon / 1e7);
vehicleInfo.callsign = adsbVehicleMsg.callsign;
vehicleInfo.availableFlags |= ADSBVehicle::CallsignAvailable;
if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_ALTITUDE) {
vehicleInfo.altitude = (double)adsbVehicleMsg.altitude / 1e3;
vehicleInfo.availableFlags |= ADSBVehicle::AltitudeAvailable;
}
if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_HEADING) {
vehicleInfo.heading = (double)adsbVehicleMsg.heading / 100.0;
vehicleInfo.availableFlags |= ADSBVehicle::HeadingAvailable;
{
if (coordinate().isValid() && homePosition().isValid()) {
_distanceToHomeFact.setRawValue(coordinate().distanceTo(homePosition()));
if (_distanceToHomeFact.rawValue().toDouble() > 1.0) {
_headingToHomeFact.setRawValue(coordinate().azimuthTo(homePosition()));
} else {
_headingToHomeFact.setRawValue(qQNaN());
}
} else {
_distanceToHomeFact.setRawValue(qQNaN());
void Vehicle::_updateHeadingToNextWP(void)
{
const int _currentIndex = _missionManager->currentIndex();
MissionItem _currentItem;
QList<MissionItem*> llist = _missionManager->missionItems();
if(llist.size()>_currentIndex && _currentIndex!=-1
&& llist[_currentIndex]->coordinate().longitude()!=0.0
&& coordinate().distanceTo(llist[_currentIndex]->coordinate())>5.0 ){
_headingToNextWPFact.setRawValue(coordinate().azimuthTo(llist[_currentIndex]->coordinate()));
}
else{
_headingToNextWPFact.setRawValue(qQNaN());
}
}
void Vehicle::_updateDistanceToGCS(void)
{
QGeoCoordinate gcsPosition = _toolbox->qgcPositionManager()->gcsPosition();
if (coordinate().isValid() && gcsPosition.isValid()) {
_distanceToGCSFact.setRawValue(coordinate().distanceTo(gcsPosition));
} else {
_distanceToGCSFact.setRawValue(qQNaN());
}
}
void Vehicle::_updateHobbsMeter(void)
{
_hobbsFact.setRawValue(hobbsMeter());
}
void Vehicle::forceInitialPlanRequestComplete(void)
{
_initialPlanRequestComplete = true;
emit initialPlanRequestCompleteChanged(true);
}
void Vehicle::sendPlan(QString planFile)
{
PlanMasterController::sendPlanToVehicle(this, planFile);
}
QString Vehicle::hobbsMeter()
{
static const char* HOOBS_HI = "LND_FLIGHT_T_HI";
static const char* HOOBS_LO = "LND_FLIGHT_T_LO";
//-- TODO: Does this exist on non PX4?
if (_parameterManager->parameterExists(FactSystem::defaultComponentId, HOOBS_HI) &&
_parameterManager->parameterExists(FactSystem::defaultComponentId, HOOBS_LO)) {
Fact* factHi = _parameterManager->getParameter(FactSystem::defaultComponentId, HOOBS_HI);
Fact* factLo = _parameterManager->getParameter(FactSystem::defaultComponentId, HOOBS_LO);
Gus Grubba
committed
uint64_t hobbsTimeSeconds = ((uint64_t)factHi->rawValue().toUInt() << 32 | (uint64_t)factLo->rawValue().toUInt()) / 1000000;
int hours = hobbsTimeSeconds / 3600;
int minutes = (hobbsTimeSeconds % 3600) / 60;
int seconds = hobbsTimeSeconds % 60;
QString timeStr;
timeStr.sprintf("%04d:%02d:%02d", hours, minutes, seconds);
qCDebug(VehicleLog) << "Hobbs Meter:" << timeStr << "(" << factHi->rawValue().toUInt() << factLo->rawValue().toUInt() << ")";
return timeStr;
}
return QString("0000:00:00");
}
void Vehicle::_vehicleParamLoaded(bool ready)
{
//-- TODO: This seems silly but can you think of a better
// way to update this?
if(ready) {
emit hobbsMeterChanged();
}
}
void Vehicle::_updateHighLatencyLink(bool sendCommand)
if (!_priorityLink) {
return;
}
if (_priorityLink->highLatency() != _highLatencyLink) {
_highLatencyLink = _priorityLink->highLatency();
_mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
emit highLatencyLinkChanged(_highLatencyLink);
if (sendCommand) {
sendMavCommand(defaultComponentId(),
MAV_CMD_CONTROL_HIGH_LATENCY,
true,
_highLatencyLink ? 1.0f : 0.0f); // request start/stop transmitting over high latency telemetry
void Vehicle::_trafficUpdate(bool /*alert*/, QString /*traffic_id*/, QString /*vehicle_id*/, QGeoCoordinate /*location*/, float /*heading*/)
#if 0
// This is ifdef'ed out for now since this code doesn't mesh with the recent ADSB manager changes. Also airmap isn't in any
// released build. So not going to waste time trying to fix up unused code.
if (_trafficVehicleMap.contains(traffic_id)) {
_trafficVehicleMap[traffic_id]->update(alert, location, heading);
ADSBVehicle* vehicle = new ADSBVehicle(location, heading, alert, this);
_trafficVehicleMap[traffic_id] = vehicle;
_adsbVehicles.append(vehicle);
}
void Vehicle::_mavlinkMessageStatus(int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent)
{
if(uasId == _id) {
_mavlinkSentCount = totalSent;
_mavlinkReceivedCount = totalReceived;
_mavlinkLossCount = totalLoss;
_mavlinkLossPercent = lossPercent;
emit mavlinkStatusChanged();
}
}
int Vehicle::versionCompare(QString& compare)
{
return _firmwarePlugin->versionCompare(this, compare);
}
int Vehicle::versionCompare(int major, int minor, int patch)
{
return _firmwarePlugin->versionCompare(this, major, minor, patch);
}
if (_pidTuningWaitingForRates) {
mavlink_message_interval_t messageInterval;
mavlink_msg_message_interval_decode(&message, &messageInterval);
int msgId = messageInterval.message_id;
if (_pidTuningMessages.contains(msgId)) {
_pidTuningMessageRatesUsecs[msgId] = messageInterval.interval_us;
}