Newer
Older
2001
2002
2003
2004
2005
2006
2007
2008
2009
2010
2011
2012
2013
2014
2015
2016
2017
2018
2019
2020
2021
2022
2023
2024
2025
2026
2027
2028
2029
2030
2031
2032
2033
2034
2035
2036
2037
2038
2039
2040
2041
2042
2043
2044
2045
2046
2047
2048
2049
2050
2051
2052
2053
2054
2055
2056
2057
2058
2059
2060
2061
2062
2063
2064
2065
2066
2067
2068
2069
2070
2071
2072
2073
2074
2075
2076
2077
2078
2079
2080
2081
2082
2083
2084
2085
2086
2087
2088
2089
2090
2091
2092
2093
2094
2095
2096
2097
2098
2099
2100
2101
2102
2103
2104
2105
2106
2107
2108
2109
2110
2111
2112
2113
2114
2115
2116
2117
2118
2119
2120
2121
2122
2123
2124
2125
2126
2127
2128
2129
2130
2131
2132
2133
2134
2135
2136
2137
2138
2139
2140
2141
2142
2143
2144
2145
2146
2147
2148
2149
2150
2151
2152
2153
2154
2155
2156
2157
2158
2159
2160
2161
2162
2163
2164
2165
2166
2167
2168
2169
2170
2171
2172
2173
2174
2175
2176
2177
2178
2179
2180
2181
2182
2183
2184
2185
2186
2187
2188
2189
2190
2191
2192
2193
2194
2195
2196
2197
2198
2199
2200
2201
2202
2203
2204
2205
2206
2207
2208
2209
2210
2211
2212
2213
2214
2215
2216
2217
2218
2219
2220
2221
2222
2223
2224
2225
2226
2227
2228
2229
2230
2231
2232
2233
2234
2235
2236
2237
2238
2239
2240
2241
2242
2243
2244
2245
2246
2247
2248
2249
2250
2251
2252
2253
2254
2255
2256
2257
2258
2259
2260
2261
2262
2263
2264
2265
2266
2267
2268
2269
2270
2271
2272
2273
2274
2275
2276
2277
2278
2279
2280
2281
2282
2283
2284
2285
2286
2287
mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL);
sendMessage(msg);
qDebug() << __FILE__ << __LINE__ << "LOADING PARAM LIST";
}
void UAS::writeParametersToStorage()
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
sendMessage(msg);
}
void UAS::readParametersFromStorage()
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
sendMessage(msg);
}
/**
* @param rate The update rate in Hz the message should be sent
*/
void UAS::enableAllDataTransmission(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
// 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 ?
stream.req_message_rate = 0;
// Start / stop the message
stream.start_stop = (rate) ? 1 : 0;
// 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)
{
// 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_RAW_SENSORS;
// Select the update rate in Hz the message should be send
stream.req_message_rate = rate;
// Start / stop the message
stream.start_stop = (rate) ? 1 : 0;
// 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
stream.req_message_rate = rate;
// Start / stop the message
stream.start_stop = (rate) ? 1 : 0;
// 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::enableRCChannelDataTransmission(int rate)
{
#if defined(MAVLINK_ENABLED_UALBERTA_MESSAGES)
mavlink_message_t msg;
mavlink_msg_request_rc_channels_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, enabled);
sendMessage(msg);
#else
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_RC_CHANNELS;
// Select the update rate in Hz the message should be send
stream.req_message_rate = rate;
// Start / stop the message
stream.start_stop = (rate) ? 1 : 0;
// 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);
#endif
}
/**
* @param rate The update rate in Hz the message should be sent
*/
void UAS::enableRawControllerDataTransmission(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_RAW_CONTROLLER;
// Select the update rate in Hz the message should be send
stream.req_message_rate = rate;
// Start / stop the message
stream.start_stop = (rate) ? 1 : 0;
// 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);
}
//void UAS::enableRawSensorFusionTransmission(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_RAW_SENSOR_FUSION;
// // Select the update rate in Hz the message should be send
// stream.req_message_rate = rate;
// // Start / stop the message
// stream.start_stop = (rate) ? 1 : 0;
// // 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);
// sendMessage(msg);
//}
/**
* @param rate The update rate in Hz the message should be sent
*/
void UAS::enablePositionTransmission(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_POSITION;
// Select the update rate in Hz the message should be send
stream.req_message_rate = rate;
// Start / stop the message
stream.start_stop = (rate) ? 1 : 0;
// 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::enableExtra1Transmission(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_EXTRA1;
// Select the update rate in Hz the message should be send
stream.req_message_rate = rate;
// Start / stop the message
stream.start_stop = (rate) ? 1 : 0;
// 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);
sendMessage(msg);
}
/**
* @param rate The update rate in Hz the message should be sent
*/
void UAS::enableExtra2Transmission(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_EXTRA2;
// Select the update rate in Hz the message should be send
stream.req_message_rate = rate;
// Start / stop the message
stream.start_stop = (rate) ? 1 : 0;
// 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);
sendMessage(msg);
}
/**
* @param rate The update rate in Hz the message should be sent
*/
void UAS::enableExtra3Transmission(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_EXTRA3;
// Select the update rate in Hz the message should be send
stream.req_message_rate = rate;
// Start / stop the message
stream.start_stop = (rate) ? 1 : 0;
// 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);
sendMessage(msg);
}
/**
* Set a parameter value onboard
*
* @param component The component to set the parameter
* @param id Name of the parameter
*/
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
{
if (!id.isNull())
{
mavlink_message_t msg;
mavlink_param_set_t p;
mavlink_param_union_t union_value;
// Assign correct value based on QVariant
switch (value.type())
{
case QVariant::Char:
union_value.param_int8 = value.toChar().toAscii();
p.param_type = MAV_PARAM_TYPE_INT8;
break;
2292
2293
2294
2295
2296
2297
2298
2299
2300
2301
2302
2303
2304
2305
2306
2307
2308
2309
2310
2311
2312
2313
2314
2315
2316
2317
2318
2319
2320
2321
2322
2323
2324
2325
2326
2327
2328
2329
2330
2331
2332
2333
2334
2335
2336
2337
2338
2339
2340
2341
2342
2343
2344
2345
2346
2347
2348
2349
2350
2351
2352
2353
2354
2355
2356
2357
2358
2359
2360
2361
2362
2363
2364
2365
2366
2367
2368
2369
2370
2371
2372
2373
2374
2375
2376
2377
2378
2379
2380
2381
2382
2383
2384
2385
2386
2387
2388
2389
2390
2391
2392
2393
2394
2395
2396
2397
2398
2399
2400
2401
2402
2403
2404
2405
2406
2407
2408
2409
2410
2411
2412
2413
2414
2415
2416
2417
2418
2419
2420
2421
2422
2423
2424
2425
2426
2427
2428
2429
2430
2431
2432
2433
2434
2435
2436
2437
2438
2439
2440
2441
2442
2443
2444
2445
2446
2447
2448
2449
2450
2451
2452
2453
2454
2455
2456
2457
2458
2459
2460
2461
2462
2463
2464
2465
2466
2467
2468
2469
2470
2471
2472
2473
2474
2475
2476
2477
2478
2479
2480
2481
2482
2483
2484
2485
2486
2487
case QVariant::Int:
union_value.param_int32 = value.toInt();
p.param_type = MAV_PARAM_TYPE_INT32;
break;
case QVariant::UInt:
union_value.param_uint32 = value.toUInt();
p.param_type = MAV_PARAM_TYPE_UINT32;
break;
case QMetaType::Float:
union_value.param_float = value.toFloat();
p.param_type = MAV_PARAM_TYPE_REAL32;
break;
default:
qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
return;
}
p.param_value = union_value.param_float;
p.target_system = (uint8_t)uasId;
p.target_component = (uint8_t)component;
//qDebug() << "SENT PARAM:" << value;
// Copy string into buffer, ensuring not to exceed the buffer size
for (unsigned int i = 0; i < sizeof(p.param_id); i++)
{
// String characters
if ((int)i < id.length())
{
p.param_id[i] = id.toAscii()[i];
}
else
{
// Fill rest with zeros
p.param_id[i] = 0;
}
}
mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
sendMessage(msg);
}
}
/**
* Request parameter, use parameter name to request it.
*/
void UAS::requestParameter(int component, int id)
{
// Request parameter, use parameter name to request it
mavlink_message_t msg;
mavlink_param_request_read_t read;
read.param_index = id;
read.param_id[0] = '\0'; // Enforce null termination
read.target_system = uasId;
read.target_component = component;
mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
sendMessage(msg);
//qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << id;
}
/**
* Request a parameter, use parameter name to request it.
*/
void UAS::requestParameter(int component, const QString& parameter)
{
// Request parameter, use parameter name to request it
mavlink_message_t msg;
mavlink_param_request_read_t read;
read.param_index = -1;
// Copy full param name or maximum max field size
if (parameter.length() > MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)
{
emit textMessageReceived(uasId, 0, 255, QString("QGC WARNING: Parameter name %1 is more than %2 bytes long. This might lead to errors and mishaps!").arg(parameter).arg(MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN-1));
}
memcpy(read.param_id, parameter.toStdString().c_str(), qMax(parameter.length(), MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN));
read.param_id[15] = '\0'; // Enforce null termination
read.target_system = uasId;
read.target_component = component;
mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
sendMessage(msg);
qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
}
/**
* @param systemType Type of MAV.
*/
void UAS::setSystemType(int systemType)
{
if((systemType >= MAV_TYPE_GENERIC) && (systemType < MAV_TYPE_ENUM_END))
{
type = systemType;
// If the airframe is still generic, change it to a close default type
if (airframe == 0)
{
switch (systemType)
{
case MAV_TYPE_FIXED_WING:
airframe = QGC_AIRFRAME_EASYSTAR;
break;
case MAV_TYPE_QUADROTOR:
airframe = QGC_AIRFRAME_MIKROKOPTER;
break;
}
}
emit systemSpecsChanged(uasId);
}
}
void UAS::setUASName(const QString& name)
{
if (name != "")
{
this->name = name;
writeSettings();
emit nameChanged(name);
emit systemSpecsChanged(uasId);
}
}
void UAS::executeCommand(MAV_CMD command)
{
mavlink_message_t msg;
mavlink_command_long_t cmd;
cmd.command = (uint16_t)command;
cmd.confirmation = 0;
cmd.param1 = 0.0f;
cmd.param2 = 0.0f;
cmd.param3 = 0.0f;
cmd.param4 = 0.0f;
cmd.param5 = 0.0f;
cmd.param6 = 0.0f;
cmd.param7 = 0.0f;
cmd.target_system = uasId;
cmd.target_component = 0;
mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
sendMessage(msg);
}
void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component)
{
mavlink_message_t msg;
mavlink_command_long_t cmd;
cmd.command = (uint16_t)command;
cmd.confirmation = confirmation;
cmd.param1 = param1;
cmd.param2 = param2;
cmd.param3 = param3;
cmd.param4 = param4;
cmd.param5 = param5;
cmd.param6 = param6;
cmd.param7 = param7;
cmd.target_system = uasId;
cmd.target_component = component;
mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
sendMessage(msg);
}
/**
* Launches the system
*
*/
void UAS::launch()
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_NAV_TAKEOFF, 1, 0, 0, 0, 0, 0, 0, 0);
sendMessage(msg);
}
/**
* @warning Depending on the UAS, this might make the rotors of a helicopter spinning
*
*/
void UAS::armSystem()
{
mavlink_message_t msg;
mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_SAFETY_ARMED, navMode);
sendMessage(msg);
}
/**
* @warning Depending on the UAS, this might completely stop all motors.
*
*/
void UAS::disarmSystem()
{
mavlink_message_t msg;
mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & ~MAV_MODE_FLAG_SAFETY_ARMED, navMode);
sendMessage(msg);
}
/**
* Set the manual control commands.
* This can only be done if the system has manual inputs enabled and is armed.
*/
void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons)
{
Bryant
committed
Q_UNUSED(xHat);
Q_UNUSED(yHat);
2491
2492
2493
2494
2495
2496
2497
2498
2499
2500
2501
2502
2503
2504
2505
2506
2507
2508
2509
2510
2511
2512
// Scale values
double rollPitchScaling = 1.0f * 1000.0f;
double yawScaling = 1.0f * 1000.0f;
double thrustScaling = 1.0f * 1000.0f;
manualRollAngle = roll * rollPitchScaling;
manualPitchAngle = pitch * rollPitchScaling;
manualYawAngle = yaw * yawScaling;
manualThrust = thrust * thrustScaling;
// If system has manual inputs enabled and is armed
if(((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (mode & MAV_MODE_FLAG_HIL_ENABLED))
{
mavlink_message_t message;
mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, (float)manualPitchAngle, (float)manualRollAngle, (float)manualThrust, (float)manualYawAngle, buttons);
sendMessage(message);
//qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;
emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
}
else
{
//qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
}
}
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(((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (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";
}
2533
2534
2535
2536
2537
2538
2539
2540
2541
2542
2543
2544
2545
2546
2547
2548
2549
2550
2551
2552
2553
2554
2555
2556
2557
2558
2559
2560
2561
2562
2563
2564
2565
2566
2567
2568
2569
2570
2571
2572
2573
2574
2575
2576
2577
2578
2579
2580
2581
2582
2583
2584
2585
2586
2587
2588
2589
2590
2591
2592
2593
2594
2595
2596
2597
2598
2599
2600
2601
2602
2603
2604
2605
2606
2607
2608
2609
2610
2611
2612
2613
2614
2615
2616
2617
2618
2619
2620
2621
2622
2623
2624
2625
2626
2627
2628
2629
2630
2631
2632
2633
2634
2635
2636
2637
2638
2639
2640
2641
2642
2643
2644
2645
2646
2647
2648
2649
2650
2651
2652
2653
2654
2655
2656
2657
2658
2659
2660
2661
2662
2663
2664
2665
2666
2667
2668
2669
2670
2671
2672
2673
2674
2675
}
/**
* @return the type of the system
*/
int UAS::getSystemType()
{
return this->type;
}
/**
* @param buttonIndex
*/
void UAS::receiveButton(int buttonIndex)
{
switch (buttonIndex)
{
case 0:
break;
case 1:
break;
default:
break;
}
// qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
}
/**
* 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);
}
/**
* 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)
{
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);
Lorenz Meier
committed
2676
2677
2678
2679
2680
2681
2682
2683
2684
2685
2686
2687
2688
2689
2690
2691
2692
2693
2694
2695
2696
2697
2698
2699
2700
2701
2702
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);
2703
2704
2705
2706
2707
2708
2709
2710
2711
2712
2713
2714
2715
2716
2717
2718
2719
2720
2721
2722
2723
2724
2725
2726
2727
2728
2729
2730
2731
2732
2733
2734
2735
2736
2737
2738
2739
2740
2741
2742
2743
2744
2745
2746
2747
2748
2749
2750
2751
2752
2753
2754
2755
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();
}
}
/**
* @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 xacc, float yacc, float zacc)
{
if (this->mode & MAV_MODE_FLAG_HIL_ENABLED)
{
if (QGC::groundTimeMilliseconds() - lastSendTimeSensors < 100) {
// Emit attitude for cross-check
emit attitudeChanged(this, 201, roll, pitch, yaw, getUnixTime());
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, "vx sim", "rad", vx*100, getUnixTime());
emit valueChanged(uasId, "vy sim", "rad", vy*100, getUnixTime());
emit valueChanged(uasId, "vz sim", "rad", vz*100, getUnixTime());
} else {
mavlink_message_t msg;
mavlink_msg_hil_state_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
time_us, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed,
lat*1e7f, lon*1e7f, alt*1000, vx*100, vy*100, vz*100, xacc*1000/9.81, yacc*1000/9.81, zacc*1000/9.81);
}
else
{
// Attempt to set HIL mode
mavlink_message_t msg;
mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
sendMessage(msg);
qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
}
}
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, quint16 fields_changed)
{
if (this->mode & MAV_MODE_FLAG_HIL_ENABLED)
{
mavlink_message_t msg;
mavlink_msg_highres_imu_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
mavlink_message_t msg;
mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
sendMessage(msg);
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 cog, int satellites)
{
// Only send at 10 Hz max rate
if (QGC::groundTimeMilliseconds() - lastSendTimeGPS < 100)
return;
if (this->mode & MAV_MODE_FLAG_HIL_ENABLED)
{
float course = cog;
// map to 0..2pi
if (course < 0)
course += 2.0f * M_PI;
// scale from radians to degrees
course = (course / M_PI) * 180.0f;
mavlink_message_t msg;
mavlink_msg_gps_raw_int_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
time_us, fix_type, lat*1e7, lon*1e7, alt*1e3, eph*1e2, epv*1e2, vel*1e2, course*1e2, satellites);
lastSendTimeGPS = QGC::groundTimeMilliseconds();
sendMessage(msg);
}
else
{
// Attempt to set HIL mode
mavlink_message_t msg;
mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
sendMessage(msg);
qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
}
}
/**
* Connect flight gear link.
**/
void UAS::startHil()
{
if (hilEnabled) return;
hilEnabled = true;
mavlink_message_t msg;
mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
sendMessage(msg);
// Connect HIL simulation link
simulation->connectSimulation();
}
/**
* disable flight gear link.
*/
void UAS::stopHil()
{
if (simulation) simulation->disconnectSimulation();
mavlink_message_t msg;
mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
sendMessage(msg);
hilEnabled = false;
2876
2877
2878
2879
2880
2881
2882
2883
2884
2885
2886
2887
2888
2889
2890
2891
2892
2893
2894
2895
2896
2897
2898
2899
2900
2901
2902
2903
2904
2905
2906
2907
2908
2909
2910
2911
2912
2913
2914
2915
2916
2917
2918
2919
2920
2921
2922
2923
2924
2925
2926
2927
2928
2929
2930
2931
2932
2933
2934
2935
2936
2937
2938
2939
2940
2941
2942
2943
2944
2945
2946
2947
2948
2949
2950
2951
2952
2953
2954
2955
2956
2957
}
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";
}
2962
2963
2964
2965
2966
2967
2968
2969
2970
2971
2972
2973
2974
2975
2976
2977
2978
2979
2980
2981
2982
2983
2984
2985
2986
2987
2988
2989
2990
2991
2992
2993
2994
2995
2996
2997
2998
2999
3000
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.
*/
QString UAS::getShortModeTextFor(int id)
{
QString mode;
uint8_t modeid = id;