Newer
Older
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
case MAVLINK_MSG_ID_RC_CHANNELS:
{
mavlink_rc_channels_t channels;
mavlink_msg_rc_channels_decode(&message, &channels);
// UINT8_MAX indicates this value is unknown
if (channels.rssi != UINT8_MAX) {
emit remoteControlRSSIChanged(channels.rssi/100.0f);
}
if (channels.chan1_raw != UINT16_MAX && channels.chancount > 0)
emit remoteControlChannelRawChanged(0, channels.chan1_raw);
if (channels.chan2_raw != UINT16_MAX && channels.chancount > 1)
emit remoteControlChannelRawChanged(1, channels.chan2_raw);
if (channels.chan3_raw != UINT16_MAX && channels.chancount > 2)
emit remoteControlChannelRawChanged(2, channels.chan3_raw);
if (channels.chan4_raw != UINT16_MAX && channels.chancount > 3)
emit remoteControlChannelRawChanged(3, channels.chan4_raw);
if (channels.chan5_raw != UINT16_MAX && channels.chancount > 4)
emit remoteControlChannelRawChanged(4, channels.chan5_raw);
if (channels.chan6_raw != UINT16_MAX && channels.chancount > 5)
emit remoteControlChannelRawChanged(5, channels.chan6_raw);
if (channels.chan7_raw != UINT16_MAX && channels.chancount > 6)
emit remoteControlChannelRawChanged(6, channels.chan7_raw);
if (channels.chan8_raw != UINT16_MAX && channels.chancount > 7)
emit remoteControlChannelRawChanged(7, channels.chan8_raw);
if (channels.chan9_raw != UINT16_MAX && channels.chancount > 8)
emit remoteControlChannelRawChanged(8, channels.chan9_raw);
if (channels.chan10_raw != UINT16_MAX && channels.chancount > 9)
emit remoteControlChannelRawChanged(9, channels.chan10_raw);
if (channels.chan11_raw != UINT16_MAX && channels.chancount > 10)
emit remoteControlChannelRawChanged(10, channels.chan11_raw);
if (channels.chan12_raw != UINT16_MAX && channels.chancount > 11)
emit remoteControlChannelRawChanged(11, channels.chan12_raw);
if (channels.chan13_raw != UINT16_MAX && channels.chancount > 12)
emit remoteControlChannelRawChanged(12, channels.chan13_raw);
if (channels.chan14_raw != UINT16_MAX && channels.chancount > 13)
emit remoteControlChannelRawChanged(13, channels.chan14_raw);
if (channels.chan15_raw != UINT16_MAX && channels.chancount > 14)
emit remoteControlChannelRawChanged(14, channels.chan15_raw);
if (channels.chan16_raw != UINT16_MAX && channels.chancount > 15)
emit remoteControlChannelRawChanged(15, channels.chan16_raw);
if (channels.chan17_raw != UINT16_MAX && channels.chancount > 16)
emit remoteControlChannelRawChanged(16, channels.chan17_raw);
if (channels.chan18_raw != UINT16_MAX && channels.chancount > 17)
emit remoteControlChannelRawChanged(17, channels.chan18_raw);
}
break;
case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
{
mavlink_rc_channels_scaled_t channels;
mavlink_msg_rc_channels_scaled_decode(&message, &channels);
const unsigned int portWidth = 8; // XXX magic number
emit remoteControlRSSIChanged(channels.rssi/255.0f);
if (static_cast<uint16_t>(channels.chan1_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 0, channels.chan1_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan2_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 1, channels.chan2_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan3_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 2, channels.chan3_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan4_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 3, channels.chan4_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan5_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 4, channels.chan5_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan6_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 5, channels.chan6_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan7_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 6, channels.chan7_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan8_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 7, channels.chan8_scaled/10000.0f);
}
break;
case MAVLINK_MSG_ID_PARAM_VALUE:
{
mavlink_param_value_t rawValue;
mavlink_msg_param_value_decode(&message, &rawValue);
QByteArray bytes(rawValue.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
// Construct a string stopping at the first NUL (0) character, else copy the whole
// byte array (max MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN, so safe)
QString parameterName(bytes);
mavlink_param_union_t paramVal;
paramVal.param_float = rawValue.param_value;
paramVal.type = rawValue.param_type;
processParamValueMsg(message, parameterName,rawValue,paramVal);
Lorenz Meier
committed
processParamValueMsgHook(message, parameterName,rawValue,paramVal);
break;
case MAVLINK_MSG_ID_COMMAND_ACK:
{
mavlink_command_ack_t ack;
mavlink_msg_command_ack_decode(&message, &ack);
switch (ack.result)
{
case MAV_RESULT_ACCEPTED:
{
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, MAV_SEVERITY_WARNING, tr("FAILURE: Temporarily rejected CMD: %1").arg(ack.command));
}
break;
case MAV_RESULT_DENIED:
{
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, MAV_SEVERITY_WARNING, tr("FAILURE: Unsupported CMD: %1").arg(ack.command));
}
break;
case MAV_RESULT_FAILED:
{
emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_ERROR, tr("FAILURE: Failed CMD: %1").arg(ack.command));
}
break;
}
}
Lorenz Meier
committed
case MAVLINK_MSG_ID_ATTITUDE_TARGET:
Lorenz Meier
committed
mavlink_attitude_target_t out;
mavlink_msg_attitude_target_decode(&message, &out);
float roll, pitch, yaw;
mavlink_quaternion_to_euler(out.q, &roll, &pitch, &yaw);
quint64 time = getUnixTimeFromMs(out.time_boot_ms);
Lorenz Meier
committed
emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, out.thrust, time);
// For plotting emit roll sp, pitch sp and yaw sp values
emit valueChanged(uasId, "roll sp", "rad", roll, out.time_boot_ms);
emit valueChanged(uasId, "pitch sp", "rad", pitch, out.time_boot_ms);
emit valueChanged(uasId, "yaw sp", "rad", yaw, out.time_boot_ms);
}
break;
case MAVLINK_MSG_ID_MISSION_COUNT:
{
mavlink_mission_count_t mc;
mavlink_msg_mission_count_decode(&message, &mc);
// Special case a 0 for the target system or component, it means that anyone is the target, so we should process this.
if (mc.target_system == 0) {
mc.target_system = mavlink->getSystemId();
}
if (mc.target_component == 0) {
mc.target_component = mavlink->getComponentId();
}
// Check that this message applies to the UAS.
Lorenz Meier
committed
if(mc.target_system == mavlink->getSystemId())
Lorenz Meier
committed
if (mc.target_component != mavlink->getComponentId()) {
qDebug() << "The target component ID is not set correctly. This is currently only a warning, but will be turned into an error.";
qDebug() << "Expecting" << mavlink->getComponentId() << "but got" << mc.target_component;
}
waypointManager.handleWaypointCount(message.sysid, message.compid, mc.count);
}
else
{
Lorenz Meier
committed
qDebug() << QString("Received mission count message, but was wrong system id. Expected %1, received %2").arg(mavlink->getSystemId()).arg(mc.target_system);
}
}
break;
case MAVLINK_MSG_ID_MISSION_ITEM:
{
mavlink_mission_item_t mi;
mavlink_msg_mission_item_decode(&message, &mi);
// Special case a 0 for the target system or component, it means that anyone is the target, so we should process this.
if (mi.target_system == 0) {
mi.target_system = mavlink->getSystemId();
}
if (mi.target_component == 0) {
mi.target_component = mavlink->getComponentId();
}
// Check that the item pertains to this UAS.
Lorenz Meier
committed
if(mi.target_system == mavlink->getSystemId())
Lorenz Meier
committed
if (mi.target_component != mavlink->getComponentId()) {
qDebug() << "The target component ID is not set correctly. This is currently only a warning, but will be turned into an error.";
qDebug() << "Expecting" << mavlink->getComponentId() << "but got" << mi.target_component;
}
waypointManager.handleWaypoint(message.sysid, message.compid, &mi);
}
else
{
Lorenz Meier
committed
qDebug() << QString("Received mission item message, but was wrong system id. Expected %1, received %2").arg(mavlink->getSystemId()).arg(mi.target_system);
}
}
break;
case MAVLINK_MSG_ID_MISSION_ACK:
{
mavlink_mission_ack_t ma;
mavlink_msg_mission_ack_decode(&message, &ma);
// Special case a 0 for the target system or component, it means that anyone is the target, so we should process this.
if (ma.target_system == 0) {
ma.target_system = mavlink->getSystemId();
}
if (ma.target_component == 0) {
ma.target_component = mavlink->getComponentId();
}
// Check that the ack pertains to this UAS.
Lorenz Meier
committed
if(ma.target_system == mavlink->getSystemId())
Lorenz Meier
committed
if (ma.target_component != mavlink->getComponentId()) {
qDebug() << tr("The target component ID is not set correctly. This is currently only a warning, but will be turned into an error.");
qDebug() << "Expecting" << mavlink->getComponentId() << "but got" << ma.target_component;
}
waypointManager.handleWaypointAck(message.sysid, message.compid, &ma);
}
else
Lorenz Meier
committed
qDebug() << QString("Received mission ack message, but was wrong system id. Expected %1, received %2").arg(mavlink->getSystemId()).arg(ma.target_system);
}
}
break;
case MAVLINK_MSG_ID_MISSION_REQUEST:
{
mavlink_mission_request_t mr;
mavlink_msg_mission_request_decode(&message, &mr);
// Special case a 0 for the target system or component, it means that anyone is the target, so we should process this.
if (mr.target_system == 0) {
mr.target_system = mavlink->getSystemId();
}
if (mr.target_component == 0) {
mr.target_component = mavlink->getComponentId();
}
// Check that the request pertains to this UAS.
Lorenz Meier
committed
if(mr.target_system == mavlink->getSystemId())
Lorenz Meier
committed
if (mr.target_component != mavlink->getComponentId()) {
qDebug() << QString("The target component ID is not set correctly. This is currently only a warning, but will be turned into an error.");
qDebug() << "Expecting" << mavlink->getComponentId() << "but got" << mr.target_component;
}
waypointManager.handleWaypointRequest(message.sysid, message.compid, &mr);
}
else
{
Lorenz Meier
committed
qDebug() << QString("Received mission request message, but was wrong system id. Expected %1, received %2").arg(mavlink->getSystemId()).arg(mr.target_system);
}
}
break;
case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
{
mavlink_mission_item_reached_t wpr;
mavlink_msg_mission_item_reached_decode(&message, &wpr);
waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
QString text = QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq);
GAudioOutput::instance()->say(text);
emit textMessageReceived(message.sysid, message.compid, MAV_SEVERITY_INFO, text);
}
break;
case MAVLINK_MSG_ID_MISSION_CURRENT:
{
mavlink_mission_current_t wpc;
mavlink_msg_mission_current_decode(&message, &wpc);
waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
}
break;
Lorenz Meier
committed
case MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED:
{
if (multiComponentSourceDetected && wrongComponent)
{
break;
}
Lorenz Meier
committed
mavlink_position_target_local_ned_t p;
mavlink_msg_position_target_local_ned_decode(&message, &p);
quint64 time = getUnixTimeFromMs(p.time_boot_ms);
emit positionSetPointsChanged(uasId, p.x, p.y, p.z, 0/* XXX remove yaw and move it to attitude */, time);
Lorenz Meier
committed
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
Lorenz Meier
committed
mavlink_set_position_target_local_ned_t p;
mavlink_msg_set_position_target_local_ned_decode(&message, &p);
emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, 0/* XXX remove yaw and move it to attitude */);
}
break;
case MAVLINK_MSG_ID_STATUSTEXT:
{
QByteArray b;
Lorenz Meier
committed
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
mavlink_msg_statustext_get_text(&message, b.data());
Lorenz Meier
committed
// Ensure NUL-termination
b[b.length()-1] = '\0';
QString text = QString(b);
int severity = mavlink_msg_statustext_get_severity(&message);
if (text.startsWith("#") || severity <= MAV_SEVERITY_WARNING)
{
text.remove("#audio:");
emit textMessageReceived(uasId, message.compid, severity, QString("Audio message: ") + text);
GAudioOutput::instance()->say(text.toLower(), severity);
}
else
{
emit textMessageReceived(uasId, message.compid, severity, text);
}
}
break;
Hyon Lim (Retina)
committed
#if 0
case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
{
mavlink_servo_output_raw_t raw;
mavlink_msg_servo_output_raw_decode(&message, &raw);
if (hilEnabled && raw.port == 0)
emit hilActuatorsChanged(static_cast<uint64_t>(getUnixTimeFromMs(raw.time_usec)), static_cast<float>(raw.servo1_raw),
static_cast<float>(raw.servo2_raw), static_cast<float>(raw.servo3_raw),
static_cast<float>(raw.servo4_raw), static_cast<float>(raw.servo5_raw), static_cast<float>(raw.servo6_raw),
static_cast<float>(raw.servo7_raw), static_cast<float>(raw.servo8_raw));
}
}
break;
Hyon Lim (Retina)
committed
#endif
case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
{
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();
}
break;
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];
}
++pos;
}
++imagePacketsArrived;
// emit signal if all packets arrived
if (imagePacketsArrived >= imagePackets)
{
// Restart statemachine
emit imageReady(this);
}
}
break;
case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
Michael Carpenter
committed
{
mavlink_nav_controller_output_t p;
mavlink_msg_nav_controller_output_decode(&message,&p);
setDistToWaypoint(p.wp_dist);
setBearingToWaypoint(p.nav_bearing);
emit navigationControllerErrorsChanged(this, p.alt_error, p.aspd_error, p.xtrack_error);
Michael Carpenter
committed
}
break;
// Messages to ignore
case MAVLINK_MSG_ID_RAW_IMU:
case MAVLINK_MSG_ID_SCALED_IMU:
case MAVLINK_MSG_ID_RAW_PRESSURE:
case MAVLINK_MSG_ID_SCALED_PRESSURE:
case MAVLINK_MSG_ID_OPTICAL_FLOW:
case MAVLINK_MSG_ID_DEBUG_VECT:
case MAVLINK_MSG_ID_DEBUG:
case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
case MAVLINK_MSG_ID_NAMED_VALUE_INT:
case MAVLINK_MSG_ID_MANUAL_CONTROL:
case MAVLINK_MSG_ID_HIGHRES_IMU:
break;
default:
{
if (!unknownPackets.contains(message.msgid))
{
unknownPackets.append(message.msgid);
emit unknownPacketReceived(uasId, message.compid, message.msgid);
qDebug() << "Unknown message from system:" << uasId << "message:" << message.msgid;
}
}
break;
}
}
}
/**
* Set the home position of the UAS.
* @param lat The latitude fo the home position
* @param lon The longitude of the home position
* @param alt The altitude of the home position
*/
void UAS::setHomePosition(double lat, double lon, double alt)
{
if (blockHomePositionChanges)
return;
QString uasName = (getUASName() == "")?
tr("UAS") + QString::number(getUASID())
: getUASName();
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Warning);
msgBox.setText(tr("Set a new home position for vehicle %1").arg(uasName));
1452
1453
1454
1455
1456
1457
1458
1459
1460
1461
1462
1463
1464
1465
1466
1467
1468
1469
1470
1471
1472
1473
1474
1475
1476
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);
} else {
blockHomePositionChanges = true;
}
}
/**
* Set the origin to the current GPS location.
**/
void UAS::setLocalOriginAtCurrentGPSPosition()
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Warning);
msgBox.setText("Set the home position at the current GPS position?");
1490
1491
1492
1493
1494
1495
1496
1497
1498
1499
1500
1501
1502
1503
1504
1505
1506
1507
1508
1509
1510
1511
1512
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);
}
}
/**
* Set a local position setpoint.
* @param x postion
* @param y position
* @param z position
*/
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
}
/**
* Set a offset of the local position.
* @param x position
* @param y position
* @param z position
* @param yaw
*/
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
}
Lorenz Meier
committed
void UAS::startRadioControlCalibration(int param)
{
mavlink_message_t msg;
// Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
Lorenz Meier
committed
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, param, 0, 0, 0);
Lorenz Meier
committed
sendMessage(msg);
}
void UAS::endRadioControlCalibration()
{
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, 0, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 0, 0, 0, 0);
1550
1551
1552
1553
1554
1555
1556
1557
1558
1559
1560
1561
1562
1563
1564
1565
1566
1567
1568
1569
1570
1571
1572
1573
1574
1575
1576
1577
1578
1579
1580
1581
1582
1583
1584
1585
1586
1587
1588
1589
1590
sendMessage(msg);
}
void UAS::startDataRecording()
{
mavlink_message_t msg;
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);
sendMessage(msg);
}
void UAS::stopDataRecording()
{
mavlink_message_t msg;
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);
sendMessage(msg);
}
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);
sendMessage(msg);
}
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);
sendMessage(msg);
}
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);
sendMessage(msg);
}
/**
* Check if time is smaller than 40 years, assuming no system without Unix
1593
1594
1595
1596
1597
1598
1599
1600
1601
1602
1603
1604
1605
1606
1607
1608
1609
1610
1611
1612
1613
1614
1615
1616
1617
1618
1619
1620
1621
1622
1623
1624
1625
1626
1627
1628
1629
1630
1631
1632
1633
1634
1635
1636
1637
1638
1639
1640
1641
1642
1643
* 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.
*/
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
else if (time < 1261440000000000)
#endif
{
// 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
1662
1663
1664
1665
1666
1667
1668
1669
1670
1671
1672
1673
1674
1675
1676
1677
1678
1679
1680
1681
1682
1683
1684
1685
1686
1687
1688
1689
1690
1691
1692
1693
1694
1695
1696
1697
1698
1699
1700
1701
1702
1703
1704
1705
1706
1707
1708
1709
1710
1711
1712
1713
1714
1715
1716
1717
1718
1719
1720
1721
1722
1723
1724
1725
1726
1727
1728
1729
1730
1731
1732
1733
1734
1735
1736
1737
1738
1739
* 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)
{
quint64 ret = 0;
if (attitudeStamped)
{
ret = lastAttitude;
}
if (time == 0)
{
ret = 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
else if (time < 1261440000000000)
#endif
{
// qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
if (onboardTimeOffset == 0 || time < (lastNonNullTime - 100))
{
lastNonNullTime = time;
onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
}
if (time > lastNonNullTime) lastNonNullTime = time;
ret = time/1000 + onboardTimeOffset;
}
else
{
// Time is not zero and larger than 40 years -> has to be
// a Unix epoch timestamp. Do nothing.
ret = time/1000;
}
return ret;
}
/**
* @param component that will be searched for in the map of parameters.
*/
QList<QString> UAS::getParameterNames(int component)
{
if (parameters.contains(component))
{
return parameters.value(component)->keys();
}
else
{
return QList<QString>();
}
}
QList<int> UAS::getComponentIds()
{
return parameters.keys();
}
/**
Thomas Gubler
committed
* @param newBaseMode that UAS is to be set to.
* @param newCustomMode that UAS is to be set to.
void UAS::setMode(uint8_t newBaseMode, uint32_t newCustomMode)
Thomas Gubler
committed
if (receivedMode)
{
//this->mode = mode; //no call assignament, update receive message from UAS
Thomas Gubler
committed
// Strip armed / disarmed call for safety reasons, this is not relevant for setting the mode
newBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
// Now set current state (request no change)
newBaseMode |= this->base_mode & MAV_MODE_FLAG_SAFETY_ARMED;
Thomas Gubler
committed
// // Strip HIL part, replace it with current system state
// newBaseMode &= (~MAV_MODE_FLAG_HIL_ENABLED);
// // Now set current state (request no change)
// newBaseMode |= this->base_mode & MAV_MODE_FLAG_HIL_ENABLED;
Thomas Gubler
committed
setModeArm(newBaseMode, newCustomMode);
}
else
{
qDebug() << "WARNING: setMode called before base_mode bitmask was received from UAS, new mode was not sent to system";
Thomas Gubler
committed
}
}
/**
* @param newBaseMode that UAS is to be set to.
* @param newCustomMode that UAS is to be set to.
*/
void UAS::setModeArm(uint8_t newBaseMode, uint32_t newCustomMode)
{
if (receivedMode)
{
mavlink_message_t msg;
mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, newBaseMode, newCustomMode);
qDebug() << "mavlink_msg_set_mode_pack 1";
sendMessage(msg);
qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", MODE " << newBaseMode << " " << newCustomMode;
}
else
{
qDebug() << "WARNING: setModeArm called before base_mode bitmask was received from UAS, new mode was not sent to system";
Thomas Gubler
committed
}
}
/**
* Send a message to every link that is connected.
* @param message that is to be sent
*/
void UAS::sendMessage(mavlink_message_t message)
{
if (!LinkManager::instance())
{
return;
}
if (links->count() < 1) {
qDebug() << "NO LINK AVAILABLE TO SEND!";
}
// Emit message on all links that are currently connected
foreach (LinkInterface* link, *links)
{
if (LinkManager::instance()->getLinks().contains(link))
{
if (link->isConnected())
sendMessage(link, message);
1810
1811
1812
1813
1814
1815
1816
1817
1818
1819
1820
1821
1822
1823
1824
1825
1826
1827
1828
1829
1830
1831
1832
1833
1834
1835
1836
1837
1838
}
else
{
// Remove from list
links->removeAt(links->indexOf(link));
}
}
}
/**
* Forward a message to all links that are currently connected.
* @param message that is to be forwarded
*/
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))
{
if (link->isConnected()) {
qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
sendMessage(serial, message);
}
1843
1844
1845
1846
1847
1848
1849
1850
1851
1852
1853
1854
1855
1856
1857
1858
1859
1860
1861
1862
1863
}
}
}
}
}
}
/**
* 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)
{
if(!link) return;
// 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 is connected
if (link->isConnected())
{
// Send the portion of the buffer now occupied by the message
link->writeBytes((const char*)buffer, len);
}
else
{
qDebug() << "LINK NOT CONNECTED, NOT SENDING!";
}
}
/**
* @param value battery voltage
*/
float UAS::filterVoltage(float value) const
{
/**
1886
1887
1888
1889
1890
1891
1892
1893
1894
1895
1896
1897
1898
1899
1900
1901
1902
1903
1904
1905
1906
1907
1908
1909
1910
1911
1912
1913
1914
1915
1916
1917
1918
1919
1920
1921
1922
1923
1924
1925
1926
1927
1928
1929
1930
1931
1932
1933
1934
1935
1936
1937
1938
1939
1940
1941
1942
1943
1944
1945
1946
* 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)
{
case MAV_STATE_UNINIT:
uasState = tr("UNINIT");
stateDescription = tr("Unitialized, booting up.");
break;
case MAV_STATE_BOOT:
uasState = tr("BOOT");
stateDescription = tr("Booting system, please wait.");
break;
case MAV_STATE_CALIBRATING:
uasState = tr("CALIBRATING");
stateDescription = tr("Calibrating sensors, please wait.");
break;
case MAV_STATE_ACTIVE:
uasState = tr("ACTIVE");
stateDescription = tr("Active, normal operation.");
break;
case MAV_STATE_STANDBY:
uasState = tr("STANDBY");
stateDescription = tr("Standby mode, ready for launch.");
break;
case MAV_STATE_CRITICAL:
uasState = tr("CRITICAL");
stateDescription = tr("FAILURE: Continuing operation.");
break;
case MAV_STATE_EMERGENCY:
uasState = tr("EMERGENCY");
stateDescription = tr("EMERGENCY: Land Immediately!");
break;
//case MAV_STATE_HILSIM:
//uasState = tr("HIL SIM");
//stateDescription = tr("HIL Simulation, Sensors read from SIM");
//break;
case MAV_STATE_POWEROFF:
uasState = tr("SHUTDOWN");
stateDescription = tr("Powering off system.");
break;
default:
uasState = tr("UNKNOWN");
stateDescription = tr("Unknown system state");
break;
}
}
QImage UAS::getImage()
{
// qDebug() << "IMAGE TYPE:" << imageType;
// RAW greyscale
if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
{
// Construct PGM header
QString header("P5\n%1 %2\n%3\n");
header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
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()<< __FILE__ << __LINE__ << "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)
{
if (!image.loadFromData(imageRecBuffer))
{
qDebug() << __FILE__ << __LINE__ << "Loading data from image buffer failed!";
// Restart statemachine
imagePacketsArrived = 0;
imagePackets = 0;
imageRecBuffer.clear();
return image;
}
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_message_t msg;
mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, MAVLINK_DATA_STREAM_IMG_JPEG, 0, 0, 0, 0, 0, 50);