Commit 69aa348d authored by Bryant Mairs's avatar Bryant Mairs

Replaced hard-coded severity values with proper MAV_SEVERITY_* macros.

parent a3943266
......@@ -126,19 +126,19 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
switch (mlAction.actionId) {
case SLUGS_ACTION_EEPROM:
if (mlAction.actionVal == SLUGS_ACTION_FAIL) {
emit textMessageReceived(message.sysid, message.compid, 255, "EEPROM Write Fail, Data was not saved in Memory!");
emit textMessageReceived(message.sysid, message.compid, MAV_SEVERITY_ERROR, "EEPROM Write Fail, Data was not saved in Memory!");
}
break;
case SLUGS_ACTION_PT_CHANGE:
if (mlAction.actionVal == SLUGS_ACTION_SUCCESS) {
emit textMessageReceived(message.sysid, message.compid, 0, "Passthrough Succesfully Changed");
emit textMessageReceived(message.sysid, message.compid, MAV_SEVERITY_INFO, "Passthrough Succesfully Changed");
}
break;
case SLUGS_ACTION_MLC_CHANGE:
if (mlAction.actionVal == SLUGS_ACTION_SUCCESS) {
emit textMessageReceived(message.sysid, message.compid, 0, "Mid-level Commands Succesfully Changed");
emit textMessageReceived(message.sysid, message.compid, MAV_SEVERITY_INFO, "Mid-level Commands Succesfully Changed");
}
break;
}
......
......@@ -955,7 +955,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
setGroundSpeed(vel);
emit speedChanged(this, groundSpeed, airSpeed, time);
} else {
emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_NOTICE, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
}
}
}
......@@ -1055,27 +1055,27 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
case MAV_RESULT_ACCEPTED:
{
emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_INFO, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
}
break;
case MAV_RESULT_TEMPORARILY_REJECTED:
{
emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Temporarily rejected CMD: %1").arg(ack.command));
emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_WARNING, tr("FAILURE: Temporarily rejected CMD: %1").arg(ack.command));
}
break;
case MAV_RESULT_DENIED:
{
emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Denied CMD: %1").arg(ack.command));
emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_ERROR, tr("FAILURE: Denied CMD: %1").arg(ack.command));
}
break;
case MAV_RESULT_UNSUPPORTED:
{
emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Unsupported CMD: %1").arg(ack.command));
emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_WARNING, tr("FAILURE: Unsupported CMD: %1").arg(ack.command));
}
break;
case MAV_RESULT_FAILED:
{
emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Failed CMD: %1").arg(ack.command));
emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_ERROR, tr("FAILURE: Failed CMD: %1").arg(ack.command));
}
break;
}
......@@ -2732,7 +2732,7 @@ void UAS::requestParameter(int component, const QString& parameter)
// Copy full param name or maximum max field size
if (parameter.length() > MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)
{
emit textMessageReceived(uasId, 0, 255, QString("QGC WARNING: Parameter name %1 is more than %2 bytes long. This might lead to errors and mishaps!").arg(parameter).arg(MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN-1));
emit textMessageReceived(uasId, 0, MAV_SEVERITY_WARNING, QString("QGC WARNING: Parameter name %1 is more than %2 bytes long. This might lead to errors and mishaps!").arg(parameter).arg(MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN-1));
}
memcpy(read.param_id, parameter.toStdString().c_str(), qMax(parameter.length(), MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN));
read.param_id[15] = '\0'; // Enforce null termination
......@@ -3595,7 +3595,7 @@ void UAS::setBatterySpecs(const QString& specs)
}
else
{
emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
emit textMessageReceived(0, 0, MAV_SEVERITY_WARNING, "Could not set battery options, format is wrong");
}
}
else
......@@ -3621,7 +3621,7 @@ void UAS::setBatterySpecs(const QString& specs)
}
else
{
emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
emit textMessageReceived(0, 0, MAV_SEVERITY_WARNING, "Could not set battery options, format is wrong");
}
}
}
......
......@@ -302,7 +302,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
// Enforce null termination
str[messageInfo[msgid].fields[fieldid].array_length-1] = '\0';
QString string(name + ": " + str);
if (!textMessageFilter.contains(msgid)) emit textMessageReceived(msg->sysid, msg->compid, 0, string);
if (!textMessageFilter.contains(msgid)) emit textMessageReceived(msg->sysid, msg->compid, MAV_SEVERITY_INFO, string);
}
else
{
......
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