Newer
Older
Bryant Mairs
committed
// Send the MANUAL_COMMAND message
mavlink_message_t message;
mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, newPitchCommand, newRollCommand, newThrustCommand, newYawCommand, buttons);
Bryant Mairs
committed
sendMessage(message);
// Emit an update in control values to other UI elements, like the HSI display
emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
}
}
}
void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw)
{
// If system has manual inputs enabled and is armed
if(((base_mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (base_mode & MAV_MODE_FLAG_HIL_ENABLED))
{
mavlink_message_t message;
mavlink_msg_setpoint_6dof_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, (float)x, (float)y, (float)z, (float)roll, (float)pitch, (float)yaw);
sendMessage(message);
qDebug() << __FILE__ << __LINE__ << ": SENT 6DOF CONTROL MESSAGE: x" << x << " y: " << y << " z: " << z << " roll: " << roll << " pitch: " << pitch << " yaw: " << yaw;
//emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
}
else
{
qDebug() << "3DMOUSE/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send 3DMouse commands first";
}
3029
3030
3031
3032
3033
3034
3035
3036
3037
3038
3039
3040
3041
3042
3043
3044
3045
3046
3047
3048
3049
3050
3051
3052
3053
3054
3055
3056
3057
3058
}
/**
* @return the type of the system
*/
int UAS::getSystemType()
{
return this->type;
}
/**
* Halt the uas.
*/
void UAS::halt()
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_HOLD, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0);
sendMessage(msg);
}
/**
* Make the UAS move.
*/
void UAS::go()
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0);
sendMessage(msg);
}
/**
* Order the robot to return home
*/
void UAS::home()
{
mavlink_message_t msg;
double latitude = UASManager::instance()->getHomeLatitude();
double longitude = UASManager::instance()->getHomeLongitude();
double altitude = UASManager::instance()->getHomeAltitude();
int frame = UASManager::instance()->getHomeFrame();
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, frame, 0, latitude, longitude, altitude);
sendMessage(msg);
}
/**
* Order the robot to land on the runway
*/
void UAS::land()
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_LAND, 1, 0, 0, 0, 0, 0, 0, 0);
sendMessage(msg);
}
*/
void UAS::pairRX(int rxType, int rxSubType)
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_START_RX_PAIR, 0, rxType, rxSubType, 0, 0, 0, 0, 0);
sendMessage(msg);
}
3097
3098
3099
3100
3101
3102
3103
3104
3105
3106
3107
3108
3109
3110
3111
3112
3113
3114
3115
3116
3117
3118
3119
3120
3121
3122
3123
3124
3125
3126
3127
3128
3129
3130
3131
3132
3133
3134
3135
3136
3137
3138
3139
3140
3141
3142
3143
3144
3145
3146
3147
/**
* The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
* and might differ between systems.
*/
void UAS::emergencySTOP()
{
// FIXME MAVLINKV10PORTINGNEEDED
halt();
}
/**
* Shut down this mav - All onboard systems are immediately shut down (e.g. the
* main power line is cut).
* @warning This might lead to a crash.
*
* The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
*/
bool UAS::emergencyKILL()
{
halt();
// FIXME MAVLINKV10PORTINGNEEDED
// bool result = false;
// QMessageBox msgBox;
// msgBox.setIcon(QMessageBox::Critical);
// msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS");
// msgBox.setInformativeText("Do you want to cut power on all systems?");
// 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;
// // 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);
// // Send message twice to increase chance of reception
// sendMessage(msg);
// sendMessage(msg);
// result = true;
// }
// return result;
return false;
}
/**
* If enabled, connect the flight gear link.
*/
void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObject * configuration)
{
QGCFlightGearLink* link = dynamic_cast<QGCFlightGearLink*>(simulation);
if (!link || !simulation) {
// Delete wrong sim
if (simulation) {
stopHil();
delete simulation;
}
simulation = new QGCFlightGearLink(this, options);
}
// Connect Flight Gear Link
link = dynamic_cast<QGCFlightGearLink*>(simulation);
link->setStartupArguments(options);
QObject::connect(configuration, SIGNAL(barometerOffsetChanged(float)), link, SLOT(setBarometerOffset(float)));
Lorenz Meier
committed
3164
3165
3166
3167
3168
3169
3170
3171
3172
3173
3174
3175
3176
3177
3178
3179
3180
3181
3182
3183
3184
3185
3186
3187
3188
3189
3190
if (enable)
{
startHil();
}
else
{
stopHil();
}
}
/**
* If enabled, connect the JSBSim link.
*/
void UAS::enableHilJSBSim(bool enable, QString options)
{
QGCJSBSimLink* link = dynamic_cast<QGCJSBSimLink*>(simulation);
if (!link || !simulation) {
// Delete wrong sim
if (simulation) {
stopHil();
delete simulation;
}
simulation = new QGCJSBSimLink(this, options);
}
// Connect Flight Gear Link
link = dynamic_cast<QGCJSBSimLink*>(simulation);
link->setStartupArguments(options);
3191
3192
3193
3194
3195
3196
3197
3198
3199
3200
3201
3202
3203
3204
3205
3206
3207
3208
3209
3210
3211
3212
3213
3214
3215
3216
3217
3218
3219
3220
3221
3222
3223
3224
3225
if (enable)
{
startHil();
}
else
{
stopHil();
}
}
/**
* If enabled, connect the X-plane gear link.
*/
void UAS::enableHilXPlane(bool enable)
{
QGCXPlaneLink* link = dynamic_cast<QGCXPlaneLink*>(simulation);
if (!link || !simulation) {
if (simulation) {
stopHil();
delete simulation;
}
qDebug() << "CREATED NEW XPLANE LINK";
simulation = new QGCXPlaneLink(this);
}
// Connect X-Plane Link
if (enable)
{
startHil();
}
else
{
stopHil();
}
}
3226
3227
3228
3229
3230
3231
3232
3233
3234
3235
3236
3237
3238
3239
3240
3241
3242
3243
3244
3245
3246
3247
/**
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
*/
void UAS::sendHilGroundTruth(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
float pitchspeed, float yawspeed, double lat, double lon, double alt,
float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc)
{
Don Gagne
committed
Q_UNUSED(time_us);
Q_UNUSED(xacc);
Q_UNUSED(yacc);
Q_UNUSED(zacc);
3253
3254
3255
3256
3257
3258
3259
3260
3261
3262
3263
3264
3265
3266
3267
3268
3269
3270
3271
3272
3273
// Emit attitude for cross-check
emit valueChanged(uasId, "roll sim", "rad", roll, getUnixTime());
emit valueChanged(uasId, "pitch sim", "rad", pitch, getUnixTime());
emit valueChanged(uasId, "yaw sim", "rad", yaw, getUnixTime());
emit valueChanged(uasId, "roll rate sim", "rad/s", rollspeed, getUnixTime());
emit valueChanged(uasId, "pitch rate sim", "rad/s", pitchspeed, getUnixTime());
emit valueChanged(uasId, "yaw rate sim", "rad/s", yawspeed, getUnixTime());
emit valueChanged(uasId, "lat sim", "deg", lat*1e7, getUnixTime());
emit valueChanged(uasId, "lon sim", "deg", lon*1e7, getUnixTime());
emit valueChanged(uasId, "alt sim", "deg", alt*1e3, getUnixTime());
emit valueChanged(uasId, "vx sim", "m/s", vx*1e2, getUnixTime());
emit valueChanged(uasId, "vy sim", "m/s", vy*1e2, getUnixTime());
emit valueChanged(uasId, "vz sim", "m/s", vz*1e2, getUnixTime());
emit valueChanged(uasId, "IAS sim", "m/s", ind_airspeed, getUnixTime());
emit valueChanged(uasId, "TAS sim", "m/s", true_airspeed, getUnixTime());
}
/**
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
*/
void UAS::sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
float pitchspeed, float yawspeed, double lat, double lon, double alt,
float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc)
if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
float q[4];
double cosPhi_2 = cos(double(roll) / 2.0);
double sinPhi_2 = sin(double(roll) / 2.0);
double cosTheta_2 = cos(double(pitch) / 2.0);
double sinTheta_2 = sin(double(pitch) / 2.0);
double cosPsi_2 = cos(double(yaw) / 2.0);
double sinPsi_2 = sin(double(yaw) / 2.0);
q[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
sinPhi_2 * sinTheta_2 * sinPsi_2);
q[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
cosPhi_2 * sinTheta_2 * sinPsi_2);
q[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 +
sinPhi_2 * cosTheta_2 * sinPsi_2);
q[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 -
sinPhi_2 * sinTheta_2 * cosPsi_2);
mavlink_message_t msg;
Lorenz Meier
committed
mavlink_msg_hil_state_quaternion_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
time_us, q, rollspeed, pitchspeed, yawspeed,
lat*1e7f, lon*1e7f, alt*1000, vx*100, vy*100, vz*100, ind_airspeed*100, true_airspeed*100, xacc*1000/9.81, yacc*1000/9.81, zacc*1000/9.81);
sendMessage(msg);
}
else
{
// Attempt to set HIL mode
Thomas Gubler
committed
setMode(base_mode | MAV_MODE_FLAG_HIL_ENABLED, custom_mode);
qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
}
}
Thomas Gubler
committed
/*
* @param abs_pressure Absolute Pressure (hPa)
* @param diff_pressure Differential Pressure (hPa)
*/
void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, quint32 fields_changed)
if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
mavlink_msg_hil_sensor_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
time_us, xacc, yacc, zacc, rollspeed, pitchspeed, yawspeed,
xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature,
fields_changed);
sendMessage(msg);
lastSendTimeSensors = QGC::groundTimeMilliseconds();
}
else
{
// Attempt to set HIL mode
Thomas Gubler
committed
setMode(base_mode | MAV_MODE_FLAG_HIL_ENABLED, custom_mode);
qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
}
}
void UAS::sendHilGps(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float vn, float ve, float vd, float cog, int satellites)
// Only send at 10 Hz max rate
if (QGC::groundTimeMilliseconds() - lastSendTimeGPS < 100)
return;
if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
float course = cog;
// map to 0..2pi
if (course < 0)
// scale from radians to degrees
course = (course / M_PI) * 180.0f;
mavlink_msg_hil_gps_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
time_us, fix_type, lat*1e7, lon*1e7, alt*1e3, eph*1e2, epv*1e2, vel*1e2, vn*1e2, ve*1e2, vd*1e2, course*1e2, satellites);
lastSendTimeGPS = QGC::groundTimeMilliseconds();
sendMessage(msg);
}
else
{
// Attempt to set HIL mode
Thomas Gubler
committed
setMode(base_mode | MAV_MODE_FLAG_HIL_ENABLED, custom_mode);
qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
}
}
/**
* Connect flight gear link.
**/
void UAS::startHil()
{
if (hilEnabled) return;
hilEnabled = true;
Thomas Gubler
committed
setMode(base_mode | MAV_MODE_FLAG_HIL_ENABLED, custom_mode);
Lorenz Meier
committed
qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
// Connect HIL simulation link
simulation->connectSimulation();
}
/**
* disable flight gear link.
*/
void UAS::stopHil()
{
Lorenz Meier
committed
if (simulation && simulation->isConnected()) {
simulation->disconnectSimulation();
setMode(base_mode & ~MAV_MODE_FLAG_HIL_ENABLED, custom_mode);
qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to disable.";
}
hilEnabled = false;
3410
3411
3412
3413
3414
3415
3416
3417
3418
3419
3420
3421
3422
3423
3424
3425
3426
3427
3428
3429
3430
3431
3432
3433
3434
3435
3436
3437
3438
3439
3440
3441
3442
3443
3444
3445
3446
3447
3448
3449
3450
3451
3452
3453
3454
3455
3456
3457
3458
3459
3460
3461
3462
3463
3464
3465
3466
3467
3468
3469
3470
3471
3472
}
void UAS::shutdown()
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Shutting down the UAS");
msgBox.setInformativeText("Do you want to shut down the onboard computer?");
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)
{
// If the active UAS is set, execute command
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 0, 2, 0, 0, 0, 0, 0);
sendMessage(msg);
}
}
/**
* @param x position
* @param y position
* @param z position
* @param yaw
*/
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_PATHPLANNING, 1, 1, 1, 0, yaw, x, y, z);
sendMessage(msg);
}
/**
* @return The name of this system as string in human-readable form
*/
QString UAS::getUASName(void) const
{
QString result;
if (name == "")
{
result = tr("MAV ") + result.sprintf("%03d", getUASID());
}
else
{
result = name;
}
return result;
}
/**
* @return the state of the uas as a short text.
*/
const QString& UAS::getShortState() const
{
return shortStateText;
}
/**
* The mode can be autonomous, guided, manual or armed. It will also return if
* hardware in the loop is being used.
* @return the audio mode text for the id given.
*/
QString UAS::getAudioModeTextFor(int id)
{
QString mode;
uint8_t modeid = id;
// BASE MODE DECODING
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
{
mode += "autonomous";
}
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";
}
3496
3497
3498
3499
3500
3501
3502
3503
3504
3505
3506
3507
3508
3509
3510
3511
3512
3513
3514
3515
3516
3517
3518
3519
3520
3521
3522
3523
3524
3525
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, int autopilot)
if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
// use custom_mode - autopilot-specific
if (autopilot == MAV_AUTOPILOT_PX4) {
union px4_custom_mode px4_mode;
px4_mode.data = custom_mode;
if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) {
} else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL) {
mode += "|ALTCTL";
} else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL) {
mode += "|POSCTL";
} else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_READY) {
mode += "|READY";
} else if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF) {
mode += "|TAKEOFF";
} else if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_LOITER) {
mode += "|LOITER";
} else if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_MISSION) {
mode += "|MISSION";
} else if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_RTL) {
mode += "|RTL";
} else if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_LAND) {
mode += "|LAND";
}
// fallback to using base_mode
if (mode.length() == 0) {
// use base_mode - not autopilot-specific
if (base_mode == 0) {
mode += "|PREFLIGHT";
} else if (base_mode & MAV_MODE_FLAG_DECODE_POSITION_AUTO) {
mode += "|AUTO";
} else if (base_mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) {
if (base_mode & MAV_MODE_FLAG_DECODE_POSITION_GUIDED) {
mode += "|GUIDED";
} else if (base_mode & MAV_MODE_FLAG_DECODE_POSITION_STABILIZE) {
mode += "|STABILIZED";
}
{
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;
3609
3610
3611
3612
3613
3614
3615
3616
3617
3618
3619
3620
3621
3622
3623
3624
3625
3626
3627
3628
3629
3630
3631
3632
3633
3634
3635
3636
3637
3638
3639
3640
3641
3642
3643
3644
3645
3646
3647
3648
3649
3650
3651
3652
3653
3654
3655
3656
3657
3658
3659
3660
3661
3662
3663
3664
3665
3666
3667
3668
3669
3670
3671
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 (!links->contains(link))
{
links->append(link);
connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
}
}
void UAS::removeLink(QObject* object)
{
LinkInterface* link = dynamic_cast<LinkInterface*>(object);
if (link)
{
links->removeAt(links->indexOf(link));
}
}
/**
* @return the list of links
*/
QList<LinkInterface*>* UAS::getLinks()
{
return links;
}
/**
* @rerturn the map of the components
*/
QMap<int, QString> UAS::getComponents()
{
return components;
}
/**
* Set the battery type and the number of cells.
* @param type of the battery
* @param cells Number of cells.
*/
void UAS::setBattery(BatteryType type, int cells)
{
this->batteryType = type;
this->cells = cells;
switch (batteryType)
{
case NICD:
break;
case NIMH:
break;
case LIION:
break;
case LIPOLY:
fullVoltage = this->cells * lipoFull;
emptyVoltage = this->cells * lipoEmpty;
3674
3675
3676
3677
3678
3679
3680
3681
3682
3683
3684
3685
3686
3687
3688
3689
3690
3691
3692
3693
3694
3695
3696
3697
3698
3699
3700
break;
case LIFE:
break;
case AGZN:
break;
}
}
/**
* Set the battery specificaitons: empty voltage, warning voltage, and full voltage.
* @param specifications of the battery
*/
void UAS::setBatterySpecs(const QString& specs)
{
if (specs.length() == 0 || specs.contains("%"))
{
batteryRemainingEstimateEnabled = false;
bool ok;
QString percent = specs;
percent = percent.remove("%");
float temp = percent.toFloat(&ok);
if (ok)
{
warnLevelPercent = temp;
}
else
{
emit textMessageReceived(0, 0, MAV_SEVERITY_WARNING, "Could not set battery options, format is wrong");
3702
3703
3704
3705
3706
3707
3708
3709
3710
3711
3712
3713
3714
3715
3716
3717
3718
3719
3720
3721
3722
3723
3724
3725
3726
}
}
else
{
batteryRemainingEstimateEnabled = true;
QString stringList = specs;
stringList = stringList.remove("V");
stringList = stringList.remove("v");
QStringList parts = stringList.split(",");
if (parts.length() == 3)
{
float temp;
bool ok;
// Get the empty voltage
temp = parts.at(0).toFloat(&ok);
if (ok) emptyVoltage = temp;
// Get the warning voltage
temp = parts.at(1).toFloat(&ok);
if (ok) warnVoltage = temp;
// Get the full voltage
temp = parts.at(2).toFloat(&ok);
if (ok) fullVoltage = temp;
}
else
{
emit textMessageReceived(0, 0, MAV_SEVERITY_WARNING, "Could not set battery options, format is wrong");
3728
3729
3730
3731
3732
3733
3734
3735
3736
3737
3738
3739
3740
3741
3742
3743
3744
3745
3746
3747
3748
3749
3750
3751
3752
3753
3754
3755
3756
3757
3758
3759
3760
3761
3762
3763
3764
3765
3766
3767
3768
3769
3770
3771
3772
3773
3774
3775
3776
3777
3778
3779
3780
3781
3782
3783
3784
3785
3786
3787
3788
3789
3790
3791
3792
3793
3794
3795
3796
3797
3798
3799
3800
3801
3802
3803
}
}
}
/**
* @return the battery specifications(empty voltage, warning voltage, full voltage)
*/
QString UAS::getBatterySpecs()
{
if (batteryRemainingEstimateEnabled)
{
return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
}
else
{
return QString("%1%").arg(warnLevelPercent);
}
}
/**
* @return the time remaining.
*/
int UAS::calculateTimeRemaining()
{
quint64 dt = QGC::groundTimeMilliseconds() - startTime;
double seconds = dt / 1000.0f;
double voltDifference = startVoltage - currentVoltage;
if (voltDifference <= 0) voltDifference = 0.00000000001f;
double dischargePerSecond = voltDifference / seconds;
int remaining = static_cast<int>((currentVoltage - emptyVoltage) / dischargePerSecond);
// Can never be below 0
if (remaining < 0) remaining = 0;
return remaining;
}
/**
* @return charge level in percent - 0 - 100
*/
float UAS::getChargeLevel()
{
if (batteryRemainingEstimateEnabled)
{
if (lpVoltage < emptyVoltage)
{
chargeLevel = 0.0f;
}
else if (lpVoltage > fullVoltage)
{
chargeLevel = 100.0f;
}
else
{
chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
}
}
return chargeLevel;
}
void UAS::startLowBattAlarm()
{
if (!lowBattAlarm)
{
GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
QTimer::singleShot(3000, GAudioOutput::instance(), SLOT(startEmergency()));
lowBattAlarm = true;
}
}
void UAS::stopLowBattAlarm()
{
if (lowBattAlarm)
{
GAudioOutput::instance()->stopEmergency();
lowBattAlarm = false;
}
}