-
Notifications
You must be signed in to change notification settings - Fork 6
/
UAS.cpp
341 lines (302 loc) · 11 KB
/
UAS.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
#include "UAS.h"
#include "Vehicle.h"
#include "linkmanager.h"
#include "PX4AutopioltPlugins/PX4AutopilotPlugin.h"
#include <QDebug>
UAS::UAS(Vehicle *vehicle)
: _uasId(vehicle->id())
, _parameterLoader(NULL)
, _vehicle(vehicle)
{
}
UAS::~UAS()
{
}
void UAS::startCalibration(CalibrationType calType)
{
qDebug()<<"UAS:startCalibration"<<calType;
if(!_vehicle) {
return;
}
int gyroCal = 0;
int magCal = 0;
int magDetailCal = 0;
int accelDetailCal = 0;
int accelCal = 0;
int gyroTmpCal = 0;
int accelTmpCal = 0;
switch(calType) {
case CalibrationGyro:
gyroCal = 1;
break;
case CalibrationMag:
magCal = 1;
break;
case CalibrationMagDetail:
magDetailCal = 1;
break;
case CalibrationAccelDetail:
accelDetailCal = 1;
break;
case CalibrationAccel:
accelCal = 1;
break;
case CalibrationGyroTmp:
gyroTmpCal = 1;
break;
case CalibrationAccelTmp:
accelTmpCal = 1;
break;
}
mavlink_message_t msg;
mavlink_command_long_t command;
command.target_system = _uasId;
command.target_component = 0;
command.command = MAV_CMD_PREFLIGHT_CALIBRATION;
command.confirmation = 0; // 0 = first transmission of command
command.param1 = gyroCal; //gyro cal
command.param2 = magCal; //mag cal
command.param3 = magDetailCal; //mag detail cal
command.param4 = accelDetailCal; //accel detail cal
command.param5 = accelCal; //accel cal
command.param6 = gyroTmpCal; //gyro temp cal
command.param7 = accelTmpCal; //accel temp cal
mavlink_msg_command_long_encode(_uasId,defaultComponentId,&msg,&command);
_vehicle->linkManager()->sendMessage(msg);
}
void UAS::stopCalibration(void)
{
if(!_vehicle) {
return;
}
mavlink_message_t msg;
mavlink_command_long_t command;
command.target_system = _uasId;
command.target_component = 0;
command.command = MAV_CMD_PREFLIGHT_CALIBRATION;
command.confirmation = 0; // 0 = first transmission of command
command.param1 = 0; //gyro cal
command.param2 = 0; //mag cal
command.param3 = 0; //ground pressure
command.param4 = 0; //radio cal
command.param5 = 0; //accel cal
command.param6 = 0; //airspeed cal (compass/motor interference cal)
command.param7 = 0; //empty?
mavlink_msg_command_long_encode(_uasId,defaultComponentId,&msg,&command);
_vehicle->linkManager()->sendMessage(msg);
}
void UAS::receiveMessage(SerialLink*link, mavlink_message_t &message)
{
Q_UNUSED(link)
//qDebug()<<"uas:receiveMessage"<<message.sysid<<message.compid;
if(message.sysid == _uasId) {
switch(message.msgid) {
case MAVLINK_MSG_ID_PARAM_VALUE:
{
//qDebug()<<"Param_Value message received";
mavlink_param_value_t param_value;
mavlink_msg_param_value_decode(&message,¶m_value);
//QByteArray(const char *data, int size = -1)
QByteArray bytes(param_value.param_id,MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
QString paramName(bytes);
mavlink_param_union_t paramUnion;
paramUnion.param_float = param_value.param_value;
paramUnion.type = param_value.param_type;
_processParamValueMsg(message,paramName,param_value,paramUnion);
}
break;
case MAVLINK_MSG_ID_STATUSTEXT:
{
//qDebug()<<"STATUSTEXT received";
mavlink_statustext_t statustext;
mavlink_msg_statustext_decode(&message,&statustext);
//Status text message, without null termination character
QByteArray b(statustext.text);
b.append('\0');
QString text = b;
//QGC source code
/*
QByteArray b;
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
mavlink_msg_statustext_get_text(&message, b.data());
// Ensure NUL-termination
b[b.length()-1] = '\0';
QString text = QString(b);
int severity = mavlink_msg_statustext_get_severity(&message);
*/
// If the message is NOTIFY or higher severity, or starts with a '#',
// then read it aloud.
emit textMessageReceived(message.compid,text);
}
break;
}
}
}
void UAS::_processParamValueMsg(mavlink_message_t &message,const QString ¶mName,const mavlink_param_value_t &rawValue,mavlink_param_union_t ¶mUnion)
{
int componentId = message.compid;
QVariant paramValue;
paramValue = paramUnion.param_float;
/* switch(rawValue.param_type)
{
case MAV_PARAM_TYPE_UINT8:
paramValue = QVariant(paramUnion.param_uint8);
break;
case MAV_PARAM_TYPE_INT8:
paramValue = QVariant(paramUnion.param_int8);
break;
case MAV_PARAM_TYPE_UINT16:
paramValue = QVariant(paramUnion.param_uint16);
break;
case MAV_PARAM_TYPE_INT16:
paramValue = QVariant(paramUnion.param_int16);
break;
case MAV_PARAM_TYPE_UINT32:
paramValue = QVariant(paramUnion.param_uint32);
break;
case MAV_PARAM_TYPE_INT32:
paramValue = QVariant(paramUnion.param_int32);
break;
case MAV_PARAM_TYPE_REAL32:
paramValue = QVariant(paramUnion.param_float);
break;
default:
qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
}
*/
//qDebug() << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
emit parameterUpdate(componentId, paramName,rawValue.param_count,rawValue.param_index,rawValue.param_type,paramValue);
}
void UAS::shutdownVehicle(void)
{
_vehicle = NULL;
}
void UAS::readParameterRaw(int componentId, const QString& paramName, int paramIndex)
{
Q_UNUSED(paramIndex)
mavlink_message_t msg;
mavlink_param_request_read_t param;
Q_UNUSED(msg)
Q_UNUSED(param)
char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];
strncpy(fixedParamName,paramName.toStdString().c_str(),sizeof(fixedParamName));
//255,0 our system and component id
// _vehicle->id(), componentId , target system and component id
mavlink_msg_param_request_read_pack(255,0,&msg,_vehicle->id(),componentId,fixedParamName,paramIndex);
_vehicle->linkManager()->sendMessage(msg);
}
void UAS::writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
{
mavlink_param_set_t paramSet;
mavlink_param_union_t unionValue;
FactMetaData::ValueType_t factType = _vehicle->autopilotPlugin()->getParamFact(componentId,paramName)->type();
paramSet.param_type = _factTypeToMavType(factType);
switch(factType) {
case FactMetaData::typeUint8:
unionValue.param_uint8 = (uint8_t)value.toUInt();
break;
case FactMetaData::typeInt8:
unionValue.param_int8 = (int8_t)value.toInt();
break;
case FactMetaData::typeUint16:
unionValue.param_uint16 = (uint16_t)value.toUInt();
break;
case FactMetaData::typeInt16:
unionValue.param_int16 = (int16_t)value.toInt();
break;
case FactMetaData::typeUint32:
unionValue.param_uint32 = (uint32_t)value.toUInt();
break;
case FactMetaData::typeFloat:
unionValue.param_float = value.toFloat();
break;
default:
qDebug()<<"Unsupported fact type: "<<factType;
case FactMetaData::typeInt32:
unionValue.param_int32 = (int32_t)value.toInt();
break;
}
paramSet.param_value = unionValue.param_float;
paramSet.target_system = (uint8_t)_vehicle->id();
paramSet.target_component = (uint8_t)componentId;
strncpy(paramSet.param_id,paramName.toStdString().c_str(),sizeof(paramSet.param_id));
mavlink_message_t message;
// id of this system and component
mavlink_msg_param_set_encode(255,0,&message,¶mSet);
_vehicle->linkManager()->sendMessage(message);
}
MAV_PARAM_TYPE UAS::_factTypeToMavType(FactMetaData::ValueType_t valueType)
{
switch(valueType) {
case FactMetaData::typeUint8:
return MAV_PARAM_TYPE_UINT8;
case FactMetaData::typeUint16:
return MAV_PARAM_TYPE_UINT16;
case FactMetaData::typeUint32:
return MAV_PARAM_TYPE_UINT32;
case FactMetaData::typeInt8:
return MAV_PARAM_TYPE_INT8;
case FactMetaData::typeInt16:
return MAV_PARAM_TYPE_INT16;
case FactMetaData::typeInt32:
return MAV_PARAM_TYPE_INT32;
case FactMetaData::typeFloat:
return MAV_PARAM_TYPE_REAL32;
default:
qDebug()<<"Unsupported fact type: "<<valueType;
return MAV_PARAM_TYPE_INT32;
}
}
void UAS::writePIDParams(QString moduleName,QMap<QString,float>paramValue)
{
mavlink_message_t msg;
if(moduleName == "PITCH") {
mavlink_attitude_pitch_pid_t pitch_pid;
pitch_pid.MC_PITCH_P = paramValue.value("P");
pitch_pid.MC_PITCHRATE_P = paramValue.value("RateP");
pitch_pid.MC_PITCHRATE_I = paramValue.value("RateI");
pitch_pid.MC_PITCHRATE_D = paramValue.value("RateD");
mavlink_msg_attitude_pitch_pid_encode(255,0,&msg,&pitch_pid);
}
else if (moduleName == "ROLL") {
mavlink_attitude_roll_pid_t roll_pid;
roll_pid.MC_ROLL_P = paramValue.value("P");
roll_pid.MC_ROLLRATE_P = paramValue.value("RateP");
roll_pid.MC_ROLLRATE_I = paramValue.value("RateI");
roll_pid.MC_ROLLRATE_D = paramValue.value("RateD");
mavlink_msg_attitude_roll_pid_encode(255,0,&msg,&roll_pid);
}
else if (moduleName == "YAW") {
mavlink_attitude_yaw_pid_t yaw_pid;
yaw_pid.MC_YAW_P = paramValue.value("P");
yaw_pid.MC_YAWRATE_P = paramValue.value("RateP");
yaw_pid.MC_YAWRATE_I = paramValue.value("RateI");
yaw_pid.MC_YAWRATE_D = paramValue.value("RateD");
mavlink_msg_attitude_yaw_pid_encode(255,0,&msg,&yaw_pid);
}
else if (moduleName == "X") {
mavlink_position_x_pid_t x_pid;
x_pid.MPC_X_P= paramValue.value("P");
x_pid.MPC_XRATE_P = paramValue.value("RateP");
x_pid.MPC_XRATE_I = paramValue.value("RateI");
x_pid.MPC_XRATE_D = paramValue.value("RateD");
mavlink_msg_position_x_pid_encode(255,0,&msg,&x_pid);
}
else if (moduleName == "Y") {
mavlink_position_y_pid_t y_pid;
y_pid.MPC_Y_P= paramValue.value("P");
y_pid.MPC_YRATE_P = paramValue.value("RateP");
y_pid.MPC_YRATE_I = paramValue.value("RateI");
y_pid.MPC_YRATE_D = paramValue.value("RateD");
mavlink_msg_position_y_pid_encode(255,0,&msg,&y_pid);
}
else if (moduleName == "Z") {
mavlink_position_z_pid_t z_pid;
z_pid.MPC_Z_P= paramValue.value("P");
z_pid.MPC_ZRATE_P = paramValue.value("RateP");
z_pid.MPC_ZRATE_I = paramValue.value("RateI");
z_pid.MPC_ZRATE_D = paramValue.value("RateD");
mavlink_msg_position_z_pid_encode(255,0,&msg,&z_pid);
}
_vehicle->linkManager()->sendMessage(msg);
}