Newer
Older
mavlink_msg_mission_current_decode(&message, &wpc);
waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
}
case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
if (multiComponentSourceDetected && wrongComponent)
{
mavlink_local_position_setpoint_t p;
mavlink_msg_local_position_setpoint_decode(&message, &p);
emit positionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw, QGC::groundTimeUsecs());
}
case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
{
mavlink_set_local_position_setpoint_t p;
mavlink_msg_set_local_position_setpoint_decode(&message, &p);
emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw);
}
case MAVLINK_MSG_ID_STATUSTEXT:
{
QByteArray b;
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
mavlink_msg_statustext_get_text(&message, b.data());
//b.append('\0');
QString text = QString(b);
int severity = mavlink_msg_statustext_get_severity(&message);
//qDebug() << "RECEIVED STATUS:" << text;false
//emit statusTextReceived(severity, text);
if (text.startsWith("#audio:"))
{
text.remove("#audio:");
emit textMessageReceived(uasId, message.compid, severity, QString("Audio message: ") + text);
GAudioOutput::instance()->say(text, severity);
}
else
{
emit textMessageReceived(uasId, message.compid, severity, text);
}
#ifdef MAVLINK_ENABLED_PIXHAWK
case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
{
qDebug() << "RECIEVED ACK TO GET IMAGE";
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();
}
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];
// emit signal if all packets arrived
if ((imagePacketsArrived >= imagePackets))
{
// Restart statemachine
imagePacketsArrived = 0;
emit imageReady(this);
//qDebug() << "imageReady emitted. all packets arrived";
#endif
1100
1101
1102
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
1120
1121
1122
1123
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
1156
// case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT:
// {
// mavlink_object_detection_event_t event;
// mavlink_msg_object_detection_event_decode(&message, &event);
// QString str(event.name);
// emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance);
// }
// break;
// WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET
// case MAVLINK_MSG_ID_MEMORY_VECT:
// {
// mavlink_memory_vect_t vect;
// mavlink_msg_memory_vect_decode(&message, &vect);
// QString str("mem_%1");
// quint64 time = getUnixTime(0);
// int16_t *mem0 = (int16_t *)&vect.value[0];
// uint16_t *mem1 = (uint16_t *)&vect.value[0];
// int32_t *mem2 = (int32_t *)&vect.value[0];
// // uint32_t *mem3 = (uint32_t *)&vect.value[0]; causes overload problem
// float *mem4 = (float *)&vect.value[0];
// if ( vect.ver == 0) vect.type = 0, vect.ver = 1; else ;
// if ( vect.ver == 1)
// {
// switch (vect.type) {
// default:
// case 0:
// for (int i = 0; i < 16; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
// break;
// case 1:
// for (int i = 0; i < 16; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
// break;
// case 2:
// for (int i = 0; i < 16; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
// break;
// case 3:
// for (int i = 0; i < 16; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
// break;
// case 4:
// for (int i = 0; i < 8; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
// break;
// case 5:
// for (int i = 0; i < 8; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
// break;
// case 6:
// for (int i = 0; i < 8; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
// break;
// }
// }
// }
// break;
case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
{
mavlink_nav_filter_bias_t bias;
mavlink_msg_nav_filter_bias_decode(&message, &bias);
quint64 time = getUnixTime();
// FIXME REMOVE LATER emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time);
}
case MAVLINK_MSG_ID_RADIO_CALIBRATION:
1172
1173
1174
1175
1176
1177
1178
1179
1180
1181
1182
1183
1184
1185
1186
1187
1188
1189
1190
1191
1192
1193
1194
1195
1196
1197
1198
{
mavlink_radio_calibration_t radioMsg;
mavlink_msg_radio_calibration_decode(&message, &radioMsg);
QVector<uint16_t> aileron;
QVector<uint16_t> elevator;
QVector<uint16_t> rudder;
QVector<uint16_t> gyro;
QVector<uint16_t> pitch;
QVector<uint16_t> throttle;
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN; ++i)
aileron << radioMsg.aileron[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN; ++i)
elevator << radioMsg.elevator[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN; ++i)
rudder << radioMsg.rudder[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN; ++i)
gyro << radioMsg.gyro[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN; ++i)
pitch << radioMsg.pitch[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN; ++i)
throttle << radioMsg.throttle[i];
QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
emit radioCalibrationReceived(radioData);
delete radioData;
}
case MAVLINK_MSG_ID_RAW_IMU:
case MAVLINK_MSG_ID_SCALED_IMU:
case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
case MAVLINK_MSG_ID_RAW_PRESSURE:
case MAVLINK_MSG_ID_SCALED_PRESSURE:
case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
case MAVLINK_MSG_ID_OPTICAL_FLOW:
case MAVLINK_MSG_ID_DEBUG_VECT:
case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
case MAVLINK_MSG_ID_NAMED_VALUE_INT:
Lorenz Meier
committed
case MAVLINK_MSG_ID_MANUAL_CONTROL:
case MAVLINK_MSG_ID_HIGHRES_IMU:
default:
{
if (!unknownPackets.contains(message.msgid))
{
unknownPackets.append(message.msgid);
QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid);
//GAudioOutput::instance()->say(errString+tr(", please check console for details."));
emit textMessageReceived(uasId, message.compid, 255, errString);
std::cout << "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;
hengli
committed
#if defined(QGC_PROTOBUF_ENABLED)
Lionel Heng
committed
void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message)
{
Lionel Heng
committed
if (!links->contains(link))
{
addLink(link);
}
1252
1253
1254
1255
1256
1257
1258
1259
1260
1261
1262
1263
1264
1265
1266
1267
1268
1269
1270
1271
1272
1273
1274
1275
1276
1277
1278
1279
1280
1281
1282
1283
1284
1285
1286
const google::protobuf::Descriptor* descriptor = message->GetDescriptor();
if (!descriptor)
{
return;
}
const google::protobuf::FieldDescriptor* headerField = descriptor->FindFieldByName("header");
if (!headerField)
{
return;
}
const google::protobuf::Descriptor* headerDescriptor = headerField->message_type();
if (!headerDescriptor)
{
return;
}
const google::protobuf::FieldDescriptor* sourceSysIdField = headerDescriptor->FindFieldByName("source_sysid");
if (!sourceSysIdField)
{
return;
}
const google::protobuf::Reflection* reflection = message->GetReflection();
const google::protobuf::Message& headerMsg = reflection->GetMessage(*message, headerField);
const google::protobuf::Reflection* headerReflection = headerMsg.GetReflection();
int source_sysid = headerReflection->GetInt32(headerMsg, sourceSysIdField);
if (source_sysid != uasId)
{
return;
}
hengli
committed
#ifdef QGC_USE_PIXHAWK_MESSAGES
if (message->GetTypeName() == overlay.GetTypeName())
Lionel Heng
committed
{
receivedOverlayTimestamp = QGC::groundTimeSeconds();
overlayMutex.lock();
overlay.CopyFrom(*message);
overlayMutex.unlock();
emit overlayChanged(this);
Lionel Heng
committed
}
else if (message->GetTypeName() == obstacleList.GetTypeName())
{
receivedObstacleListTimestamp = QGC::groundTimeSeconds();
obstacleList.CopyFrom(*message);
emit obstacleListChanged(this);
}
else if (message->GetTypeName() == path.GetTypeName())
{
receivedPathTimestamp = QGC::groundTimeSeconds();
path.CopyFrom(*message);
emit pathChanged(this);
}
else if (message->GetTypeName() == pointCloud.GetTypeName())
{
receivedPointCloudTimestamp = QGC::groundTimeSeconds();
pointCloudMutex.lock();
pointCloud.CopyFrom(*message);
pointCloudMutex.unlock();
emit pointCloudChanged(this);
}
else if (message->GetTypeName() == rgbdImage.GetTypeName())
{
receivedRGBDImageTimestamp = QGC::groundTimeSeconds();
rgbdImageMutex.lock();
rgbdImage.CopyFrom(*message);
rgbdImageMutex.unlock();
emit rgbdImageChanged(this);
}
hengli
committed
#endif
Lionel Heng
committed
}
#endif
* @param lat The latitude fo the home position
* @param lon The longitute of the home position
* @param alt The altitude of the home position
void UAS::setHomePosition(double lat, double lon, double alt)
{
1341
1342
1343
1344
1345
1346
1347
1348
1349
1350
1351
1352
1353
1354
1355
1356
1357
1358
1359
1360
1361
1362
1363
1364
1365
1366
1367
1368
1369
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Warning);
msgBox.setText("Setting new World Coordinate Frame Origin");
msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location");
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 msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 0, 0, 0, 0, lat, lon, alt);
// Send message twice to increase chance that it reaches its goal
sendMessage(msg);
// Send new home position to UAS
mavlink_set_gps_global_origin_t home;
home.target_system = uasId;
home.latitude = lat*1E7;
home.longitude = lon*1E7;
home.altitude = alt*1000;
qDebug() << "lat:" << home.latitude << " lon:" << home.longitude;
mavlink_msg_set_gps_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home);
sendMessage(msg);
}
* Set the origin to the current GPS location.
void UAS::setLocalOriginAtCurrentGPSPosition()
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Warning);
msgBox.setText("Setting new World Coordinate Frame Origin");
msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location");
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 msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 1, 0, 0, 0, 0, 0, 0);
// Send message twice to increase chance that it reaches its goal
sendMessage(msg);
* @param x postion
* @param y position
* @param z position
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw/M_PI*180.0);
#else
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
#endif
* @param x position
* @param y position
* @param z position
* @param yaw
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
mavlink_message_t msg;
mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
sendMessage(msg);
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
#endif
}
void UAS::startRadioControlCalibration()
mavlink_message_t msg;
// Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1, 0, 0, 0);
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2, 0, 0, 0);
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0, 0, 0, 0);
void UAS::startMagnetometerCalibration()
{
mavlink_message_t msg;
// Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0, 0, 0, 0);
}
void UAS::startGyroscopeCalibration()
{
mavlink_message_t msg;
// Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0, 0, 0, 0);
}
void UAS::startPressureCalibration()
{
mavlink_message_t msg;
// Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 1, 0, 0, 0, 0);
/**
* 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.
1491
1492
1493
1494
1495
1496
1497
1498
1499
1500
1501
1502
1503
1504
1505
1506
1507
1508
1509
1510
1511
1512
1513
1514
1515
1516
1517
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
// 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
* 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)
{
if (time == 0)
{
}
// 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)
// qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
if (onboardTimeOffset == 0 || time < (lastNonNullTime - 100))
{
lastNonNullTime = time;
}
if (time > lastNonNullTime) lastNonNullTime = time;
}
else
{
// Time is not zero and larger than 40 years -> has to be
// a Unix epoch timestamp. Do nothing.
}
}
* @param component that will be searched for in the map of parameters.
lm
committed
QList<QString> UAS::getParameterNames(int component)
{
if (parameters.contains(component))
{
lm
committed
return parameters.value(component)->keys();
}
else
{
lm
committed
return QList<QString>();
}
}
QList<int> UAS::getComponentIds()
{
return parameters.keys();
}
* @param mode that UAS is to be set to.
*/
//this->mode = mode; //no call assignament, update receive message from UAS
mavlink_message_t msg;
mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode, (uint16_t)navMode);
sendMessage(msg);
qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
* Send a message to every link that is connected.
void UAS::sendMessage(mavlink_message_t message)
{
// Emit message on all links that are currently connected
foreach (LinkInterface* link, *links)
{
Lorenz Meier
committed
//qDebug() << "ITERATING THROUGH LINKS";
if (link)
{
sendMessage(link, message);
Lorenz Meier
committed
//qDebug() << "SENT MESSAGE";
}
else
{
// Remove from list
links->removeAt(links->indexOf(link));
}
* Forward a message to all links that are currently connected.
void UAS::forwardMessage(mavlink_message_t message)
{
// Emit message on all links that are currently connected
QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
foreach(LinkInterface* link, link_list)
{
if (link)
{
SerialLink* serial = dynamic_cast<SerialLink*>(link);
if(serial != 0)
{
for(int i=0; i<links->size(); i++)
{
if(serial != links->at(i))
{
qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
sendMessage(serial, message);
}
}
}
}
}
}
* Send a message to the link that is connected.
* @param link that the message will be sent to
* @message that is to be sent
void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
{
// Create buffer
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
// Write message into buffer, prepending start sign
int len = mavlink_msg_to_send_buffer(buffer, &message);
static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
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;
* The mode can be preflight or unknown.
* @Return the mode of the autopilot
QString UAS::getNavModeText(int mode)
{
switch (mode)
{
case 0:
return QString("PREFLIGHT");
break;
default:
return QString("UNKNOWN");
}
}
else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
return QString("UNKNOWN");
}
else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
{
return QString("UNKNOWN");
}
// If nothing matches, return unknown
return QString("UNKNOWN");
/**
* 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)
{
stateDescription = tr("Unitialized, booting up.");
stateDescription = tr("Booting system, please wait.");
stateDescription = tr("Calibrating sensors, please wait.");
stateDescription = tr("Active, normal operation.");
stateDescription = tr("Standby mode, ready for launch.");
stateDescription = tr("FAILURE: Continuing operation.");
stateDescription = tr("EMERGENCY: Land Immediately!");
//uasState = tr("HIL SIM");
//stateDescription = tr("HIL Simulation, Sensors read from SIM");
//break;
Mariano Lizarraga
committed
stateDescription = tr("Powering off system.");
Mariano Lizarraga
committed
stateDescription = tr("Unknown system state");
// qDebug() << "IMAGE TYPE:" << imageType;
// RAW greyscale
if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
{
// TODO FIXME
int imgColors = 255;//imageSize/(imageWidth*imageHeight);
//const int headerSize = 15;
// Construct PGM header
QString header("P5\n%1 %2\n%3\n");
header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
1826
1827
1828
1829
1830
1831
1832
1833
1834
1835
1836
1837
1838
1839
1840
1841
1842
1843
1844
1845
1846
1847
1848
1849
1850
QByteArray tmpImage(header.toStdString().c_str(), header.toStdString().size());
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()<< "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)
{
qDebug() << "Loading data from image buffer failed!";
// Restart statemachine
imagePacketsArrived = 0;
}
void UAS::requestImage()
{
qDebug() << "trying to get an image from the uas...";
// check if there is already an image transmission going on
if (imagePacketsArrived == 0)
{
mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50);
#endif
quint64 UAS::getUptime() const
if(startTime == 0)
{
}
else
{
int UAS::getCommunicationStatus() const
void UAS::requestParameters()
{
mavlink_message_t msg;
mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL);
qDebug() << __FILE__ << __LINE__ << "LOADING PARAM LIST";
}
{
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
}
void UAS::readParametersFromStorage()
{
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
/**
* @param rate The update rate in Hz the message should be sent
void UAS::enableAllDataTransmission(int rate)
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
// Select the message to request from now on
// 0 is a magic ID and will enable/disable the standard message set except for heartbeat
stream.req_stream_id = MAV_DATA_STREAM_ALL;
// Select the update rate in Hz the message should be send
// All messages will be send with their default rate
// TODO: use 0 to turn off and get rid of enable/disable? will require
// a different magic flag for turning on defaults, possibly something really high like 1111 ?
// The system which should take this command
stream.target_system = uasId;
// The component / subsystem which should take this command
stream.target_component = 0;
// Encode and send the message
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception
sendMessage(msg);
/**
* @param rate The update rate in Hz the message should be sent
void UAS::enableRawSensorDataTransmission(int rate)
mavlink_request_data_stream_t stream;
stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
// The system which should take this command
stream.target_system = uasId;
// The component / subsystem which should take this command
stream.target_component = 0;
// Encode and send the message
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception
sendMessage(msg);
/**
* @param rate The update rate in Hz the message should be sent
void UAS::enableExtendedSystemStatusTransmission(int rate)
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
// Select the message to request from now on
stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
// Select the update rate in Hz the message should be send
// Start / stop the message
// The system which should take this command
stream.target_system = uasId;
// The component / subsystem which should take this command
stream.target_component = 0;
// Encode and send the message
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);