Commit 146474c9 authored by lm's avatar lm

Onboard params work on console

parent 6c0d0f01
...@@ -197,6 +197,18 @@ bool GAudioOutput::startEmergency() ...@@ -197,6 +197,18 @@ bool GAudioOutput::startEmergency()
return true; return true;
} }
/**
* The emergency sound will be played continously during the emergency.
* call stopEmergency() to disable it again. No speech synthesis or other
* audio output is available during the emergency.
*
* @return true if the emergency could be started, false else
*/
bool GAudioOutput::startEmergency(QString message)
{
return startEmergency();
}
/** /**
* Stops the continous emergency sound. Use startEmergency() to start * Stops the continous emergency sound. Use startEmergency() to start
* the emergency sound. * the emergency sound.
......
...@@ -77,6 +77,8 @@ public slots: ...@@ -77,6 +77,8 @@ public slots:
bool alert(QString text); bool alert(QString text);
/** @brief Start emergency sound */ /** @brief Start emergency sound */
bool startEmergency(); bool startEmergency();
/** @brief Start emergency sound */
bool startEmergency(QString);
/** @brief Stop emergency sound */ /** @brief Stop emergency sound */
bool stopEmergency(); bool stopEmergency();
/** @brief Select female voice */ /** @brief Select female voice */
......
...@@ -67,7 +67,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : ...@@ -67,7 +67,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) :
manualThrust(0), manualThrust(0),
receiveDropRate(0), receiveDropRate(0),
sendDropRate(0), sendDropRate(0),
unknownPackets() unknownPackets(),
lowBattAlarm(false)
{ {
setBattery(LIPOLY, 3); setBattery(LIPOLY, 3);
mavlink = protocol; mavlink = protocol;
...@@ -181,6 +182,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -181,6 +182,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining); emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
emit voltageChanged(message.sysid, state.vbat/1000.0f); emit voltageChanged(message.sysid, state.vbat/1000.0f);
// LOW BATTERY ALARM
float chargeLevel = getChargeLevel();
if (chargeLevel <= 10.0f)
{
startLowBattAlarm();
}
else
{
stopLowBattAlarm();
}
// COMMUNICATIONS DROP RATE // COMMUNICATIONS DROP RATE
emit dropRateChanged(this->getUASID(), this->receiveDropRate, this->sendDropRate); emit dropRateChanged(this->getUASID(), this->receiveDropRate, this->sendDropRate);
...@@ -806,11 +818,32 @@ int UAS::calculateTimeRemaining() ...@@ -806,11 +818,32 @@ int UAS::calculateTimeRemaining()
return remaining; return remaining;
} }
/**
* @return charge level in percent - 0 - 100
*/
double UAS::getChargeLevel() double UAS::getChargeLevel()
{ {
return 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage)); return 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
} }
void UAS::startLowBattAlarm()
{
if (!lowBattAlarm)
{
GAudioOutput::instance()->startEmergency("BATTERY");
lowBattAlarm = true;
}
}
void UAS::stopLowBattAlarm()
{
if (lowBattAlarm)
{
GAudioOutput::instance()->stopEmergency();
lowBattAlarm = false;
}
}
void UAS::clearWaypointList() void UAS::clearWaypointList()
{ {
mavlink_message_t message; mavlink_message_t message;
......
...@@ -121,6 +121,7 @@ protected: ...@@ -121,6 +121,7 @@ protected:
double manualThrust; ///< Thrust set by human pilot (radians) double manualThrust; ///< Thrust set by human pilot (radians)
float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs) float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs)
float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS
bool lowBattAlarm; ///< Switch if battery is low
/** @brief Set the current battery type */ /** @brief Set the current battery type */
void setBattery(BatteryType type, int cells); void setBattery(BatteryType type, int cells);
...@@ -136,7 +137,9 @@ protected: ...@@ -136,7 +137,9 @@ protected:
public slots: public slots:
/** @brief Launches the system **/ /** @brief Launches the system **/
void launch(); void launch();
/** @brief Write this waypoint to the list of waypoints */
void setWaypoint(Waypoint* wp); void setWaypoint(Waypoint* wp);
/** @brief Set currently active waypoint */
void setWaypointActive(int id); void setWaypointActive(int id);
/** @brief Order the robot to return home / to land on the runway **/ /** @brief Order the robot to return home / to land on the runway **/
void home(); void home();
...@@ -151,6 +154,9 @@ public slots: ...@@ -151,6 +154,9 @@ public slots:
/** @brief Shut the system cleanly down. Will shut down any onboard computers **/ /** @brief Shut the system cleanly down. Will shut down any onboard computers **/
void shutdown(); void shutdown();
void startLowBattAlarm();
void stopLowBattAlarm();
void requestWaypoints(); void requestWaypoints();
void requestParameters(); void requestParameters();
void clearWaypointList(); void clearWaypointList();
......
...@@ -14,10 +14,6 @@ ParameterInterface::ParameterInterface(QWidget *parent) : ...@@ -14,10 +14,6 @@ ParameterInterface::ParameterInterface(QWidget *parent) :
m_ui->setupUi(this); m_ui->setupUi(this);
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*))); connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)));
// FIXME Testing TODO
QString testData = "IMU\n ROLL_K_P\t0.527\n ROLL_K_I\t1.255\n PITCH_K_P\t0.621\n PITCH_K_I\t2.5545\n";
tree = new ParamTreeModel(); tree = new ParamTreeModel();
treeView = new QTreeView(); treeView = new QTreeView();
...@@ -76,11 +72,10 @@ void ParameterInterface::addComponent(UASInterface* uas, int component, QString ...@@ -76,11 +72,10 @@ void ParameterInterface::addComponent(UASInterface* uas, int component, QString
void ParameterInterface::receiveParameter(int uas, int component, QString parameterName, float value) void ParameterInterface::receiveParameter(int uas, int component, QString parameterName, float value)
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
qDebug() << "RECEIVED PARAMETER" << component << parameterName << value;
// Insert parameter into map // Insert parameter into map
tree->appendParam(component, parameterName, value); tree->appendParam(component, parameterName, value);
// Refresh view // Refresh view
treeView->setModel(tree); treeView->update();
} }
/** /**
......
...@@ -40,7 +40,8 @@ ParamTreeModel::ParamTreeModel(QObject *parent) ...@@ -40,7 +40,8 @@ ParamTreeModel::ParamTreeModel(QObject *parent)
QList<QVariant> rootData; QList<QVariant> rootData;
rootData << tr("Parameter") << tr("Value"); rootData << tr("Parameter") << tr("Value");
rootItem = new ParamTreeItem(rootData); rootItem = new ParamTreeItem(rootData);
//setupModelData(data.split(QString("\n")), rootItem); QString data = "IMU\n ROLL_K_I\t1.255\n PITCH_K_P\t0.621\n PITCH_K_I\t2.5545\n";
setupModelData(data.split(QString("\n")), rootItem);
} }
ParamTreeModel::ParamTreeModel(const QString &data, QObject *parent) ParamTreeModel::ParamTreeModel(const QString &data, QObject *parent)
...@@ -153,20 +154,29 @@ void ParamTreeModel::appendComponent(int componentId, QString name) ...@@ -153,20 +154,29 @@ void ParamTreeModel::appendComponent(int componentId, QString name)
{ {
if (!components.contains(componentId)) if (!components.contains(componentId))
{ {
ParamTreeItem* item = new ParamTreeItem(name + QString("(") + QString::number(componentId) + QString(")"), 0, rootItem); ParamTreeItem* item = new ParamTreeItem(name + QString("(#") + QString::number(componentId) + QString(")"), 0, rootItem);
components.insert(componentId, item);
}
}
void ParamTreeModel::appendComponent(int componentId)
{
if (!components.contains(componentId))
{
ParamTreeItem* item = new ParamTreeItem(QString("Component #") + QString::number(componentId) + QString(""), 0, rootItem);
components.insert(componentId, item); components.insert(componentId, item);
} }
} }
void ParamTreeModel::appendParam(int componentId, QString name, float value) void ParamTreeModel::appendParam(int componentId, QString name, float value)
{ {
ParamTreeItem* comp = components.value(componentId);
// If component does not exist yet // If component does not exist yet
if (comp == NULL) if (!components.contains(componentId))
{ {
appendComponent(componentId, name); appendComponent(componentId);
comp = components.value(componentId);
} }
ParamTreeItem* comp = components.value(componentId);
// FIXME Children may be double here // FIXME Children may be double here
comp->appendChild(new ParamTreeItem(name, value, comp)); comp->appendChild(new ParamTreeItem(name, value, comp));
qDebug() << __FILE__ << __LINE__ << "Added param" << name << value << "for component" << comp->getParamName(); qDebug() << __FILE__ << __LINE__ << "Added param" << name << value << "for component" << comp->getParamName();
......
...@@ -61,6 +61,8 @@ public slots: ...@@ -61,6 +61,8 @@ public slots:
void appendParam(int componentId, QString name, float value); void appendParam(int componentId, QString name, float value);
/** @brief Add a new component for this system */ /** @brief Add a new component for this system */
void appendComponent(int componentId, QString name); void appendComponent(int componentId, QString name);
/** @brief Add a new component for this system */
void appendComponent(int componentId);
protected: protected:
ParamTreeItem* getNodeForComponentId(int id); ParamTreeItem* getNodeForComponentId(int id);
......
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