Newer
Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009, 2010 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
PIXHAWK is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Represents one unmanned aerial vehicle
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QList>
#include <QMessageBox>
#include <QTimer>
#include <iostream>
#include <QDebug>
#include <cmath>
#include "UAS.h"
#include "LinkInterface.h"
#include "UASManager.h"
#include "MG.h"
#include "MAVLinkProtocol.h"
#include <mavlink.h>
UAS::UAS(MAVLinkProtocol* protocol, int id) :
uasId(id),
startTime(MG::TIME::getGroundTimeNow()),
commStatus(COMM_DISCONNECTED),
name(""),
links(new QList<LinkInterface*>()),
thrustSum(0),
currentVoltage(0.0f),
lpVoltage(0.0f),
mode(MAV_MODE_UNINIT),
status(MAV_STATE_UNINIT),
onboardTimeOffset(0),
controlRollManual(true),
controlPitchManual(true),
controlYawManual(true),
controlThrustManual(true),
manualRollAngle(0),
manualPitchAngle(0),
manualYawAngle(0),
int UAS::getUASID() const
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
{
return uasId;
}
void UAS::setSelected()
{
UASManager::instance()->setActiveUAS(this);
}
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
if (!links->contains(link))
{
addLink(link);
}
if (message.sysid == uasId)
{
QString uasState;
QString stateDescription;
QString patternPath;
switch (message.msgid)
{
case MAVLINK_MSG_ID_HEARTBEAT:
emit heartbeat(this);
// Set new type if it has changed
if (this->type != message_heartbeat_get_type(&message))
{
this->type = message_heartbeat_get_type(&message);
emit systemTypeSet(this, type);
}
break;
case MAVLINK_MSG_ID_BOOT:
getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription);
emit statusChanged(this, uasState, stateDescription);
onboardTimeOffset = 0; // Reset offset measurement
break;
case MAVLINK_MSG_ID_SYS_STATUS:
{
sys_status_t state;
message_sys_status_decode(&message, &state);
QString audiostring = "System " + QString::number(this->getUASID());
QString stateAudio = "";
QString modeAudio = "";
bool statechanged = false;
bool modechanged = false;
statechanged = true;
this->status = state.status;
getStatusForCode((int)state.status, uasState, stateDescription);
emit statusChanged(this, uasState, stateDescription);
pixhawk
committed
stateAudio = " changed status to " + uasState;
if (static_cast<int>(this->mode) != static_cast<int>(state.mode))
{
modechanged = true;
this->mode = state.mode;
QString mode;
switch (state.mode)
{
case MAV_MODE_LOCKED:
mode = "LOCKED MODE";
break;
case MAV_MODE_MANUAL:
mode = "MANUAL MODE";
break;
case MAV_MODE_AUTO:
mode = "AUTO MODE";
break;
case MAV_MODE_TEST1:
mode = "TEST1 MODE";
break;
case MAV_MODE_TEST2:
mode = "TEST2 MODE";
break;
case MAV_MODE_TEST3:
mode = "TEST3 MODE";
break;
default:
mode = "UNINIT MODE";
break;
}
emit modeChanged(this->getUASID(), mode, "");
modeAudio = " is now in " + mode;
}
if (startVoltage == 0) startVoltage = currentVoltage;
timeRemaining = calculateTimeRemaining();
//qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
emit voltageChanged(message.sysid, state.vbat/1000.0f);
// COMMUNICATIONS DROP RATE
emit dropRateChanged(this->getUASID(), this->receiveDropRate, this->sendDropRate);
// AUDIO
if (modechanged && statechanged)
{
// Output both messages
audiostring += modeAudio + " and " + stateAudio;
}
else
{
// Output the one message
audiostring += modeAudio + stateAudio;
}
if (state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
{
GAudioOutput::instance()->startEmergency();
}
else if (modechanged || statechanged)
{
GAudioOutput::instance()->stopEmergency();
GAudioOutput::instance()->say(audiostring);
}
{
aux_status_t status;
message_aux_status_decode(&message, &status);
emit loadChanged(this, status.load/100.0f);
emit valueChanged(this, "Load", status.load/1000.0f, MG::TIME::getGroundTimeNow());
}
break;
raw_imu_t raw;
message_raw_imu_decode(&message, &raw);
quint64 time = raw.msec;
if (time == 0)
{
time = MG::TIME::getGroundTimeNow();
}
else
{
if (onboardTimeOffset == 0)
{
onboardTimeOffset = MG::TIME::getGroundTimeNow() - time;
}
time += onboardTimeOffset;
}
emit valueChanged(uasId, "Accel. X", raw.xacc, time);
emit valueChanged(uasId, "Accel. Y", raw.yacc, time);
emit valueChanged(uasId, "Accel. Z", raw.zacc, time);
emit valueChanged(uasId, "Gyro Phi", raw.xgyro, time);
emit valueChanged(uasId, "Gyro Theta", raw.ygyro, time);
emit valueChanged(uasId, "Gyro Psi", raw.zgyro, time);
emit valueChanged(uasId, "Mag. X", raw.xmag, time);
emit valueChanged(uasId, "Mag. Y", raw.ymag, time);
emit valueChanged(uasId, "Mag. Z", raw.zmag, time);
raw_aux_t raw;
message_raw_aux_decode(&message, &raw);
quint64 time = MG::TIME::getGroundTimeNow();//raw.msec;
if (time == 0)
{
time = MG::TIME::getGroundTimeNow();
}
else
{
if (onboardTimeOffset == 0)
{
onboardTimeOffset = MG::TIME::getGroundTimeNow() - time;
}
time += onboardTimeOffset;
}
emit valueChanged(uasId, "Pressure", raw.baro, time);
case MAVLINK_MSG_ID_ATTITUDE:
//std::cerr << std::endl;
//std::cerr << "Decoded attitude message:" << " roll: " << std::dec << message_attitude_get_roll(message.payload) << " pitch: " << message_attitude_get_pitch(message.payload) << " yaw: " << message_attitude_get_yaw(message.payload) << std::endl;
{
attitude_t attitude;
message_attitude_decode(&message, &attitude);
quint64 time = message_attitude_get_msec(&message);
if (time == 0)
{
time = MG::TIME::getGroundTimeNow();
}
else
{
if (onboardTimeOffset == 0)
{
onboardTimeOffset = MG::TIME::getGroundTimeNow() - time;
}
time += onboardTimeOffset;
}
emit valueChanged(uasId, "roll IMU", message_attitude_get_roll(&message), time);
emit valueChanged(uasId, "pitch IMU", message_attitude_get_pitch(&message), time);
emit valueChanged(uasId, "yaw IMU", message_attitude_get_yaw(&message), time);
emit valueChanged(this, "roll IMU", message_attitude_get_roll(&message), time);
emit valueChanged(this, "pitch IMU", message_attitude_get_pitch(&message), time);
emit valueChanged(this, "yaw IMU", message_attitude_get_yaw(&message), time);
emit valueChanged(uasId, "rollspeed IMU", attitude.rollspeed, time);
emit valueChanged(uasId, "pitchspeed IMU", attitude.pitchspeed, time);
emit valueChanged(uasId, "yawspeed IMU", attitude.yawspeed, time);
emit attitudeChanged(this, message_attitude_get_roll(&message), message_attitude_get_pitch(&message), message_attitude_get_yaw(&message), time);
}
break;
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
case MAVLINK_MSG_ID_POSITION:
//std::cerr << std::endl;
//std::cerr << "Decoded attitude message:" << " roll: " << std::dec << message_attitude_get_roll(message.payload) << " pitch: " << message_attitude_get_pitch(message.payload) << " yaw: " << message_attitude_get_yaw(message.payload) << std::endl;
{
position_t pos;
message_position_decode(&message, &pos);
quint64 time = pos.msec;
if (time == 0)
{
time = MG::TIME::getGroundTimeNow();
}
else
{
if (onboardTimeOffset == 0)
{
onboardTimeOffset = MG::TIME::getGroundTimeNow() - time;
}
time += onboardTimeOffset;
}
emit valueChanged(uasId, "x", pos.x, time);
emit valueChanged(uasId, "y", pos.y, time);
emit valueChanged(uasId, "z", pos.z, time);
//emit valueChanged(this, "roll IMU", message_attitude_get_roll(&message), time);
//emit valueChanged(this, "pitch IMU", message_attitude_get_pitch(&message), time);
//emit valueChanged(this, "yaw IMU", message_attitude_get_yaw(&message), time);
emit valueChanged(uasId, "vx", pos.vx, time);
emit valueChanged(uasId, "vy", pos.vy, time);
emit valueChanged(uasId, "vz", pos.vz, time);
emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
}
break;
case MAVLINK_MSG_ID_PARAM_VALUE:
{
param_value_t value;
message_param_value_decode(&message, &value);
emit parameterChanged(uasId, message.compid, QString((char*)value.param_id), value.param_value);
}
break;
case MAVLINK_MSG_ID_DEBUG:
emit valueChanged(uasId, QString("debug ") + QString::number(message_debug_get_ind(&message)), message_debug_get_value(&message), MG::TIME::getGroundTimeNow());
break;
emit waypointUpdated(this->getUASID(), message_emitwaypoint_get_id(message.payload), message_emitwaypoint_get_x(message.payload), message_emitwaypoint_get_y(message.payload), message_emitwaypoint_get_z(message.payload), message_emitwaypoint_get_yaw(message.payload), (message_emitwaypoint_get_autocontinue(message.payload) == 1 ? true : false), (message_emitwaypoint_get_active(message.payload) == 1 ? true : false));
break;
emit valueChanged(uasId, "WP X", message_gotowaypoint_get_x(message.payload), MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "WP Y", message_gotowaypoint_get_y(message.payload), MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "WP Z", message_gotowaypoint_get_z(message.payload), MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "WP speed X", message_gotowaypoint_get_speedX(message.payload), MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "WP speed Y", message_gotowaypoint_get_speedY(message.payload), MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "WP speed Z", message_gotowaypoint_get_speedZ(message.payload), MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "WP yaw", message_gotowaypoint_get_yaw(message.payload)/M_PI*180.0f, MG::TIME::getGroundTimeNow());
break;
case MAVLINK_MSG_ID_WP_REACHED:
qDebug() << "WAYPOINT REACHED";
emit waypointReached(this, message_wp_reached_get_id(message.payload));
break;
case MAVLINK_MSG_ID_STATUSTEXT:
{
QByteArray b;
b.resize(256);
message_statustext_get_text(&message, (int8_t*)b.data());
//b.append('\0');
QString text = QString(b);
int severity = message_statustext_get_severity(&message);
//qDebug() << "RECEIVED STATUS:" << text;
emit textMessageReceived(uasId, severity, text);
}
break;
case MAVLINK_MSG_ID_PATTERN_DETECTED:
{
QByteArray b;
b.resize(256);
message_pattern_detected_get_file(&message, (int8_t*)b.data());
b.append('\0');
QString path = QString(b);
bool detected (message_pattern_detected_get_detected(&message) == 1 ? true : false );
emit detectionReceived(uasId, path, 0, 0, 0, 0, 0, 0, 0, 0, message_pattern_detected_get_confidence(&message), detected);
}
break;
{
if (!unknownPackets.contains(message.msgid))
{
unknownPackets.append(message.msgid);
GAudioOutput::instance()->say("UNABLE TO DECODE MESSAGE WITH ID " + QString::number(message.msgid) + " FROM SYSTEM " + QString::number(message.sysid));
std::cerr << "Unable to decode message from system " << std::dec << static_cast<int>(message.sysid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
//qDebug() << std::cerr << "Unable to decode message from system " << std::dec << static_cast<int>(message.acid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
}
}
if (mode >= MAV_MODE_LOCKED && mode <= MAV_MODE_TEST3)
{
this->mode = mode;
mavlink_message_t msg;
message_set_mode_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, getUASID(), (unsigned char)mode);
sendMessage(msg);
}
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
}
void UAS::sendMessage(mavlink_message_t message)
{
qDebug() << "In send message";
// Emit message on all links that are currently connected
QList<LinkInterface*>::iterator i;
qDebug() << "LINKS: " << links->length();
for (i = links->begin(); i != links->end(); ++i)
{
// if (i != NULL)
// {
qDebug() << "UAS::sendMessage()";
sendMessage(*i, message);
}
}
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
qDebug() << "UAS::sendMessage(link, message)";
// Create buffer
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
// Write message into buffer, prepending start sign
int len = message_to_send_buffer(buffer, &message);
// If link is connected
if (link->isConnected())
{
// Send the portion of the buffer now occupied by the message
link->writeBytes((const char*)buffer, len);
}
}
/**
* @param value battery voltage
*/
float UAS::filterVoltage(float value) const
return lpVoltage * 0.7f + value * 0.3f;
/*
currentVoltage = value;
static QList<float> voltages<float>(20);
const int dropPercent = 20;
voltages.takeFirst();
voltages.append(value);
// Drop top and bottom xx percent of values
QList<float> v(voltages);
qSort(v);
v = QList::mid(v.size()/dropPercent, v.size() - v.size()/dropPercent);
lpVoltage = 0.0f;
foreach (float value, v)
{
lpVoltage += v;
}*/
}
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
switch (statusCode)
{
uasState = tr("UNINIT");
stateDescription = tr("Not initialized");
break;
uasState = tr("BOOT");
stateDescription = tr("Booting system, please wait..");
break;
uasState = tr("CALIBRATING");
stateDescription = tr("Calibrating sensors..");
break;
uasState = tr("ACTIVE");
stateDescription = tr("Normal operation mode");
break;
case MAV_STATE_STANDBY:
uasState = tr("STANDBY");
stateDescription = tr("Standby, operational");
break;
case MAV_STATE_CRITICAL:
uasState = tr("CRITICAL");
stateDescription = tr("Failure occured!");
break;
uasState = tr("EMERGENCY");
stateDescription = tr("EMERGENCY: Please land");
break;
uasState = tr("SHUTDOWN");
stateDescription = tr("Powering off system");
break;
uasState = tr("UNKNOWN");
stateDescription = tr("FAILURE: Unknown system state");
break;
}
}
/* MANAGEMENT */
/*
*
* @return The uptime in milliseconds
*
**/
quint64 UAS::getUptime() const
{
if(startTime == 0) {
return 0;
} else {
return MG::TIME::getGroundTimeNow() - startTime;
}
}
int UAS::getCommunicationStatus() const
{
return commStatus;
}
void UAS::requestWaypoints()
{
mavlink_message_t message;
//messagePackGetWaypoints(MG::SYSTEM::ID, &message); FIXME
sendMessage(message);
qDebug() << "UAS Request WPs";
}
void UAS::requestParameters()
{
mavlink_message_t msg;
message_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg);
sendMessage(msg);
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
/**
* @brief Launches the system
*
**/
void UAS::launch()
{
mavlink_message_t message;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
message_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->getUASID(),(int)MAV_ACTION_LAUNCH);
sendMessage(message);
qDebug() << "UAS LAUNCHED!";
//emit commandSent(LAUNCH);
}
/**
* Depending on the UAS, this might make the rotors of a helicopter spinning
*
**/
void UAS::enable_motors()
{
mavlink_message_t message;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
message_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->getUASID(),(int)MAV_ACTION_MOTORS_START);
sendMessage(message);
}
/**
* @warning Depending on the UAS, this might completely stop all motors.
*
**/
void UAS::disable_motors()
{
mavlink_message_t message;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
message_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->getUASID(),(int)MAV_ACTION_MOTORS_STOP);
sendMessage(message);
}
void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust)
{
// Scale values
double rollPitchScaling = 0.2f;
double yawScaling = 0.5f;
double thrustScaling = 1.0f;
manualRollAngle = roll * rollPitchScaling;
manualPitchAngle = pitch * rollPitchScaling;
manualYawAngle = yaw * yawScaling;
manualThrust = thrust * thrustScaling;
if(mode == MAV_MODE_MANUAL)
{
mavlink_message_t message;
message_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual);
sendMessage(message);
qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;
emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
}
}
void UAS::receiveButton(int buttonIndex)
{
switch (buttonIndex)
{
case 0:
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
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
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
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
break;
default:
break;
}
qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
}
void UAS::setWaypoint(Waypoint* wp)
{
mavlink_message_t message;
// FIXME
//messagePackSetWaypoint(MG::SYSTEM::ID, &message, wp->id, wp->x, wp->y, wp->z, wp->yaw, (wp->autocontinue ? 1 : 0));
sendMessage(message);
qDebug() << "UAS SENT Waypoint " << wp->id;
}
void UAS::setWaypointActive(int id)
{
mavlink_message_t message;
// FIXME
//messagePackChooseWaypoint(MG::SYSTEM::ID, &message, id);
sendMessage(message);
// TODO This should be not directly emitted, but rather being fed back from the UAS
emit waypointSelected(getUASID(), id);
}
void UAS::halt()
{
mavlink_message_t message;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
message_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->getUASID(), (int)MAV_ACTION_HALT);
sendMessage(message);
}
void UAS::go()
{
mavlink_message_t message;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
message_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->getUASID(), (int)MAV_ACTION_CONTINUE);
sendMessage(message);
}
/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
mavlink_message_t message;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
message_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->getUASID(), (int)MAV_ACTION_RETURN);
sendMessage(message);
}
/**
* The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
* and might differ between systems.
*/
void UAS::emergencySTOP()
{
mavlink_message_t message;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
message_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->getUASID(), (int)MAV_ACTION_EMCY_LAND);
}
/**
* All systems are immediately shut down (e.g. the main power line is cut).
* @warning This might lead to a crash
*
* The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
*/
bool UAS::emergencyKILL()
{
bool result = false;
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS");
msgBox.setInformativeText("Do you want to cut power on all systems?");
msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
msgBox.setDefaultButton(QMessageBox::Cancel);
int ret = msgBox.exec();
// Close the message box shortly after the click to prevent accidental clicks
QTimer::singleShot(5000, &msgBox, SLOT(reject()));
if (ret == QMessageBox::Yes)
{
mavlink_message_t message;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
message_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->getUASID(), (int)MAV_ACTION_EMCY_KILL);
sendMessage(message);
result = true;
}
return result;
}
void UAS::shutdown()
{
bool result = false;
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Shutting down the UAS");
msgBox.setInformativeText("Do you want to shut down the onboard computer?");
msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
msgBox.setDefaultButton(QMessageBox::Cancel);
int ret = msgBox.exec();
// Close the message box shortly after the click to prevent accidental clicks
QTimer::singleShot(5000, &msgBox, SLOT(reject()));
if (ret == QMessageBox::Yes)
{
// If the active UAS is set, execute command
mavlink_message_t message;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
message_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->getUASID(), (int)MAV_ACTION_SHUTDOWN);
sendMessage(message);
result = true;
}
}
/**
* @return The name of this system as string in human-readable form
*/
QString UAS::getUASName(void) const
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
769
770
771
772
773
774
775
776
777
778
{
QString result;
if (name == "")
{
result = tr("MAV ") + result.sprintf("%03d", getUASID());
}
else
{
result = name;
}
return result;
}
void UAS::addLink(LinkInterface* link)
{
if (!links->contains(link))
{
links->append(link);
}
//links->append(link);
//qDebug() << " ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK";
}
/**
* @brief Get the links associated with this robot
*
**/
QList<LinkInterface*>* UAS::getLinks()
{
return links;
}
void UAS::setBattery(BatteryType type, int cells)
{
this->batteryType = type;
this->cells = cells;
switch (batteryType)
{
fullVoltage = this->cells * UAS::lipoFull;
emptyVoltage = this->cells * UAS::lipoEmpty;
break;
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
break;
}
}
int UAS::calculateTimeRemaining()
{
quint64 dt = MG::TIME::getGroundTimeNow() - startTime;
double seconds = dt / 1000.0f;
double voltDifference = startVoltage - currentVoltage;
if (voltDifference <= 0) voltDifference = 0.00000000001f;
double dischargePerSecond = voltDifference / seconds;
int remaining = static_cast<int>((currentVoltage - emptyVoltage) / dischargePerSecond);
// Can never be below 0
if (remaining < 0) remaining = 0;
return remaining;
}
double UAS::getChargeLevel()
{
return 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
}
void UAS::clearWaypointList()
{
mavlink_message_t message;
// FIXME
//messagePackRemoveWaypoints(MG::SYSTEM::ID, &message);
sendMessage(message);
qDebug() << "UAS clears Waypoints!";
}