Newer
Older
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
// THIS CLASS IS DEPRECATED. ALL NEW FUNCTIONALITY SHOULD GO INTO Vehicle class
#include <QList>
#include <QTimer>
#include <QSettings>
#include <iostream>
#include <QDebug>
#include <cmath>
#include <qmath.h>
#include <limits>
#include <cstdlib>
#include "UAS.h"
#include "LinkInterface.h"
#include "QGC.h"
#include "GAudioOutput.h"
#include "MAVLinkProtocol.h"
#include "QGCMAVLink.h"
#include "LinkManager.h"
#include "SerialLink.h"
#include "QGCLoggingCategory.h"
#include "QGCApplication.h"
QGC_LOGGING_CATEGORY(UASLog, "UASLog")
// THIS CLASS IS DEPRECATED. ALL NEW FUNCTIONALITY SHOULD GO INTO Vehicle class
UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * firmwarePluginManager) : UASInterface(),
lipoFull(4.2f),
lipoEmpty(3.5f),
unknownPackets(),
mavlink(protocol),
receiveDropRate(0),
sendDropRate(0),
status(-1),
startTime(QGC::groundTimeMilliseconds()),
onboardTimeOffset(0),
controlRollManual(true),
controlPitchManual(true),
controlYawManual(true),
controlThrustManual(true),
manualRollAngle(0),
manualPitchAngle(0),
manualYawAngle(0),
manualThrust(0),
attitudeKnown(false),
attitudeStamped(false),
lastAttitude(0),
roll(0.0),
pitch(0.0),
yaw(0.0),
imagePackets(0), // We must initialize to 0, otherwise extended data packets maybe incorrectly thought to be images
// Note variances calculated from flight case from this log: http://dash.oznet.ch/view/MRjW8NUNYQSuSZkbn8dEjY
// TODO: calibrate stand-still pixhawk variances
xacc_var(0.6457f),
zacc_var(0.97885f),
rollspeed_var(0.8126f),
pitchspeed_var(0.6145f),
yawspeed_var(0.5852f),
xmag_var(0.2393f),
ymag_var(0.2283f),
zmag_var(0.1665f),
abs_pressure_var(0.5802f),
diff_pressure_var(0.5802f),
pressure_alt_var(0.5802f),
temperature_var(0.7145f),
Lorenz Meier
committed
/*
xacc_var(0.0f),
yacc_var(0.0f),
zacc_var(0.0f),
rollspeed_var(0.0f),
pitchspeed_var(0.0f),
yawspeed_var(0.0f),
xmag_var(0.0f),
ymag_var(0.0f),
zmag_var(0.0f),
abs_pressure_var(0.0f),
diff_pressure_var(0.0f),
pressure_alt_var(0.0f),
temperature_var(0.0f),
Lorenz Meier
committed
*/
// The protected members.
connectionLost(false),
lastVoltageWarning(0),
lastNonNullTime(0),
onboardTimeOffsetInvalidCount(0),
hilEnabled(false),
sensorHil(false),
lastSendTimeGPS(0),
_vehicle(vehicle),
_firmwarePluginManager(firmwarePluginManager)
for (unsigned int i = 0; i<255;++i)
{
componentID[i] = -1;
componentMulti[i] = false;
}
connect(_vehicle, &Vehicle::mavlinkMessageReceived, &fileManager, &FileManager::receiveMessage);
color = UASInterface::getNextColor();
}
/**
* @ return the id of the uas
*/
int UAS::getUASID() const
{
return uasId;
}
void UAS::receiveMessage(mavlink_message_t message)
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
{
if (!components.contains(message.compid))
{
QString componentName;
switch (message.compid)
{
case MAV_COMP_ID_ALL:
{
componentName = "ANONYMOUS";
break;
}
case MAV_COMP_ID_IMU:
{
componentName = "IMU #1";
break;
}
case MAV_COMP_ID_CAMERA:
{
componentName = "CAMERA";
break;
}
case MAV_COMP_ID_MISSIONPLANNER:
{
componentName = "MISSIONPLANNER";
break;
}
}
components.insert(message.compid, componentName);
}
// qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq;
// Only accept messages from this system (condition 1)
// and only then if a) attitudeStamped is disabled OR b) attitudeStamped is enabled
// and we already got one attitude packet
if (message.sysid == uasId && (!attitudeStamped || (attitudeStamped && (lastAttitude != 0)) || message.msgid == MAVLINK_MSG_ID_ATTITUDE))
{
QString uasState;
QString stateDescription;
bool multiComponentSourceDetected = false;
bool wrongComponent = false;
switch (message.compid)
{
case MAV_COMP_ID_IMU_2:
// Prefer IMU 2 over IMU 1 (FIXME)
componentID[message.msgid] = MAV_COMP_ID_IMU_2;
break;
default:
// Do nothing
break;
}
// Store component ID
if (componentID[message.msgid] == -1)
{
// Prefer the first component
componentID[message.msgid] = message.compid;
}
else
{
// Got this message already
if (componentID[message.msgid] != message.compid)
{
componentMulti[message.msgid] = true;
wrongComponent = true;
}
}
if (componentMulti[message.msgid] == true) multiComponentSourceDetected = true;
switch (message.msgid)
{
case MAVLINK_MSG_ID_HEARTBEAT:
{
if (multiComponentSourceDetected && wrongComponent)
{
break;
}
mavlink_heartbeat_t state;
mavlink_msg_heartbeat_decode(&message, &state);
// Send the base_mode and system_status values to the plotter. This uses the ground time
// so the Ground Time checkbox must be ticked for these values to display
quint64 time = getUnixTime();
QString name = QString("M%1:HEARTBEAT.%2").arg(message.sysid);
emit valueChanged(uasId, name.arg("base_mode"), "bits", state.base_mode, time);
emit valueChanged(uasId, name.arg("custom_mode"), "bits", state.custom_mode, time);
emit valueChanged(uasId, name.arg("system_status"), "-", state.system_status, time);
case MAVLINK_MSG_ID_SYS_STATUS:
{
if (multiComponentSourceDetected && wrongComponent)
{
break;
}
mavlink_sys_status_t state;
mavlink_msg_sys_status_decode(&message, &state);
// Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present.
quint64 time = getUnixTime();
QString name = QString("M%1:SYS_STATUS.%2").arg(message.sysid);
emit valueChanged(uasId, name.arg("sensors_enabled"), "bits", state.onboard_control_sensors_enabled, time);
emit valueChanged(uasId, name.arg("sensors_health"), "bits", state.onboard_control_sensors_health, time);
emit valueChanged(uasId, name.arg("errors_comm"), "-", state.errors_comm, time);
emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time);
emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time);
emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time);
emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);
// Process CPU load.
emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
emit valueChanged(uasId, name.arg("drop_rate_comm"), "%", state.drop_rate_comm/100.0f, time);
}
break;
case MAVLINK_MSG_ID_ATTITUDE:
{
mavlink_attitude_t attitude;
mavlink_msg_attitude_decode(&message, &attitude);
quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time);
if (!wrongComponent)
{
lastAttitude = time;
Michael Carpenter
committed
setRoll(QGC::limitAngleToPMPIf(attitude.roll));
setPitch(QGC::limitAngleToPMPIf(attitude.pitch));
setYaw(QGC::limitAngleToPMPIf(attitude.yaw));
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
attitudeKnown = true;
emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
}
}
break;
case MAVLINK_MSG_ID_ATTITUDE_QUATERNION:
{
mavlink_attitude_quaternion_t attitude;
mavlink_msg_attitude_quaternion_decode(&message, &attitude);
quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
double a = attitude.q1;
double b = attitude.q2;
double c = attitude.q3;
double d = attitude.q4;
double aSq = a * a;
double bSq = b * b;
double cSq = c * c;
double dSq = d * d;
float dcm[3][3];
dcm[0][0] = aSq + bSq - cSq - dSq;
dcm[0][1] = 2.0 * (b * c - a * d);
dcm[0][2] = 2.0 * (a * c + b * d);
dcm[1][0] = 2.0 * (b * c + a * d);
dcm[1][1] = aSq - bSq + cSq - dSq;
dcm[1][2] = 2.0 * (c * d - a * b);
dcm[2][0] = 2.0 * (b * d - a * c);
dcm[2][1] = 2.0 * (a * b + c * d);
dcm[2][2] = aSq - bSq - cSq + dSq;
float phi, theta, psi;
theta = asin(-dcm[2][0]);
if (fabs(theta - M_PI_2) < 1.0e-3f) {
phi = 0.0f;
psi = (atan2(dcm[1][2] - dcm[0][1],
dcm[0][2] + dcm[1][1]) + phi);
} else if (fabs(theta + M_PI_2) < 1.0e-3f) {
phi = 0.0f;
psi = atan2f(dcm[1][2] - dcm[0][1],
dcm[0][2] + dcm[1][1] - phi);
} else {
phi = atan2f(dcm[2][1], dcm[2][2]);
psi = atan2f(dcm[1][0], dcm[0][0]);
}
emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(phi),
QGC::limitAngleToPMPIf(theta),
QGC::limitAngleToPMPIf(psi), time);
if (!wrongComponent)
{
lastAttitude = time;
setRoll(QGC::limitAngleToPMPIf(phi));
setPitch(QGC::limitAngleToPMPIf(theta));
setYaw(QGC::limitAngleToPMPIf(psi));
attitudeKnown = true;
Michael Carpenter
committed
emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
}
}
break;
case MAVLINK_MSG_ID_HIL_CONTROLS:
{
mavlink_hil_controls_t hil;
mavlink_msg_hil_controls_decode(&message, &hil);
emit hilControlsChanged(hil.time_usec, hil.roll_ailerons, hil.pitch_elevator, hil.yaw_rudder, hil.throttle, hil.mode, hil.nav_mode);
}
break;
case MAVLINK_MSG_ID_VFR_HUD:
{
mavlink_vfr_hud_t hud;
mavlink_msg_vfr_hud_decode(&message, &hud);
quint64 time = getUnixTime();
if (!attitudeKnown)
{
Anton Babushkin
committed
setYaw(QGC::limitAngleToPMPId((((double)hud.heading)/180.0)*M_PI));
Michael Carpenter
committed
emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
}
}
break;
case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
{
mavlink_global_vision_position_estimate_t pos;
mavlink_msg_global_vision_position_estimate_decode(&message, &pos);
quint64 time = getUnixTime(pos.usec);
emit attitudeChanged(this, message.compid, pos.roll, pos.pitch, pos.yaw, time);
}
break;
case MAVLINK_MSG_ID_PARAM_VALUE:
{
mavlink_param_value_t rawValue;
mavlink_msg_param_value_decode(&message, &rawValue);
QByteArray bytes(rawValue.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
// Construct a string stopping at the first NUL (0) character, else copy the whole
// byte array (max MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN, so safe)
QString parameterName(bytes);
mavlink_param_union_t paramVal;
paramVal.param_float = rawValue.param_value;
paramVal.type = rawValue.param_type;
processParamValueMsg(message, parameterName,rawValue,paramVal);
}
Lorenz Meier
committed
case MAVLINK_MSG_ID_ATTITUDE_TARGET:
Lorenz Meier
committed
mavlink_attitude_target_t out;
mavlink_msg_attitude_target_decode(&message, &out);
float roll, pitch, yaw;
mavlink_quaternion_to_euler(out.q, &roll, &pitch, &yaw);
quint64 time = getUnixTimeFromMs(out.time_boot_ms);
// For plotting emit roll sp, pitch sp and yaw sp values
emit valueChanged(uasId, "roll sp", "rad", roll, time);
emit valueChanged(uasId, "pitch sp", "rad", pitch, time);
emit valueChanged(uasId, "yaw sp", "rad", yaw, time);
case MAVLINK_MSG_ID_STATUSTEXT:
{
QByteArray b;
Lorenz Meier
committed
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
mavlink_msg_statustext_get_text(&message, b.data());
Lorenz Meier
committed
// Ensure NUL-termination
b[b.length()-1] = '\0';
QString text = QString(b);
int severity = mavlink_msg_statustext_get_severity(&message);
// If the message is NOTIFY or higher severity, or starts with a '#',
// then read it aloud.
if (text.startsWith("#") || severity <= MAV_SEVERITY_NOTICE)
text.remove("#");
emit textMessageReceived(uasId, message.compid, severity, text);
}
else
{
emit textMessageReceived(uasId, message.compid, severity, text);
}
}
break;
case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
{
mavlink_data_transmission_handshake_t p;
mavlink_msg_data_transmission_handshake_decode(&message, &p);
imageSize = p.size;
imagePackets = p.packets;
imagePayload = p.payload;
imageQuality = p.jpg_quality;
imageType = p.type;
imageWidth = p.width;
imageHeight = p.height;
imageStart = QGC::groundTimeMilliseconds();
}
break;
case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
{
mavlink_encapsulated_data_t img;
mavlink_msg_encapsulated_data_decode(&message, &img);
int seq = img.seqnr;
int pos = seq * imagePayload;
// Check if we have a valid transaction
if (imagePackets == 0)
{
// NO VALID TRANSACTION - ABORT
// Restart statemachine
imagePacketsArrived = 0;
}
for (int i = 0; i < imagePayload; ++i)
{
if (pos <= imageSize) {
imageRecBuffer[pos] = img.data[i];
}
++pos;
}
++imagePacketsArrived;
// emit signal if all packets arrived
if (imagePacketsArrived >= imagePackets)
{
// Restart statemachine
emit imageReady(this);
}
}
break;
case MAVLINK_MSG_ID_LOG_ENTRY:
{
mavlink_log_entry_t log;
mavlink_msg_log_entry_decode(&message, &log);
emit logEntry(this, log.time_utc, log.size, log.id, log.num_logs, log.last_log_num);
}
break;
case MAVLINK_MSG_ID_LOG_DATA:
{
mavlink_log_data_t log;
mavlink_msg_log_data_decode(&message, &log);
emit logData(this, log.ofs, log.id, log.count, log.data);
}
break;
default:
break;
}
}
}
void UAS::startCalibration(UASInterface::StartCalibrationType calType)
if (!_vehicle) {
return;
}
int gyroCal = 0;
int magCal = 0;
int airspeedCal = 0;
int radioCal = 0;
int accelCal = 0;
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
case StartCalibrationGyro:
gyroCal = 1;
break;
case StartCalibrationMag:
magCal = 1;
break;
case StartCalibrationAirspeed:
airspeedCal = 1;
break;
case StartCalibrationRadio:
radioCal = 1;
break;
case StartCalibrationCopyTrims:
radioCal = 2;
break;
case StartCalibrationAccel:
accelCal = 1;
break;
case StartCalibrationLevel:
accelCal = 2;
break;
case StartCalibrationEsc:
escCal = 1;
break;
case StartCalibrationUavcanEsc:
escCal = 2;
break;
case StartCalibrationCompassMot:
airspeedCal = 1; // ArduPilot, bit of a hack
break;
// We can't use sendMavCommand here since we have no idea how long it will be before the command returns a result. This in turn
// causes the retry logic to break down.
mavlink_message_t msg;
mavlink_msg_command_long_pack_chan(mavlink->getSystemId(),
mavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
uasId,
_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_CALIBRATION, // command id
0, // 0=first transmission of command
gyroCal, // gyro cal
magCal, // mag cal
0, // ground pressure
radioCal, // radio cal
accelCal, // accel cal
airspeedCal, // PX4: airspeed cal, ArduPilot: compass mot
escCal); // esc cal
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
Lorenz Meier
committed
}
Lorenz Meier
committed
{
if (!_vehicle) {
return;
}
_vehicle->sendMavCommand(_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_CALIBRATION, // command id
true, // showError
0, // gyro cal
0, // mag cal
0, // ground pressure
0, // radio cal
0, // accel cal
0, // airspeed cal
0); // unused
void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
{
if (!_vehicle) {
return;
}
switch (calType) {
case StartBusConfigActuators:
actuatorCal = 1;
break;
case EndBusConfigActuators:
actuatorCal = 0;
break;
_vehicle->sendMavCommand(_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
true, // showError
actuatorCal); // actuators
}
void UAS::stopBusConfig(void)
{
if (!_vehicle) {
return;
}
_vehicle->sendMavCommand(_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
true, // showError
0); // cancel
/**
* Check if time is smaller than 40 years, assuming no system without Unix
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
* timestamp runs longer than 40 years continuously without reboot. In worst case
* this will add/subtract the communication delay between GCS and MAV, it will
* never alter the timestamp in a safety critical way.
*/
quint64 UAS::getUnixReferenceTime(quint64 time)
{
// Same as getUnixTime, but does not react to attitudeStamped mode
if (time == 0)
{
// qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
return QGC::groundTimeMilliseconds();
}
// Check if time is smaller than 40 years,
// assuming no system without Unix timestamp
// runs longer than 40 years continuously without
// reboot. In worst case this will add/subtract the
// communication delay between GCS and MAV,
// it will never alter the timestamp in a safety
// critical way.
//
// Calculation:
// 40 years
// 365 days
// 24 hours
// 60 minutes
// 60 seconds
// 1000 milliseconds
// 1000 microseconds
#ifndef _MSC_VER
else if (time < 1261440000000000LLU)
#else
else if (time < 1261440000000000)
#endif
{
// qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
if (onboardTimeOffset == 0)
{
onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
}
return time/1000 + onboardTimeOffset;
}
else
{
// Time is not zero and larger than 40 years -> has to be
// a Unix epoch timestamp. Do nothing.
return time/1000;
}
}
/**
* @warning If attitudeStamped is enabled, this function will not actually return
* the precise time stamp of this measurement augmented to UNIX time, but will
* MOVE the timestamp IN TIME to match the last measured attitude. There is no
* reason why one would want this, except for system setups where the onboard
* clock is not present or broken and datasets should be collected that are still
* roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE
* SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
*/
quint64 UAS::getUnixTimeFromMs(quint64 time)
{
return getUnixTime(time*1000);
}
/**
* @warning If attitudeStamped is enabled, this function will not actually return
* the precise time stam of this measurement augmented to UNIX time, but will
* MOVE the timestamp IN TIME to match the last measured attitude. There is no
* reason why one would want this, except for system setups where the onboard
* clock is not present or broken and datasets should be collected that are
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
* still roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED
* RUINS THE SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
*/
quint64 UAS::getUnixTime(quint64 time)
{
quint64 ret = 0;
if (attitudeStamped)
{
ret = lastAttitude;
}
if (time == 0)
{
ret = QGC::groundTimeMilliseconds();
}
// Check if time is smaller than 40 years,
// assuming no system without Unix timestamp
// runs longer than 40 years continuously without
// reboot. In worst case this will add/subtract the
// communication delay between GCS and MAV,
// it will never alter the timestamp in a safety
// critical way.
//
// Calculation:
// 40 years
// 365 days
// 24 hours
// 60 minutes
// 60 seconds
// 1000 milliseconds
// 1000 microseconds
#ifndef _MSC_VER
else if (time < 1261440000000000LLU)
#else
else if (time < 1261440000000000)
#endif
{
// qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
if (onboardTimeOffset == 0 || time < (lastNonNullTime - 100))
{
lastNonNullTime = time;
onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
}
if (time > lastNonNullTime) lastNonNullTime = time;
ret = time/1000 + onboardTimeOffset;
}
else
{
// Time is not zero and larger than 40 years -> has to be
// a Unix epoch timestamp. Do nothing.
ret = time/1000;
}
return ret;
}
/**
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
* Get the status of the code and a description of the status.
* Status can be unitialized, booting up, calibrating sensors, active
* standby, cirtical, emergency, shutdown or unknown.
*/
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
switch (statusCode)
{
case MAV_STATE_UNINIT:
uasState = tr("UNINIT");
stateDescription = tr("Unitialized, booting up.");
break;
case MAV_STATE_BOOT:
uasState = tr("BOOT");
stateDescription = tr("Booting system, please wait.");
break;
case MAV_STATE_CALIBRATING:
uasState = tr("CALIBRATING");
stateDescription = tr("Calibrating sensors, please wait.");
break;
case MAV_STATE_ACTIVE:
uasState = tr("ACTIVE");
stateDescription = tr("Active, normal operation.");
break;
case MAV_STATE_STANDBY:
uasState = tr("STANDBY");
stateDescription = tr("Standby mode, ready for launch.");
break;
case MAV_STATE_CRITICAL:
uasState = tr("CRITICAL");
stateDescription = tr("FAILURE: Continuing operation.");
break;
case MAV_STATE_EMERGENCY:
uasState = tr("EMERGENCY");
stateDescription = tr("EMERGENCY: Land Immediately!");
break;
//case MAV_STATE_HILSIM:
//uasState = tr("HIL SIM");
//stateDescription = tr("HIL Simulation, Sensors read from SIM");
//break;
case MAV_STATE_POWEROFF:
uasState = tr("SHUTDOWN");
stateDescription = tr("Powering off system.");
break;
default:
uasState = tr("UNKNOWN");
stateDescription = tr("Unknown system state");
break;
}
}
QImage UAS::getImage()
{
// qDebug() << "IMAGE TYPE:" << imageType;
// RAW greyscale
if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
{
// Construct PGM header
QString header("P5\n%1 %2\n%3\n");
header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
QByteArray tmpImage(header.toStdString().c_str(), header.length());
tmpImage.append(imageRecBuffer);
//qDebug() << "IMAGE SIZE:" << tmpImage.size() << "HEADER SIZE: (15):" << header.size() << "HEADER: " << header;
if (imageRecBuffer.isNull())
{
qDebug()<< "could not convertToPGM()";
return QImage();
}
if (!image.loadFromData(tmpImage, "PGM"))
{
qDebug()<< __FILE__ << __LINE__ << "could not create extracted image";
return QImage();
}
}
// BMP with header
else if (imageType == MAVLINK_DATA_STREAM_IMG_BMP ||
imageType == MAVLINK_DATA_STREAM_IMG_JPEG ||
imageType == MAVLINK_DATA_STREAM_IMG_PGM ||
imageType == MAVLINK_DATA_STREAM_IMG_PNG)
{
if (!image.loadFromData(imageRecBuffer))
{
qDebug() << __FILE__ << __LINE__ << "Loading data from image buffer failed!";
// Restart statemachine
imagePacketsArrived = 0;
imagePackets = 0;
imageRecBuffer.clear();
return image;
}
void UAS::requestImage()
{
if (!_vehicle) {
return;
}
qDebug() << "trying to get an image from the uas...";
// check if there is already an image transmission going on
if (imagePacketsArrived == 0)
{
mavlink_message_t msg;
mavlink_msg_data_transmission_handshake_pack_chan(mavlink->getSystemId(),
mavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
MAVLINK_DATA_STREAM_IMG_JPEG,
0, 0, 0, 0, 0, 50);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
}
}
/* MANAGEMENT */
/**
*
* @return The uptime in milliseconds
*
*/
quint64 UAS::getUptime() const
{
if(startTime == 0)
{
return 0;
}
else
{
return QGC::groundTimeMilliseconds() - startTime;
}
}
//TODO update this to use the parameter manager / param data model instead
void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramUnion)
{
int compId = msg.compid;
// Insert with correct type
switch (rawValue.param_type) {
case MAV_PARAM_TYPE_REAL32:
case MAV_PARAM_TYPE_UINT16:
paramValue = QVariant(paramUnion.param_uint16);
break;
case MAV_PARAM_TYPE_UINT32:
//-- Note: These are not handled above:
//
// MAV_PARAM_TYPE_UINT64
// MAV_PARAM_TYPE_INT64
// MAV_PARAM_TYPE_REAL64
//
// No space in message (the only storage allocation is a "float") and not present in mavlink_param_union_t
default:
qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
emit parameterUpdate(uasId, compId, paramName, rawValue.param_count, rawValue.param_index, rawValue.param_type, paramValue);
/**
* Set the manual control commands.
* This can only be done if the system has manual inputs enabled and is armed.
*/
void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode)
if (!_vehicle) {
return;
}
if (!_vehicle->priorityLink()) {
return;
}
Bryant Mairs
committed
// Store the previous manual commands
static float manualRollAngle = 0.0;
static float manualPitchAngle = 0.0;
static float manualYawAngle = 0.0;
static float manualThrust = 0.0;
static quint16 manualButtons = 0;
static quint8 countSinceLastTransmission = 0; // Track how many calls to this function have occurred since the last MAVLink transmission
// Transmit the external setpoints only if they've changed OR if it's been a little bit since they were last transmit. To make sure there aren't issues with
// response rate, we make sure that a message is transmit when the commands have changed, then one more time, and then switch to the lower transmission rate
// if no command inputs have changed.
// The default transmission rate is 25Hz, but when no inputs have changed it drops down to 5Hz.
bool sendCommand = false;
if (countSinceLastTransmission++ >= 5) {