|
|
@ -75,12 +75,12 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), |
|
|
|
pitch(0.0), |
|
|
|
pitch(0.0), |
|
|
|
yaw(0.0), |
|
|
|
yaw(0.0), |
|
|
|
statusTimeout(new QTimer(this)), |
|
|
|
statusTimeout(new QTimer(this)), |
|
|
|
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) |
|
|
|
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) |
|
|
|
receivedPointCloudTimestamp(0.0), |
|
|
|
receivedPointCloudTimestamp(0.0), |
|
|
|
receivedRGBDImageTimestamp(0.0), |
|
|
|
receivedRGBDImageTimestamp(0.0), |
|
|
|
receivedObstacleListTimestamp(0.0), |
|
|
|
receivedObstacleListTimestamp(0.0), |
|
|
|
receivedPathTimestamp(0.0), |
|
|
|
receivedPathTimestamp(0.0), |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
paramsOnceRequested(false), |
|
|
|
paramsOnceRequested(false), |
|
|
|
airframe(QGC_AIRFRAME_EASYSTAR), |
|
|
|
airframe(QGC_AIRFRAME_EASYSTAR), |
|
|
|
attitudeKnown(false), |
|
|
|
attitudeKnown(false), |
|
|
@ -274,6 +274,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) |
|
|
|
{ |
|
|
|
{ |
|
|
|
case MAVLINK_MSG_ID_HEARTBEAT: |
|
|
|
case MAVLINK_MSG_ID_HEARTBEAT: |
|
|
|
{ |
|
|
|
{ |
|
|
|
|
|
|
|
if (multiComponentSourceDetected && wrongComponent) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
} |
|
|
|
lastHeartbeat = QGC::groundTimeUsecs(); |
|
|
|
lastHeartbeat = QGC::groundTimeUsecs(); |
|
|
|
emit heartbeat(this); |
|
|
|
emit heartbeat(this); |
|
|
|
mavlink_heartbeat_t state; |
|
|
|
mavlink_heartbeat_t state; |
|
|
@ -381,22 +385,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) |
|
|
|
GAudioOutput::instance()->say(audiostring.toLower()); |
|
|
|
GAudioOutput::instance()->say(audiostring.toLower()); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// if (state.system_status == MAV_STATE_POWEROFF)
|
|
|
|
// if (state.system_status == MAV_STATE_POWEROFF)
|
|
|
|
// {
|
|
|
|
// {
|
|
|
|
// emit systemRemoved(this);
|
|
|
|
// emit systemRemoved(this);
|
|
|
|
// emit systemRemoved();
|
|
|
|
// emit systemRemoved();
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
break; |
|
|
|
break; |
|
|
|
// case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
|
|
|
|
// case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
|
|
|
|
// case MAVLINK_MSG_ID_NAMED_VALUE_INT:
|
|
|
|
// case MAVLINK_MSG_ID_NAMED_VALUE_INT:
|
|
|
|
// // Receive named value message
|
|
|
|
// // Receive named value message
|
|
|
|
// receiveMessageNamedValue(message);
|
|
|
|
// receiveMessageNamedValue(message);
|
|
|
|
// break;
|
|
|
|
// break;
|
|
|
|
case MAVLINK_MSG_ID_SYS_STATUS: |
|
|
|
case MAVLINK_MSG_ID_SYS_STATUS: |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (multiComponentSourceDetected && message.compid != MAV_COMP_ID_IMU_2) |
|
|
|
if (multiComponentSourceDetected && wrongComponent) |
|
|
|
{ |
|
|
|
{ |
|
|
|
break; |
|
|
|
break; |
|
|
|
} |
|
|
|
} |
|
|
@ -445,22 +449,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) |
|
|
|
pitch = QGC::limitAngleToPMPIf(attitude.pitch); |
|
|
|
pitch = QGC::limitAngleToPMPIf(attitude.pitch); |
|
|
|
yaw = QGC::limitAngleToPMPIf(attitude.yaw); |
|
|
|
yaw = QGC::limitAngleToPMPIf(attitude.yaw); |
|
|
|
|
|
|
|
|
|
|
|
// // Emit in angles
|
|
|
|
// // Emit in angles
|
|
|
|
|
|
|
|
|
|
|
|
// // Convert yaw angle to compass value
|
|
|
|
// // Convert yaw angle to compass value
|
|
|
|
// // in 0 - 360 deg range
|
|
|
|
// // in 0 - 360 deg range
|
|
|
|
// float compass = (yaw/M_PI)*180.0+360.0f;
|
|
|
|
// float compass = (yaw/M_PI)*180.0+360.0f;
|
|
|
|
// if (compass > -10000 && compass < 10000)
|
|
|
|
// if (compass > -10000 && compass < 10000)
|
|
|
|
// {
|
|
|
|
// {
|
|
|
|
// while (compass > 360.0f) {
|
|
|
|
// while (compass > 360.0f) {
|
|
|
|
// compass -= 360.0f;
|
|
|
|
// compass -= 360.0f;
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
// else
|
|
|
|
// else
|
|
|
|
// {
|
|
|
|
// {
|
|
|
|
// // Set to 0, since it is an invalid value
|
|
|
|
// // Set to 0, since it is an invalid value
|
|
|
|
// compass = 0.0f;
|
|
|
|
// compass = 0.0f;
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
|
|
|
|
|
|
|
|
attitudeKnown = true; |
|
|
|
attitudeKnown = true; |
|
|
|
emit attitudeChanged(this, roll, pitch, yaw, time); |
|
|
|
emit attitudeChanged(this, roll, pitch, yaw, time); |
|
|
@ -890,63 +894,63 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) |
|
|
|
} |
|
|
|
} |
|
|
|
break; |
|
|
|
break; |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
// case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT:
|
|
|
|
// case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT:
|
|
|
|
// {
|
|
|
|
// {
|
|
|
|
// mavlink_object_detection_event_t event;
|
|
|
|
// mavlink_object_detection_event_t event;
|
|
|
|
// mavlink_msg_object_detection_event_decode(&message, &event);
|
|
|
|
// mavlink_msg_object_detection_event_decode(&message, &event);
|
|
|
|
// QString str(event.name);
|
|
|
|
// QString str(event.name);
|
|
|
|
// emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance);
|
|
|
|
// emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance);
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
// break;
|
|
|
|
// break;
|
|
|
|
// WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET
|
|
|
|
// WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET
|
|
|
|
// case MAVLINK_MSG_ID_MEMORY_VECT:
|
|
|
|
// case MAVLINK_MSG_ID_MEMORY_VECT:
|
|
|
|
// {
|
|
|
|
// {
|
|
|
|
// mavlink_memory_vect_t vect;
|
|
|
|
// mavlink_memory_vect_t vect;
|
|
|
|
// mavlink_msg_memory_vect_decode(&message, &vect);
|
|
|
|
// mavlink_msg_memory_vect_decode(&message, &vect);
|
|
|
|
// QString str("mem_%1");
|
|
|
|
// QString str("mem_%1");
|
|
|
|
// quint64 time = getUnixTime(0);
|
|
|
|
// quint64 time = getUnixTime(0);
|
|
|
|
// int16_t *mem0 = (int16_t *)&vect.value[0];
|
|
|
|
// int16_t *mem0 = (int16_t *)&vect.value[0];
|
|
|
|
// uint16_t *mem1 = (uint16_t *)&vect.value[0];
|
|
|
|
// uint16_t *mem1 = (uint16_t *)&vect.value[0];
|
|
|
|
// int32_t *mem2 = (int32_t *)&vect.value[0];
|
|
|
|
// int32_t *mem2 = (int32_t *)&vect.value[0];
|
|
|
|
// // uint32_t *mem3 = (uint32_t *)&vect.value[0]; causes overload problem
|
|
|
|
// // uint32_t *mem3 = (uint32_t *)&vect.value[0]; causes overload problem
|
|
|
|
// float *mem4 = (float *)&vect.value[0];
|
|
|
|
// float *mem4 = (float *)&vect.value[0];
|
|
|
|
// if ( vect.ver == 0) vect.type = 0, vect.ver = 1; else ;
|
|
|
|
// if ( vect.ver == 0) vect.type = 0, vect.ver = 1; else ;
|
|
|
|
// if ( vect.ver == 1)
|
|
|
|
// if ( vect.ver == 1)
|
|
|
|
// {
|
|
|
|
// {
|
|
|
|
// switch (vect.type) {
|
|
|
|
// switch (vect.type) {
|
|
|
|
// default:
|
|
|
|
// default:
|
|
|
|
// case 0:
|
|
|
|
// case 0:
|
|
|
|
// for (int i = 0; i < 16; i++)
|
|
|
|
// for (int i = 0; i < 16; i++)
|
|
|
|
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
|
|
|
|
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
|
|
|
|
// break;
|
|
|
|
// break;
|
|
|
|
// case 1:
|
|
|
|
// case 1:
|
|
|
|
// for (int i = 0; i < 16; i++)
|
|
|
|
// for (int i = 0; i < 16; i++)
|
|
|
|
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
|
|
|
|
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
|
|
|
|
// break;
|
|
|
|
// break;
|
|
|
|
// case 2:
|
|
|
|
// case 2:
|
|
|
|
// for (int i = 0; i < 16; i++)
|
|
|
|
// 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);
|
|
|
|
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
|
|
|
|
// break;
|
|
|
|
// break;
|
|
|
|
// case 3:
|
|
|
|
// case 3:
|
|
|
|
// for (int i = 0; i < 16; i++)
|
|
|
|
// 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);
|
|
|
|
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
|
|
|
|
// break;
|
|
|
|
// break;
|
|
|
|
// case 4:
|
|
|
|
// case 4:
|
|
|
|
// for (int i = 0; i < 8; i++)
|
|
|
|
// for (int i = 0; i < 8; i++)
|
|
|
|
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
|
|
|
|
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
|
|
|
|
// break;
|
|
|
|
// break;
|
|
|
|
// case 5:
|
|
|
|
// case 5:
|
|
|
|
// for (int i = 0; i < 8; i++)
|
|
|
|
// for (int i = 0; i < 8; i++)
|
|
|
|
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
|
|
|
|
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
|
|
|
|
// break;
|
|
|
|
// break;
|
|
|
|
// case 6:
|
|
|
|
// case 6:
|
|
|
|
// for (int i = 0; i < 8; i++)
|
|
|
|
// for (int i = 0; i < 8; i++)
|
|
|
|
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
|
|
|
|
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
|
|
|
|
// break;
|
|
|
|
// break;
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
// break;
|
|
|
|
// break;
|
|
|
|
#ifdef MAVLINK_ENABLED_UALBERTA |
|
|
|
#ifdef MAVLINK_ENABLED_UALBERTA |
|
|
|
case MAVLINK_MSG_ID_NAV_FILTER_BIAS: |
|
|
|
case MAVLINK_MSG_ID_NAV_FILTER_BIAS: |
|
|
|
{ |
|
|
|
{ |
|
|
@ -1127,10 +1131,6 @@ void UAS::setHomePosition(double lat, double lon, double alt) |
|
|
|
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); |
|
|
|
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
|
|
|
|
// Send message twice to increase chance that it reaches its goal
|
|
|
|
sendMessage(msg); |
|
|
|
sendMessage(msg); |
|
|
|
// Wait 15 ms
|
|
|
|
|
|
|
|
QGC::SLEEP::usleep(15000); |
|
|
|
|
|
|
|
// Send again
|
|
|
|
|
|
|
|
sendMessage(msg); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// Send new home position to UAS
|
|
|
|
// Send new home position to UAS
|
|
|
|
mavlink_set_gps_global_origin_t home; |
|
|
|
mavlink_set_gps_global_origin_t home; |
|
|
@ -1164,10 +1164,6 @@ void UAS::setLocalOriginAtCurrentGPSPosition() |
|
|
|
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); |
|
|
|
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
|
|
|
|
// Send message twice to increase chance that it reaches its goal
|
|
|
|
sendMessage(msg); |
|
|
|
sendMessage(msg); |
|
|
|
// Wait 15 ms
|
|
|
|
|
|
|
|
QGC::SLEEP::usleep(15000); |
|
|
|
|
|
|
|
// Send again
|
|
|
|
|
|
|
|
sendMessage(msg); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -1614,7 +1610,7 @@ quint64 UAS::getUptime() const |
|
|
|
} |
|
|
|
} |
|
|
|
else |
|
|
|
else |
|
|
|
{ |
|
|
|
{ |
|
|
|
return MG::TIME::getGroundTimeNow() - startTime; |
|
|
|
return QGC::groundTimeMilliseconds() - startTime; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -1626,7 +1622,7 @@ int UAS::getCommunicationStatus() const |
|
|
|
void UAS::requestParameters() |
|
|
|
void UAS::requestParameters() |
|
|
|
{ |
|
|
|
{ |
|
|
|
mavlink_message_t msg; |
|
|
|
mavlink_message_t msg; |
|
|
|
mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25); |
|
|
|
mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL); |
|
|
|
sendMessage(msg); |
|
|
|
sendMessage(msg); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -2088,7 +2084,7 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double |
|
|
|
sendMessage(message); |
|
|
|
sendMessage(message); |
|
|
|
qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust; |
|
|
|
qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust; |
|
|
|
|
|
|
|
|
|
|
|
emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow()); |
|
|
|
emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds()); |
|
|
|
} |
|
|
|
} |
|
|
|
else |
|
|
|
else |
|
|
|
{ |
|
|
|
{ |
|
|
@ -2168,30 +2164,30 @@ bool UAS::emergencyKILL() |
|
|
|
{ |
|
|
|
{ |
|
|
|
halt(); |
|
|
|
halt(); |
|
|
|
// FIXME MAVLINKV10PORTINGNEEDED
|
|
|
|
// FIXME MAVLINKV10PORTINGNEEDED
|
|
|
|
// bool result = false;
|
|
|
|
// bool result = false;
|
|
|
|
// QMessageBox msgBox;
|
|
|
|
// QMessageBox msgBox;
|
|
|
|
// msgBox.setIcon(QMessageBox::Critical);
|
|
|
|
// msgBox.setIcon(QMessageBox::Critical);
|
|
|
|
// msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS");
|
|
|
|
// msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS");
|
|
|
|
// msgBox.setInformativeText("Do you want to cut power on all systems?");
|
|
|
|
// msgBox.setInformativeText("Do you want to cut power on all systems?");
|
|
|
|
// msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
|
|
|
|
// msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
|
|
|
|
// msgBox.setDefaultButton(QMessageBox::Cancel);
|
|
|
|
// msgBox.setDefaultButton(QMessageBox::Cancel);
|
|
|
|
// int ret = msgBox.exec();
|
|
|
|
// int ret = msgBox.exec();
|
|
|
|
|
|
|
|
|
|
|
|
// // Close the message box shortly after the click to prevent accidental clicks
|
|
|
|
// // Close the message box shortly after the click to prevent accidental clicks
|
|
|
|
// QTimer::singleShot(5000, &msgBox, SLOT(reject()));
|
|
|
|
// QTimer::singleShot(5000, &msgBox, SLOT(reject()));
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// if (ret == QMessageBox::Yes)
|
|
|
|
// if (ret == QMessageBox::Yes)
|
|
|
|
// {
|
|
|
|
// {
|
|
|
|
// mavlink_message_t msg;
|
|
|
|
// mavlink_message_t msg;
|
|
|
|
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
|
|
|
|
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
|
|
|
|
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
|
|
|
|
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
|
|
|
|
// // Send message twice to increase chance of reception
|
|
|
|
// // Send message twice to increase chance of reception
|
|
|
|
// sendMessage(msg);
|
|
|
|
// sendMessage(msg);
|
|
|
|
// sendMessage(msg);
|
|
|
|
// sendMessage(msg);
|
|
|
|
// result = true;
|
|
|
|
// result = true;
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
// return result;
|
|
|
|
// return result;
|
|
|
|
return false; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -2322,19 +2318,19 @@ QString UAS::getShortModeTextFor(int id) |
|
|
|
} |
|
|
|
} |
|
|
|
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED) |
|
|
|
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED) |
|
|
|
{ |
|
|
|
{ |
|
|
|
mode += "GUIDED"; |
|
|
|
mode += "|GUID"; |
|
|
|
} |
|
|
|
} |
|
|
|
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE) |
|
|
|
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE) |
|
|
|
{ |
|
|
|
{ |
|
|
|
mode += "STABILIZED"; |
|
|
|
mode += "|STAB"; |
|
|
|
} |
|
|
|
} |
|
|
|
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST) |
|
|
|
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST) |
|
|
|
{ |
|
|
|
{ |
|
|
|
mode += "TEST"; |
|
|
|
mode += "|TEST"; |
|
|
|
} |
|
|
|
} |
|
|
|
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL) |
|
|
|
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL) |
|
|
|
{ |
|
|
|
{ |
|
|
|
mode += "MANUAL"; |
|
|
|
mode += "|MAN"; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
if (modeid == 0) |
|
|
|
if (modeid == 0) |
|
|
@ -2345,11 +2341,11 @@ QString UAS::getShortModeTextFor(int id) |
|
|
|
// ARMED STATE DECODING
|
|
|
|
// ARMED STATE DECODING
|
|
|
|
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) |
|
|
|
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) |
|
|
|
{ |
|
|
|
{ |
|
|
|
mode.prepend("A|"); |
|
|
|
mode.prepend("A/"); |
|
|
|
} |
|
|
|
} |
|
|
|
else |
|
|
|
else |
|
|
|
{ |
|
|
|
{ |
|
|
|
mode.prepend("D|"); |
|
|
|
mode.prepend("D/"); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// HARDWARE IN THE LOOP DECODING
|
|
|
|
// HARDWARE IN THE LOOP DECODING
|
|
|
@ -2480,7 +2476,7 @@ QString UAS::getBatterySpecs() |
|
|
|
|
|
|
|
|
|
|
|
int UAS::calculateTimeRemaining() |
|
|
|
int UAS::calculateTimeRemaining() |
|
|
|
{ |
|
|
|
{ |
|
|
|
quint64 dt = MG::TIME::getGroundTimeNow() - startTime; |
|
|
|
quint64 dt = QGC::groundTimeMilliseconds() - startTime; |
|
|
|
double seconds = dt / 1000.0f; |
|
|
|
double seconds = dt / 1000.0f; |
|
|
|
double voltDifference = startVoltage - currentVoltage; |
|
|
|
double voltDifference = startVoltage - currentVoltage; |
|
|
|
if (voltDifference <= 0) voltDifference = 0.00000000001f; |
|
|
|
if (voltDifference <= 0) voltDifference = 0.00000000001f; |
|
|
|