Newer
Older
_rcRSSI = filteredRSSI;
emit rcRSSIChanged(_rcRSSI);
}
}
void Vehicle::virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
{
// The following if statement prevents the virtualTabletJoystick from sending values if the standard joystick is enabled
if ( !_joystickEnabled ) {
_uas->setExternalControlSetpoint(roll, pitch, yaw, thrust, 0, JoystickModeRC);
}
void Vehicle::setConnectionLostEnabled(bool connectionLostEnabled)
{
if (_connectionLostEnabled != connectionLostEnabled) {
_connectionLostEnabled = connectionLostEnabled;
emit connectionLostEnabledChanged(_connectionLostEnabled);
}
}
void Vehicle::_connectionLostTimeout(void)
{
if (_connectionLostEnabled && !_connectionLost) {
_connectionLost = true;
_heardFrom = false;
Lorenz Meier
committed
_maxProtoVersion = 0;
_say(QString("%1 communication lost").arg(_vehicleIdSpeech()));
Lorenz Meier
committed
// Reset link state
for (int i = 0; i < _links.length(); i++) {
_mavlink->resetMetadataForLink(_links.at(i));
}
}
}
void Vehicle::_connectionActive(void)
{
_connectionLostTimer.start();
if (_connectionLost) {
_connectionLost = false;
emit connectionLostChanged(false);
_say(QString("%1 communication regained").arg(_vehicleIdSpeech()));
Lorenz Meier
committed
// Re-negotiate protocol version for the link
sendMavCommand(MAV_COMP_ID_ALL, // Don't know default component id yet.
MAV_CMD_REQUEST_PROTOCOL_VERSION,
false, // No error shown if fails
1); // Request protocol version
_toolbox->audioOutput()->say(text.toLower());
bool Vehicle::fixedWing(void) const
{
return QGCMAVLink::isFixedWing(vehicleType());
return QGCMAVLink::isRover(vehicleType());
bool Vehicle::sub(void) const
{
return QGCMAVLink::isSub(vehicleType());
bool Vehicle::multiRotor(void) const
{
return QGCMAVLink::isMultiRotor(vehicleType());
return _firmwarePlugin->isVtol(this);
bool Vehicle::supportsThrottleModeCenterZero(void) const
{
return _firmwarePlugin->supportsThrottleModeCenterZero();
}
bool Vehicle::supportsNegativeThrust(void) const
{
return _firmwarePlugin->supportsNegativeThrust();
}
bool Vehicle::supportsRadio(void) const
{
return _firmwarePlugin->supportsRadio();
}
bool Vehicle::supportsJSButton(void) const
{
return _firmwarePlugin->supportsJSButton();
}
bool Vehicle::supportsMotorInterference(void) const
{
return _firmwarePlugin->supportsMotorInterference();
}
2112
2113
2114
2115
2116
2117
2118
2119
2120
2121
2122
2123
2124
2125
2126
2127
2128
2129
2130
2131
2132
2133
2134
2135
2136
2137
2138
2139
2140
2141
2142
2143
2144
2145
QString Vehicle::vehicleTypeName() const {
static QMap<int, QString> typeNames = {
{ MAV_TYPE_GENERIC, tr("Generic micro air vehicle" )},
{ MAV_TYPE_FIXED_WING, tr("Fixed wing aircraft")},
{ MAV_TYPE_QUADROTOR, tr("Quadrotor")},
{ MAV_TYPE_COAXIAL, tr("Coaxial helicopter")},
{ MAV_TYPE_HELICOPTER, tr("Normal helicopter with tail rotor.")},
{ MAV_TYPE_ANTENNA_TRACKER, tr("Ground installation")},
{ MAV_TYPE_GCS, tr("Operator control unit / ground control station")},
{ MAV_TYPE_AIRSHIP, tr("Airship, controlled")},
{ MAV_TYPE_FREE_BALLOON, tr("Free balloon, uncontrolled")},
{ MAV_TYPE_ROCKET, tr("Rocket")},
{ MAV_TYPE_GROUND_ROVER, tr("Ground rover")},
{ MAV_TYPE_SURFACE_BOAT, tr("Surface vessel, boat, ship")},
{ MAV_TYPE_SUBMARINE, tr("Submarine")},
{ MAV_TYPE_HEXAROTOR, tr("Hexarotor")},
{ MAV_TYPE_OCTOROTOR, tr("Octorotor")},
{ MAV_TYPE_TRICOPTER, tr("Octorotor")},
{ MAV_TYPE_FLAPPING_WING, tr("Flapping wing")},
{ MAV_TYPE_KITE, tr("Flapping wing")},
{ MAV_TYPE_ONBOARD_CONTROLLER, tr("Onboard companion controller")},
{ MAV_TYPE_VTOL_DUOROTOR, tr("Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter")},
{ MAV_TYPE_VTOL_QUADROTOR, tr("Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter")},
{ MAV_TYPE_VTOL_TILTROTOR, tr("Tiltrotor VTOL")},
{ MAV_TYPE_VTOL_RESERVED2, tr("VTOL reserved 2")},
{ MAV_TYPE_VTOL_RESERVED3, tr("VTOL reserved 3")},
{ MAV_TYPE_VTOL_RESERVED4, tr("VTOL reserved 4")},
{ MAV_TYPE_VTOL_RESERVED5, tr("VTOL reserved 5")},
{ MAV_TYPE_GIMBAL, tr("Onboard gimbal")},
{ MAV_TYPE_ADSB, tr("Onboard ADSB peripheral")},
};
return typeNames[_vehicleType];
}
/// Returns the string to speak to identify the vehicle
QString Vehicle::_vehicleIdSpeech(void)
{
if (_toolbox->multiVehicleManager()->vehicles()->count() > 1) {
return QString("vehicle %1").arg(id());
} else {
void Vehicle::_handleFlightModeChanged(const QString& flightMode)
_say(QString("%1 %2 flight mode").arg(_vehicleIdSpeech()).arg(flightMode));
emit guidedModeChanged(_firmwarePlugin->isGuidedMode(this));
}
void Vehicle::_announceArmedChanged(bool armed)
{
_say(QString("%1 %2").arg(_vehicleIdSpeech()).arg(armed ? QStringLiteral("armed") : QStringLiteral("disarmed")));
void Vehicle::_setFlying(bool flying)
_flying = flying;
emit flyingChanged(flying);
}
}
void Vehicle::_setLanding(bool landing)
{
if (armed() && _landing != landing) {
_landing = landing;
emit landingChanged(landing);
}
}
bool Vehicle::guidedModeSupported(void) const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::GuidedModeCapability);
}
bool Vehicle::pauseVehicleSupported(void) const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::PauseVehicleCapability);
}
bool Vehicle::orbitModeSupported() const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::OrbitModeCapability);
bool Vehicle::takeoffVehicleSupported() const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::TakeoffVehicleCapability);
}
void Vehicle::guidedModeRTL(void)
{
if (!guidedModeSupported()) {
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
return;
}
_firmwarePlugin->guidedModeRTL(this);
}
void Vehicle::guidedModeLand(void)
{
if (!guidedModeSupported()) {
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
return;
}
_firmwarePlugin->guidedModeLand(this);
}
void Vehicle::guidedModeTakeoff(void)
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
_firmwarePlugin->guidedModeTakeoff(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 = 1000.0;
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()));
return;
}
_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 velocity, double altitude)
{
if (!orbitModeSupported()) {
qgcApp()->showMessage(QStringLiteral("Orbit mode not supported by Vehicle."));
return;
}
_firmwarePlugin->guidedModeOrbit(this, centerCoord, radius, velocity, 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
Danny Schrader
committed
climbOutAltitude);
}
bool Vehicle::guidedMode(void) const
{
return _firmwarePlugin->isGuidedMode(this);
}
void Vehicle::setGuidedMode(bool guidedMode)
{
return _firmwarePlugin->setGuidedMode(this, guidedMode);
}
void Vehicle::emergencyStop(void)
{
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(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
id(),
_compID,
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)
2325
2326
2327
2328
2329
2330
2331
2332
2333
2334
2335
2336
2337
2338
2339
2340
2341
2342
2343
2344
2345
2346
2347
MavCommandQueueEntry_t entry;
entry.component = component;
entry.command = command;
entry.showError = showError;
entry.rgParam[0] = param1;
entry.rgParam[1] = param2;
entry.rgParam[2] = param3;
entry.rgParam[3] = param4;
entry.rgParam[4] = param5;
entry.rgParam[5] = param6;
entry.rgParam[6] = param7;
_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) {
// We aren't going to get a response back for capabilities, so stop waiting for it before we ask for mission items
qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES. Setting no capabilities. Starting Plan request.";
if (queuedCommand.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) {
Lorenz Meier
committed
// We aren't going to get a response back for the protocol version, so assume v1 is all we can do.
// If the max protocol version is uninitialized, fall back to v1.
qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_PROTOCOL_VERSION. Starting Plan request.";
Lorenz Meier
committed
if (_maxProtoVersion == 0) {
qCDebug(VehicleLog) << "Setting _maxProtoVersion to 100 since not yet set.";
Lorenz Meier
committed
_setMaxProtoVersion(100);
} else {
qCDebug(VehicleLog) << "Leaving _maxProtoVersion at current value" << _maxProtoVersion;
Lorenz Meier
committed
}
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;
}
// We always let AUTOPILOT_CAPABILITIES go through multiple times even if we don't get acks. This is because
// we really need to get capabilities and version info back over a lossy link.
if (queuedCommand.command != MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
if (px4Firmware()) {
// Older PX4 firmwares are inconsistent with repect to sending back an Ack from a COMMAND_LONG, hence we can't support retry logic for it.
if (_firmwareMajorVersion != versionNotSetValue) {
// If no version set assume lastest master dev build, so acks are suppored
if (_firmwareMajorVersion <= 1 && _firmwareMinorVersion <= 5 && _firmwarePatchVersion <= 3) {
// Acks not supported in this version
return;
}
}
} else {
if (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();
mavlink_message_t msg;
mavlink_command_long_t cmd;
cmd.command = queuedCommand.command;
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];
cmd.target_system = _id;
cmd.target_component = queuedCommand.component;
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();
}
}
2444
2445
2446
2447
2448
2449
2450
2451
2452
2453
2454
2455
2456
2457
2458
2459
2460
2461
2462
2463
2464
2465
2466
2467
2468
2469
2470
2471
2472
2473
2474
2475
2476
2477
2478
2479
2480
2481
2482
2483
2484
2485
2486
2487
2488
2489
2490
2491
2492
2493
2494
2495
2496
2497
2498
2499
2500
2501
2502
2503
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) {
// We aren't going to get a response back for capabilities, so stop waiting for it before we ask for mission items
qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities. Starting Plan request.").arg(ack.result);
_setCapabilities(0);
}
if (ack.command == MAV_CMD_REQUEST_PROTOCOL_VERSION && ack.result != MAV_RESULT_ACCEPTED) {
// The autopilot does not understand the request and consequently is likely handling only
// MAVLink 1
qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_PROTOCOL_VERSION with error(%1).").arg(ack.result);
if (_maxProtoVersion == 0) {
qCDebug(VehicleLog) << "Setting _maxProtoVersion to 100 since not yet set.";
_setMaxProtoVersion(100);
} else {
qCDebug(VehicleLog) << "Leaving _maxProtoVersion at current value" << _maxProtoVersion;
}
// FIXME: Is this missing here. I believe it is a bug. Debug to verify. May need to go into Stable.
//_startPlanRequest();
}
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((MAV_CMD)ack.command);
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("");
}
sendMavCommand(_defaultComponentId, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, true, 1.0f);
void Vehicle::setSoloFirmware(bool soloFirmware)
{
if (soloFirmware != _soloFirmware) {
_soloFirmware = soloFirmware;
emit soloFirmwareChanged(soloFirmware);
}
}
#if 0
// Temporarily removed, waiting for new command implementation
void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
{
doCommandLongUnverified(_defaultComponentId, MAV_CMD_DO_MOTOR_TEST, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs);
QString Vehicle::brandImageIndoor(void) const
return _firmwarePlugin->brandImageIndoor(this);
}
QString Vehicle::brandImageOutdoor(void) const
{
return _firmwarePlugin->brandImageOutdoor(this);
2583
2584
2585
2586
2587
2588
2589
2590
2591
2592
2593
2594
2595
2596
2597
2598
2599
2600
2601
2602
2603
2604
2605
2606
2607
2608
2609
2610
2611
2612
2613
2614
2615
2616
2617
2618
2619
2620
2621
2622
2623
2624
2625
2626
2627
2628
2629
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" },
};
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
const char* VehicleGPSFactGroup::_latFactName = "lat";
const char* VehicleGPSFactGroup::_lonFactName = "lon";
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)
, _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::landFlightMode(void) const
{
return _firmwarePlugin->landFlightMode();
}
QString Vehicle::takeControlFlightMode(void) const
{
return _firmwarePlugin->takeControlFlightMode();
}
2758
2759
2760
2761
2762
2763
2764
2765
2766
2767
2768
2769
2770
2771
2772
2773
2774
2775
2776
2777
2778
2779
2780
2781
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);
}
2805
2806
2807
2808
2809
2810
2811
2812
2813
2814
2815
2816
2817
2818
2819
2820
2821
2822
2823
2824
2825
2826
2827
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_adsb_vehicle_t adsbVehicle;
mavlink_msg_adsb_vehicle_decode(&message, &adsbVehicle);
if (adsbVehicle.flags | ADSB_FLAGS_VALID_COORDS) {
if (_adsbICAOMap.contains(adsbVehicle.ICAO_address)) {
if (adsbVehicle.tslc > maxTimeSinceLastSeen) {
ADSBVehicle* vehicle = _adsbICAOMap[adsbVehicle.ICAO_address];
_adsbVehicles.removeOne(vehicle);
_adsbICAOMap.remove(adsbVehicle.ICAO_address);
vehicle->deleteLater();
} else {
_adsbICAOMap[adsbVehicle.ICAO_address]->update(adsbVehicle);
ADSBVehicle* vehicle = new ADSBVehicle(adsbVehicle, this);
_adsbICAOMap[adsbVehicle.ICAO_address] = vehicle;
_adsbVehicles.append(vehicle);
}
}
}
void Vehicle::_updateDistanceToHome(void)
{
if (coordinate().isValid() && homePosition().isValid()) {
_distanceToHomeFact.setRawValue(coordinate().distanceTo(homePosition()));
} else {
_distanceToHomeFact.setRawValue(qQNaN());
}
}
void Vehicle::forceInitialPlanRequestComplete(void)
{
_initialPlanRequestComplete = true;
emit initialPlanRequestCompleteChanged(true);
}
void Vehicle::sendPlan(QString planFile)
{
PlanMasterController::sendPlanToVehicle(this, planFile);
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
const char* VehicleBatteryFactGroup::_voltageFactName = "voltage";
const char* VehicleBatteryFactGroup::_percentRemainingFactName = "percentRemaining";
const char* VehicleBatteryFactGroup::_mahConsumedFactName = "mahConsumed";
const char* VehicleBatteryFactGroup::_currentFactName = "current";
const char* VehicleBatteryFactGroup::_temperatureFactName = "temperature";
const char* VehicleBatteryFactGroup::_cellCountFactName = "cellCount";
const char* VehicleBatteryFactGroup::_settingsGroup = "Vehicle.battery";
const double VehicleBatteryFactGroup::_voltageUnavailable = -1.0;
const int VehicleBatteryFactGroup::_percentRemainingUnavailable = -1;
const int VehicleBatteryFactGroup::_mahConsumedUnavailable = -1;
const int VehicleBatteryFactGroup::_currentUnavailable = -1;
const double VehicleBatteryFactGroup::_temperatureUnavailable = -1.0;
const int VehicleBatteryFactGroup::_cellCountUnavailable = -1.0;
VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/BatteryFact.json", parent)
, _voltageFact (0, _voltageFactName, FactMetaData::valueTypeDouble)
, _percentRemainingFact (0, _percentRemainingFactName, FactMetaData::valueTypeInt32)
, _mahConsumedFact (0, _mahConsumedFactName, FactMetaData::valueTypeInt32)
, _currentFact (0, _currentFactName, FactMetaData::valueTypeFloat)
, _temperatureFact (0, _temperatureFactName, FactMetaData::valueTypeDouble)
, _cellCountFact (0, _cellCountFactName, FactMetaData::valueTypeInt32)
{
_addFact(&_voltageFact, _voltageFactName);
_addFact(&_percentRemainingFact, _percentRemainingFactName);
_addFact(&_mahConsumedFact, _mahConsumedFactName);
_addFact(&_currentFact, _currentFactName);
_addFact(&_temperatureFact, _temperatureFactName);
_addFact(&_cellCountFact, _cellCountFactName);
// Start out as not available
_voltageFact.setRawValue (_voltageUnavailable);
_percentRemainingFact.setRawValue (_percentRemainingUnavailable);
_mahConsumedFact.setRawValue (_mahConsumedUnavailable);
_currentFact.setRawValue (_currentUnavailable);
_temperatureFact.setRawValue (_temperatureUnavailable);
_cellCountFact.setRawValue (_cellCountUnavailable);
}
const char* VehicleWindFactGroup::_directionFactName = "direction";
const char* VehicleWindFactGroup::_speedFactName = "speed";
const char* VehicleWindFactGroup::_verticalSpeedFactName = "verticalSpeed";
VehicleWindFactGroup::VehicleWindFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/WindFact.json", parent)
, _directionFact (0, _directionFactName, FactMetaData::valueTypeDouble)
, _speedFact (0, _speedFactName, FactMetaData::valueTypeDouble)
, _verticalSpeedFact(0, _verticalSpeedFactName, FactMetaData::valueTypeDouble)
{
_addFact(&_directionFact, _directionFactName);
_addFact(&_speedFact, _speedFactName);
_addFact(&_verticalSpeedFact, _verticalSpeedFactName);
// Start out as not available "--.--"
_directionFact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_speedFact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_verticalSpeedFact.setRawValue (std::numeric_limits<float>::quiet_NaN());
}
const char* VehicleVibrationFactGroup::_xAxisFactName = "xAxis";
const char* VehicleVibrationFactGroup::_yAxisFactName = "yAxis";
const char* VehicleVibrationFactGroup::_zAxisFactName = "zAxis";
const char* VehicleVibrationFactGroup::_clipCount1FactName = "clipCount1";
const char* VehicleVibrationFactGroup::_clipCount2FactName = "clipCount2";
const char* VehicleVibrationFactGroup::_clipCount3FactName = "clipCount3";
2944
2945
2946
2947
2948
2949
2950
2951
2952
2953
2954
2955
2956
2957
2958
2959
2960
2961
2962
2963
2964
VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/VibrationFact.json", parent)
, _xAxisFact (0, _xAxisFactName, FactMetaData::valueTypeDouble)
, _yAxisFact (0, _yAxisFactName, FactMetaData::valueTypeDouble)
, _zAxisFact (0, _zAxisFactName, FactMetaData::valueTypeDouble)
, _clipCount1Fact (0, _clipCount1FactName, FactMetaData::valueTypeUint32)
, _clipCount2Fact (0, _clipCount2FactName, FactMetaData::valueTypeUint32)
, _clipCount3Fact (0, _clipCount3FactName, FactMetaData::valueTypeUint32)
{
_addFact(&_xAxisFact, _xAxisFactName);
_addFact(&_yAxisFact, _yAxisFactName);
_addFact(&_zAxisFact, _zAxisFactName);
_addFact(&_clipCount1Fact, _clipCount1FactName);
_addFact(&_clipCount2Fact, _clipCount2FactName);
_addFact(&_clipCount3Fact, _clipCount3FactName);
// Start out as not available "--.--"
_xAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
_yAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
_zAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
}
2965
2966
2967
2968
2969
2970
2971
2972
2973
2974
2975
2976
2977
2978
2979
2980
2981
2982
2983
2984
2985
const char* VehicleTemperatureFactGroup::_temperature1FactName = "temperature1";
const char* VehicleTemperatureFactGroup::_temperature2FactName = "temperature2";
const char* VehicleTemperatureFactGroup::_temperature3FactName = "temperature3";
VehicleTemperatureFactGroup::VehicleTemperatureFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/TemperatureFact.json", parent)
, _temperature1Fact (0, _temperature1FactName, FactMetaData::valueTypeDouble)
, _temperature2Fact (0, _temperature2FactName, FactMetaData::valueTypeDouble)
, _temperature3Fact (0, _temperature3FactName, FactMetaData::valueTypeDouble)
{
_addFact(&_temperature1Fact, _temperature1FactName);
_addFact(&_temperature2Fact, _temperature2FactName);
_addFact(&_temperature3Fact, _temperature3FactName);
// Start out as not available "--.--"
_temperature1Fact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_temperature2Fact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_temperature3Fact.setRawValue (std::numeric_limits<float>::quiet_NaN());
}