Newer
Older
else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
{
mode += "guided";
}
else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
{
mode += "stabilized";
}
3009
3010
3011
3012
3013
3014
3015
3016
3017
3018
3019
3020
3021
3022
3023
3024
3025
3026
3027
3028
3029
3030
3031
3032
3033
3034
3035
3036
3037
3038
else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
{
mode += "manual";
}
else
{
// Nothing else applies, we're in preflight
mode += "preflight";
}
if (modeid != 0)
{
mode += " mode";
}
// ARMED STATE DECODING
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
{
mode.append(" and armed");
}
// HARDWARE IN THE LOOP DECODING
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
{
mode.append(" using hardware in the loop simulation");
}
return mode;
}
/**
* The mode returned can be auto, stabilized, test, manual, preflight or unknown.
* @return the short text of the mode for the id given.
*/
* The mode returned can be auto, stabilized, test, manual, preflight or unknown.
* @return the short text of the mode for the id given.
*/
QString UAS::getShortModeTextFor(uint8_t base_mode, uint32_t custom_mode) const
QString mode = AutoPilotPluginManager::instance()->getShortModeText(base_mode, custom_mode, autopilot);
{
mode = "|UNKNOWN";
qDebug() << __FILE__ << __LINE__ << " Unknown mode: base_mode=" << base_mode << " custom_mode=" << custom_mode << " autopilot=" << autopilot;
}
// ARMED STATE DECODING
if (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
{
mode.prepend("A");
}
else
{
mode.prepend("D");
}
// HARDWARE IN THE LOOP DECODING
if (base_mode & MAV_MODE_FLAG_DECODE_POSITION_HIL)
{
mode.prepend("HIL:");
}
//qDebug() << "base_mode=" << base_mode << " custom_mode=" << custom_mode << " autopilot=" << autopilot << ": " << mode;
return mode;
}
const QString& UAS::getShortMode() const
{
return shortModeText;
}
/**
* Add the link and connect a signal to it which will be set off when it is destroyed.
*/
void UAS::addLink(LinkInterface* link)
{
if (!_containsLink(link))
_links.append(LinkManager::instance()->sharedPointerForLink(link));
qCDebug(UASLog) << "addLink:" << QString("%1").arg((ulong)link, 0, 16);
connect(LinkManager::instance(), &LinkManager::linkDisconnected, this, &UAS::_linkDisconnected);
void UAS::_linkDisconnected(LinkInterface* link)
qCDebug(UASLog) << "_linkDisconnected:" << link->getName();
qCDebug(UASLog) << "link count:" << _links.count();
for (int i=0; i<_links.count(); i++) {
if (_links[i].data() == link) {
_links.removeAt(i);
break;
}
}
if (_links.count() == 0) {
// Remove the UAS when all links to it close
UASManager::instance()->removeUAS(this);
}
}
/**
* @return the list of links
*/
QList<LinkInterface*> UAS::getLinks()
QList<LinkInterface*> list;
foreach (SharedLinkInterface sharedLink, _links) {
list << sharedLink.data();
}
return list;
}
/**
* @rerturn the map of the components
*/
QMap<int, QString> UAS::getComponents()
{
return components;
}
/**
* Set the battery specificaitons: empty voltage, warning voltage, and full voltage.
* @param specifications of the battery
*/
void UAS::setBatterySpecs(const QString& specs)
{
batteryRemainingEstimateEnabled = false;
bool ok;
QString percent = specs;
percent = percent.remove("%");
float temp = percent.toFloat(&ok);
if (ok)
}
else
{
emit textMessageReceived(0, 0, MAV_SEVERITY_WARNING, "Could not set battery options, format is wrong");
}
}
/**
* @return the battery specifications(empty voltage, warning voltage, full voltage)
*/
QString UAS::getBatterySpecs()
{
return QString("%1%").arg(warnLevelPercent);
}
/**
* @return the time remaining.
*/
int UAS::calculateTimeRemaining()
{
}
/**
* @return charge level in percent - 0 - 100
*/
float UAS::getChargeLevel()
{
return chargeLevel;
}
void UAS::startLowBattAlarm()
{
if (!lowBattAlarm)
{
GAudioOutput::instance()->alert(tr("System %1 has low battery").arg(getUASID()));
lowBattAlarm = true;
}
}
void UAS::stopLowBattAlarm()
{
if (lowBattAlarm)
{
lowBattAlarm = false;
}
}
void UAS::sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax)
{
mavlink_message_t message;
char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};
// Copy string into buffer, ensuring not to exceed the buffer size
for (unsigned int i = 0; i < sizeof(param_id_cstr); i++)
{
if ((int)i < param_id.length())
{
param_id_cstr[i] = param_id.toLatin1()[i];
}
}
mavlink_msg_param_map_rc_pack(mavlink->getSystemId(),
mavlink->getComponentId(),
&message,
this->uasId,
0,
param_id_cstr,
value0,
scale,
valueMin,
valueMax);
sendMessage(message);
qDebug() << "Mavlink message sent";
}
void UAS::unsetRCToParameterMap()
{
char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};
for (int i = 0; i < 3; i++) {
mavlink_message_t message;
mavlink_msg_param_map_rc_pack(mavlink->getSystemId(),
mavlink->getComponentId(),
&message,
this->uasId,
0,
param_id_cstr,
0.0f);
sendMessage(message);
}
}