Commit dd603e07 authored by lm's avatar lm

Testing mail commit hook

parent ca963db2
...@@ -25,7 +25,7 @@ DOXYFILE_ENCODING = UTF-8 ...@@ -25,7 +25,7 @@ DOXYFILE_ENCODING = UTF-8
# The PROJECT_NAME tag is a single word (or a sequence of words surrounded # The PROJECT_NAME tag is a single word (or a sequence of words surrounded
# by quotes) that should identify the project. # by quotes) that should identify the project.
PROJECT_NAME = "PIXHAWK Groundstation" PROJECT_NAME = "QGroundControl"
# The PROJECT_NUMBER tag can be used to enter a project or revision number. # The PROJECT_NUMBER tag can be used to enter a project or revision number.
# This could be handy for archiving the generated documentation or # This could be handy for archiving the generated documentation or
......
...@@ -31,7 +31,7 @@ This file is part of the PIXHAWK project ...@@ -31,7 +31,7 @@ This file is part of the PIXHAWK project
/** /**
* @mainpage PIXHAWK API Documentation * @mainpage QGroundControl API Documentation
* *
* @section intro_sec Introduction * @section intro_sec Introduction
* *
...@@ -40,17 +40,17 @@ This file is part of the PIXHAWK project ...@@ -40,17 +40,17 @@ This file is part of the PIXHAWK project
* In case you have generated this documentation locally, the most recent version (generated on every commit) * In case you have generated this documentation locally, the most recent version (generated on every commit)
* is also publicly available on the internet. * is also publicly available on the internet.
* *
* @sa http://pixhawk.ethz.ch/api/embedded/ - Embedded / Computer Vision API docs * @sa http://pixhawk.ethz.ch/api/qgroundcontrol/ - (this) Groundstation code base
* @sa http://pixhawk.ethz.ch/api/groundstation/ - Groundstation code base * @sa http://pixhawk.ethz.ch/api/mavlink - the MAVLink communication protocol
* @sa http://pixhawk.ethz.ch/api/flight/ - Flight board (ARM MCU) code base * @sa http://pixhawk.ethz.ch/api/imu_autopilot/ - Flight board (ARM MCU) code base
* @sa http://pixhawk.ethz.ch/api/blmc/ - Brushless motor controller API docs * @sa http://pixhawk.ethz.ch/api/ai_vision - Computer Vision / AI API docs
* *
* @section further_sec Further Information * @section further_sec Further Information
* *
* How to run our software and a general overview of the software architecture is documented in the project * How to run our software and a general overview of the software architecture is documented in the project
* wiki pages. * wiki pages.
* *
* @sa http://pixhawk.ethz.ch/wiki/software/groundstation/ - Groundstation main page * @sa http://qgroundcontrol.org/ - Groundstation main page
* @sa http://pixhawk.ethz.ch/wiki/software/ - The software architecture * @sa http://pixhawk.ethz.ch/wiki/software/ - The software architecture
* @sa http://pixhawk.ethz.ch/wiki/software/run - How to run the software * @sa http://pixhawk.ethz.ch/wiki/software/run - How to run the software
* *
......
...@@ -64,7 +64,8 @@ UAS::UAS(int id=0) : ...@@ -64,7 +64,8 @@ UAS::UAS(int id=0) :
manualYawAngle(0), manualYawAngle(0),
manualThrust(0), manualThrust(0),
receiveDropRate(0), receiveDropRate(0),
sendDropRate(0) sendDropRate(0),
unknownPackets()
{ {
uasId = id; uasId = id;
setBattery(LIPOLY, 3); setBattery(LIPOLY, 3);
...@@ -113,13 +114,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -113,13 +114,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit statusChanged(this, uasState, stateDescription); emit statusChanged(this, uasState, stateDescription);
onboardTimeOffset = 0; // Reset offset measurement onboardTimeOffset = 0; // Reset offset measurement
break; break;
case MAVLINK_MSG_ID_STATUSTEXT:
{
statustext_t status;
message_statustext_decode(&message, &status);
qDebug() << status.text;
}
break;
case MAVLINK_MSG_ID_SYS_STATUS: case MAVLINK_MSG_ID_SYS_STATUS:
{ {
sys_status_t state; sys_status_t state;
...@@ -157,6 +151,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -157,6 +151,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
case MAV_MODE_AUTO: case MAV_MODE_AUTO:
mode = "AUTO MODE"; mode = "AUTO MODE";
break; break;
case MAV_MODE_READY:
mode = "READY";
break;
case MAV_MODE_TEST1: case MAV_MODE_TEST1:
mode = "TEST1 MODE"; mode = "TEST1 MODE";
break; break;
...@@ -208,13 +205,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -208,13 +205,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
break; break;
case MAVLINK_MSG_ID_AUX_STATUS: case MAVLINK_MSG_ID_AUX_STATUS:
{ {
aux_status_t status; aux_status_t status;
message_aux_status_decode(&message, &status); message_aux_status_decode(&message, &status);
emit loadChanged(this, status.load/100.0f); emit loadChanged(this, status.load/100.0f);
emit valueChanged(this, "Load", status.load/1000.0f, MG::TIME::getGroundTimeNow()); emit valueChanged(this, "Load", status.load/1000.0f, MG::TIME::getGroundTimeNow());
} }
break; break;
case MAVLINK_MSG_ID_RAW_IMU: case MAVLINK_MSG_ID_RAW_IMU:
{ {
raw_imu_t raw; raw_imu_t raw;
...@@ -306,6 +303,37 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -306,6 +303,37 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit attitudeChanged(this, message_attitude_get_roll(&message), message_attitude_get_pitch(&message), message_attitude_get_yaw(&message), time); emit attitudeChanged(this, message_attitude_get_roll(&message), message_attitude_get_pitch(&message), message_attitude_get_yaw(&message), time);
} }
break; break;
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_DEBUG: 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()); emit valueChanged(uasId, QString("debug ") + QString::number(message_debug_get_ind(&message)), message_debug_get_value(&message), MG::TIME::getGroundTimeNow());
break; break;
...@@ -326,16 +354,40 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -326,16 +354,40 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
qDebug() << "WAYPOINT REACHED"; qDebug() << "WAYPOINT REACHED";
emit waypointReached(this, message_wp_reached_get_id(message.payload)); emit waypointReached(this, message_wp_reached_get_id(message.payload));
break; break;
case MAVLINK_MSG_ID_OBJ_DETECTED:
//patternPath = QString(message_detection_get_patternpath(message.payload));
//qDebug() << "OBJECT DETECTED";
//emit detectionReceived(uasId, patternPath, 0, 0, 0, 0, 0, 0, 0, 0, message_detection_get_confidence(message.payload), (message_detection_get_detected(message.payload) == 1 ? true : false ));
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 statusTextReceived(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;
default: default:
GAudioOutput::instance()->say("COMM ERROR: 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; if (!unknownPackets.contains(message.msgid))
//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; {
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;
}
}
break; break;
} }
} }
...@@ -415,35 +467,39 @@ void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDesc ...@@ -415,35 +467,39 @@ void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDesc
{ {
switch (statusCode) switch (statusCode)
{ {
case MAV_STATE_UNINIT: case MAV_STATE_UNINIT:
uasState = tr("UNINIT"); uasState = tr("UNINIT");
stateDescription = tr("Not initialized"); stateDescription = tr("Not initialized");
break; break;
case MAV_STATE_BOOT: case MAV_STATE_BOOT:
uasState = tr("BOOT"); uasState = tr("BOOT");
stateDescription = tr("Booting system, please wait.."); stateDescription = tr("Booting system, please wait..");
break; break;
case MAV_STATE_CALIBRATING: case MAV_STATE_CALIBRATING:
uasState = tr("CALIBRATING"); uasState = tr("CALIBRATING");
stateDescription = tr("Calibrating sensors.."); stateDescription = tr("Calibrating sensors..");
break; break;
case MAV_STATE_ACTIVE: case MAV_STATE_ACTIVE:
uasState = tr("ACTIVE"); uasState = tr("ACTIVE");
stateDescription = tr("Normal operation mode"); stateDescription = tr("Normal operation mode");
break; break;
case MAV_STATE_CRITICAL: case MAV_STATE_STANDBY:
uasState = tr("STANDBY");
stateDescription = tr("Standby, operational");
break;
case MAV_STATE_CRITICAL:
uasState = tr("CRITICAL"); uasState = tr("CRITICAL");
stateDescription = tr("Failure occured!"); stateDescription = tr("Failure occured!");
break; break;
case MAV_STATE_EMERGENCY: case MAV_STATE_EMERGENCY:
uasState = tr("EMERGENCY"); uasState = tr("EMERGENCY");
stateDescription = tr("EMERGENCY: Please land"); stateDescription = tr("EMERGENCY: Please land");
break; break;
case MAV_STATE_POWEROFF: case MAV_STATE_POWEROFF:
uasState = tr("SHUTDOWN"); uasState = tr("SHUTDOWN");
stateDescription = tr("Powering off system"); stateDescription = tr("Powering off system");
break; break;
default: default:
uasState = tr("UNKNOWN"); uasState = tr("UNKNOWN");
stateDescription = tr("FAILURE: Unknown system state"); stateDescription = tr("FAILURE: Unknown system state");
break; break;
...@@ -718,19 +774,19 @@ void UAS::setBattery(BatteryType type, int cells) ...@@ -718,19 +774,19 @@ void UAS::setBattery(BatteryType type, int cells)
this->cells = cells; this->cells = cells;
switch (batteryType) switch (batteryType)
{ {
case NICD: case NICD:
break; break;
case NIMH: case NIMH:
break; break;
case LIION: case LIION:
break; break;
case LIPOLY: case LIPOLY:
fullVoltage = this->cells * UAS::lipoFull; fullVoltage = this->cells * UAS::lipoFull;
emptyVoltage = this->cells * UAS::lipoEmpty; emptyVoltage = this->cells * UAS::lipoEmpty;
break; break;
case LIFE: case LIFE:
break; break;
case AGZN: case AGZN:
break; break;
} }
} }
......
...@@ -94,6 +94,7 @@ protected: ...@@ -94,6 +94,7 @@ protected:
QList<double> motorValues; QList<double> motorValues;
QList<QString> motorNames; QList<QString> motorNames;
QList<int> unknownPackets; ///< Packet IDs which are unknown and have been received
double thrustSum; ///< Sum of forward/up thrust of all thrust actuators, in Newtons double thrustSum; ///< Sum of forward/up thrust of all thrust actuators, in Newtons
double thrustMax; ///< Maximum forward/up thrust of this vehicle, in Newtons double thrustMax; ///< Maximum forward/up thrust of this vehicle, in Newtons
......
...@@ -34,6 +34,7 @@ This file is part of the PIXHAWK project ...@@ -34,6 +34,7 @@ This file is part of the PIXHAWK project
#include "ObjectDetectionView.h" #include "ObjectDetectionView.h"
#include "ui_ObjectDetectionView.h" #include "ui_ObjectDetectionView.h"
#include "UASManager.h" #include "UASManager.h"
#include "GAudioOutput.h"
#include <QDebug> #include <QDebug>
...@@ -81,13 +82,18 @@ void ObjectDetectionView::newDetection(int uasId, QString patternPath, int x1, i ...@@ -81,13 +82,18 @@ void ObjectDetectionView::newDetection(int uasId, QString patternPath, int x1, i
{ {
if (patternList.contains(patternPath)) if (patternList.contains(patternPath))
{ {
qDebug() << "REDETECTED";
QList<QAction*> actions = m_ui->listWidget->actions(); QList<QAction*> actions = m_ui->listWidget->actions();
// Find action and update it // Find action and update it
foreach (QAction* act, actions) foreach (QAction* act, actions)
{ {
qDebug() << "ACTION";
if (act->text().trimmed().split(separator).first() == patternPath) if (act->text().trimmed().split(separator).first() == patternPath)
{ {
act->setText(patternPath + separator + "(#" + QString::number(patternCount.value(patternPath)) + ")" + separator + QString::number(confidence)); int count = patternCount.value(patternPath);
patternCount.insert(patternPath, count);
act->setText(patternPath + separator + "(#" + QString::number(count) + ")" + separator + QString::number(confidence));
} }
} }
QPixmap image = QPixmap(patternFolder + "/" + patternPath); QPixmap image = QPixmap(patternFolder + "/" + patternPath);
...@@ -101,6 +107,9 @@ void ObjectDetectionView::newDetection(int uasId, QString patternPath, int x1, i ...@@ -101,6 +107,9 @@ void ObjectDetectionView::newDetection(int uasId, QString patternPath, int x1, i
} }
else else
{ {
// Emit audio message on detection
if (detected) GAudioOutput::instance()->say("System " + QString::number(uasId) + " detected pattern " + QString(patternPath.split("/").last()).split(".").first());
patternList.insert(patternPath, confidence); patternList.insert(patternPath, confidence);
patternCount.insert(patternPath, 1); patternCount.insert(patternPath, 1);
QPixmap image = QPixmap(patternFolder + "/" + patternPath); QPixmap image = QPixmap(patternFolder + "/" + patternPath);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment