RflySimSDK v3.05
RflySimSDK说明文档
载入中...
搜索中...
未找到
rfly_mavlink.h
1#pragma once
2
4#include <math.h>
5#include <stdio.h>
6#include <string.h>
7#include <vector>
8#include <algorithm> // std::transform
9#include <cctype>
10#include "rfly_data.h"
11#include "rfly_udp.h"
12
13#define MAX_BUF_LEN 300 // More than max mavlink msg len
14
15
16enum PX4_FLIGHTMODE{
17 PX4_FLIGHTMODE_MANUAL = 1,
18 PX4_FLIGHTMODE_ALT,
19 PX4_FLIGHTMODE_POS,
20 PX4_FLIGHTMODE_TAKEOFF,
21 PX4_FLIGHTMODE_LAND,
22 PX4_FLIGHTMODE_MISSION,
23 PX4_FLIGHTMODE_RTL,
24 PX4_FLIGHTMODE_STABILIZED,
25 PX4_FLIGHTMODE_OFFBOARD,
26 PX4_FLIGHTMODE_AUTO_READY,
27 PX4_FLIGHTMODE_AUTO_LOITER
28};
29
30enum PX4_CUSTOM_MAIN_MODE {
31 PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
32 PX4_CUSTOM_MAIN_MODE_ALTCTL,
33 PX4_CUSTOM_MAIN_MODE_POSCTL,
34 PX4_CUSTOM_MAIN_MODE_AUTO,
35 PX4_CUSTOM_MAIN_MODE_ACRO,
36 PX4_CUSTOM_MAIN_MODE_OFFBOARD,
37 PX4_CUSTOM_MAIN_MODE_STABILIZED,
38 PX4_CUSTOM_MAIN_MODE_RATTITUDE_LEGACY,
39 PX4_CUSTOM_MAIN_MODE_SIMPLE /* unused, but reserved for future use */
40};
41
42enum PX4_CUSTOM_SUB_MODE_AUTO {
43 PX4_CUSTOM_SUB_MODE_AUTO_READY = 1,
44 PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF,
45 PX4_CUSTOM_SUB_MODE_AUTO_LOITER,
46 PX4_CUSTOM_SUB_MODE_AUTO_MISSION,
47 PX4_CUSTOM_SUB_MODE_AUTO_RTL,
48 PX4_CUSTOM_SUB_MODE_AUTO_LAND,
49 PX4_CUSTOM_SUB_MODE_AUTO_RESERVED_DO_NOT_USE, // was PX4_CUSTOM_SUB_MODE_AUTO_RTGS, deleted 2020-03-05
50 PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET,
51 PX4_CUSTOM_SUB_MODE_AUTO_PRECLAND
52};
53
54enum PX4_CUSTOM_SUB_MODE_POSCTL {
55 PX4_CUSTOM_SUB_MODE_POSCTL_POSCTL = 0,
56 PX4_CUSTOM_SUB_MODE_POSCTL_ORBIT
57};
58
60 struct {
61 uint16_t reserved;
62 uint8_t main_mode;
63 uint8_t sub_mode;
64 };
65 uint32_t data;
66 float data_float;
67 struct {
68 uint16_t reserved_hl;
69 uint16_t custom_mode_hl;
70 };
71};
72
73
74
76 bool isHeartRec=false;
77 bool isLocalNed=false;
78 bool isGlobPos=false;
79 bool isGpsHome=false;
80 int selfCheckState=0; //-1:faild, 0 inited, 1:uav connected, 2. get local pos, 3. can offboard, 4. can armed, 5. checkPassed
81
82 uint8_t sysID=255;
83 uint8_t compID=1;
84 uint8_t TargetSysID;
85 uint8_t TargetCompID;
86
87 uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags*/
88 uint8_t base_mode; /*< System mode bitmap.*/
89 uint8_t system_status; /*< System status flag.*/
90 uint32_t time_boot_ms;
91 //float initYaw;
92 //float yawOffset;
93 double batteryInfo[6];
94 double healthInfo[10];
95
96 bool isFailSafeEn=false;
97 bool isArmed=false;
98 bool isStanby=false;
99 bool isActive=false;
100 mavlink_sys_status_t sysStatus;
101 uint8_t landed_state=0;
102
103 bool isLowBatt=false;
104 bool isHighLoad=false;
105 bool isDropComm=false;
106 bool isOffboard=false;
107 PX4_FLIGHTMODE flyMode=PX4_FLIGHTMODE_MANUAL;
108};
109
111 public:
112
113 RflySimData data;
114 MavStateData mavState;
115 UDPServer udp;
116 //MavHealthData phm;
117 std::string TargetIP;
118 int TargetPort;
119 int CopterID;
120 int RecvPort;
121 std::string RecvIP;
122 char buf[MAX_BUF_LEN+1];
123 bool isUpdate=false;
124 bool isRcc=false;
125 double GpsOrin[3]={0};
126
127
128 int SelfCheckMainState=0;
129 int SelfCheckSubState=0;
130 double lastTime=0;
131
132
133 int offCtrlState=0;
134 double offLastTime=0;
135
136 //SOut2Simulator m_show3d;
137 uint64_t m_start_time = 0;
138
139 RflyMavlink(){
140
141 }
142 ~RflyMavlink(){
143
144 }
145
146
147 bool RecvNoblock(){
148 while(true){ // Read all data in the upd buf zone
149 int recvlen=udp.RecvNoblock(buf,RecvIP,RecvPort,MAX_BUF_LEN);
150 if(recvlen>0){
151 mavlink_message_t message;
152 mavlink_status_t status;
153 uint8_t msgReceived = false;
154 for(int i = 0 ; i < recvlen ; ++i){
155 msgReceived = mavlink_parse_char(MAVLINK_COMM_1, (uint8_t)buf[i], &message, &status);
156 if(msgReceived){
157 onMavLinkMessage(message);
158 isUpdate=true;
159 }
160 }
161 }else{
162 break;
163 }
164 }
165 return isUpdate;
166 }
167
168
169 void onMavLinkMessage(mavlink_message_t message){
170
171 switch (message.msgid){
172 case MAVLINK_MSG_ID_HEARTBEAT:{
173 mavlink_heartbeat_t MavHartt;
174 mavlink_msg_heartbeat_decode(&message, &MavHartt);
175 // ignore QGC msg
176 if (MavHartt.custom_mode == 0)
177 break;
178 if (!mavState.isHeartRec){
179 mavState.isHeartRec = true;
180 mavState.TargetSysID = message.sysid;
181 mavState.TargetCompID = message.compid;
182 std::cout<<"Drone #"<<CopterID<<": "<<"Heartbeat for SysID "<<std::to_string(message.sysid)<<" and CompID "<<std::to_string(message.compid)<<std::endl;
183 //isLocalNed
184 }
185 mavState.base_mode = MavHartt.base_mode;
186 mavState.custom_mode = MavHartt.custom_mode;
187 mavState.system_status = MavHartt.system_status;
188
189 if(mavState.system_status==3){
190 mavState.isStanby=true;
191 }else{
192 mavState.isStanby=false;
193 }
194
195 if(mavState.system_status==4){
196 mavState.isActive=true;
197 }else{
198 mavState.isActive=false;
199 }
200
201 if ((mavState.base_mode & static_cast<uint8_t>(MAV_MODE_FLAG::MAV_MODE_FLAG_SAFETY_ARMED)) > 0) {
202 if(!mavState.isArmed){
203 mavState.isArmed = true;
204 std::cout<<"Drone #"<<CopterID<<": "<<"PX4 Armed "<<std::endl;
205 }
206 }else{
207 if(mavState.isArmed){
208 mavState.isArmed = false;
209 std::cout<<"Drone #"<<CopterID<<": "<<"PX4 Disamed. "<<std::endl;
210 }
211 }
212
213 PX4_FLIGHTMODE fm;
214 getFlightMode_px4(MavHartt.custom_mode,fm);
215 if(fm!=mavState.flyMode){
216 std::string qstr=getFlightModeName_px4(fm);
217 std::cout<<"Drone #"<<CopterID<<": "<<qstr<<std::endl;
218 mavState.flyMode=fm;
219 }
220 if(fm==PX4_FLIGHTMODE_OFFBOARD){
221 mavState.isOffboard=true;
222 }
223 else{
224 mavState.isOffboard=false;
225 }
226
227 break;
228 }
229 // MAVLINK_MSG_ID_SYS_STATUS may not have
230 case MAVLINK_MSG_ID_SYS_STATUS:{
231 mavlink_msg_sys_status_decode(&message, &mavState.sysStatus);
232 mavState.batteryInfo[0] = mavState.sysStatus.battery_remaining;
233 mavState.batteryInfo[1] = mavState.sysStatus.voltage_battery;
234 mavState.batteryInfo[2] = mavState.sysStatus.current_battery;
235
236 if(mavState.sysStatus.battery_remaining>=0 && mavState.sysStatus.battery_remaining<10){
237 if (!mavState.isLowBatt){
238 mavState.isLowBatt=true;
239 std::cout<<"Drone #"<<CopterID<<": "<<"Low battery."<<std::endl;
240 }
241 }
242 if(mavState.sysStatus.load>900){
243 if (!mavState.isHighLoad){
244 mavState.isHighLoad=true;
245 std::cout<<"Drone #"<<CopterID<<": "<<"High CPU load."<<std::endl;
246 }
247 }
248
249 if(mavState.sysStatus.drop_rate_comm>80){
250 if (!mavState.isDropComm){
251 mavState.isDropComm=true;
252 std::cout<<"Drone #"<<CopterID<<": "<<"Communication high drop rate."<<std::endl;
253 }
254 }
255 break;
256 }
257
258 case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:{
259 mavlink_extended_sys_state_t mss;
260 mavlink_msg_extended_sys_state_decode(&message, &mss);
261 //inCopterData[4]=mss.vtol_state;
262 //inCopterData[5]=mss.landed_state;
263 if(mavState.landed_state!=mss.landed_state){
264 mavState.landed_state=mss.landed_state;
265 switch(mss.landed_state){
266 case MAV_LANDED_STATE_ON_GROUND:
267 std::cout<<"Drone #"<<CopterID<<": "<<"On ground."<<std::endl;
268 break;
269 case MAV_LANDED_STATE_IN_AIR:
270 std::cout<<"Drone #"<<CopterID<<": "<<"In air."<<std::endl;
271 break;
272 case MAV_LANDED_STATE_TAKEOFF:
273 std::cout<<"Drone #"<<CopterID<<": "<<"Takeoff."<<std::endl;
274 break;
275 case MAV_LANDED_STATE_LANDING:
276 std::cout<<"Drone #"<<CopterID<<": "<<"Landing."<<std::endl;
277 break;
278 }
279 }
280 break;
281 }
282
283 case MAVLINK_MSG_ID_LOCAL_POSITION_NED:{
284 mavlink_local_position_ned_t lpn;
285 mavlink_msg_local_position_ned_decode(&message, &lpn);
286 data.localPos[0]=lpn.x;
287 data.localPos[1]=lpn.y;
288 data.localPos[2]=lpn.z;
289 data.localVel[0] = lpn.vx;
290 data.localVel[1] = lpn.vy;
291 data.localVel[2] = lpn.vz;
292 data.time_boot_ms = lpn.time_boot_ms;
293
294 if(!mavState.isLocalNed){
295 mavState.isLocalNed=true;
296 std::cout<<"Drone #"<<CopterID<<": Got local pos x,y,z "<<data.localPos[0]<<","<<data.localPos[1]<<","<<data.localPos[2]<<","<<std::endl;
297 }
298
299 //isUpdate=true;
300
301 if(mavState.isGpsHome){
302 if(data.calcGlobalPos(GpsOrin)){
303 if(!mavState.isGlobPos){
304 mavState.isGlobPos=true;
305 std::cout<<"Drone #"<<CopterID<<": Got global pos x,y,z "<<data.GlobalPos[0]<<","<<data.GlobalPos[1]<<","<<data.GlobalPos[2]<<","<<std::endl;
306 }
307 }
308 }
309
310 break;
311 }
312 case MAVLINK_MSG_ID_ATTITUDE:{
313 mavlink_attitude_t att;
314 mavlink_msg_attitude_decode(&message, &att);
315 //data.time_boot_ms = RunnedTime;
316 //data.copterID = copterID;
317 data.AngEular[0]=att.roll;
318 data.AngEular[1]=att.pitch;
319 data.AngEular[2]=att.yaw;
320 data.AngRate[0]=att.rollspeed;
321 data.AngRate[1]=att.pitchspeed;
322 data.AngRate[2]=att.yawspeed;
323 data.time_boot_ms = att.time_boot_ms;
324 // if (!mavState.initYaw && currentTime > 1){
325 // mavState.yawOffset = mavState.yaw - data[5];
326 // cout <<"sysID: "<<(int)(mavState.sysID) <<"\tyawOffset: "<< mavState.yawOffset << endl;
327 // mavState.initYaw = true;
328 // }
329 //isUpdate=true;
330 break;
331 }
332 case MAVLINK_MSG_ID_BATTERY_STATUS:{
333 mavlink_battery_status_t bat;
334 mavlink_msg_battery_status_decode(&message, &bat);
335 mavState.batteryInfo[0] = (double)bat.battery_remaining;
336 break;
337 }
338 case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:{
339 mavlink_global_position_int_t gp;
340 mavlink_msg_global_position_int_decode(&message, &gp);
341 //outHILStateData outHilData;
342 //data.time_boot_ms = gp.time_boot_ms;
343 //data.time_boot_ms = RunnedTime;
344 data.GpsPos[0]=gp.lat;
345 data.GpsPos[1]=gp.lon;
346 data.GpsPos[2]=gp.alt;
347 data.relative_alt = gp.relative_alt;
348 data.GpsVel[0]=gp.vx;
349 data.GpsVel[1]=gp.vy;
350 data.GpsVel[2]=gp.vz;
351 data.hdg = gp.hdg;
352 break;
353 }
354 case MAVLINK_MSG_ID_GPS_RAW_INT:{
355 //qDebug()<<"State Received!";
356 mavlink_gps_raw_int_t gri;
357 mavlink_msg_gps_raw_int_decode(&message, &gri);
358 //data.time_boot_ms = gri.time_usec;
359 data.fix_type = gri.fix_type;
360 //qDebug()<<data.fix_type;
361 data.satellites_visible = gri.satellites_visible;
362
363 break;
364 }
365 case MAVLINK_MSG_ID_ESTIMATOR_STATUS:{
366
367 //qDebug()<<"State Received!";
368 mavlink_estimator_status_t es;
369 mavlink_msg_estimator_status_decode(&message, &es);
370 //data.time_boot_ms = RunnedTime;
371 //data.time_boot_ms = es.time_usec;
372 data.pos_horiz_accuracy = es.pos_horiz_accuracy;
373 data.pos_vert_accuracy = es.pos_vert_accuracy;
374
375 //qDebug()<<"Status: "<<data.pos_horiz_accuracy<<","<<es.pos_horiz_ratio;
376 break;
377 }
378
379 case MAVLINK_MSG_ID_HOME_POSITION:{
380
381 //if(!m_flightModel.isSkipGps){
382 mavlink_home_position_t hm;
383 mavlink_msg_home_position_decode(&message, &hm);
384 data.gpsHome[0] = hm.latitude;
385 data.gpsHome[1] = hm.longitude;
386 data.gpsHome[2] = hm.altitude;
387 //data.time_boot_ms = RunnedTime;
388 mavState.isGpsHome=true;
389 break;
390 }
391 case MAVLINK_MSG_ID_STATUSTEXT:{
392 mavlink_statustext_t mavStatusText;
393 mavlink_msg_statustext_decode(&message, &mavStatusText);
394 std::string mystr(mavStatusText.text);
395 std::cout<<"Drone #"<<CopterID<<" STATUSTEXT: "<< mystr << std::endl;
396 stringToLower(mystr);
397 if (mystr.find("failsafe mode enabled") != std::string::npos) {
398 mavState.isFailSafeEn=true;
399 }
400 break;
401 }
402 case MAVLINK_MSG_ID_COMMAND_ACK:{
403 mavlink_command_ack_t mck;
404 mavlink_msg_command_ack_decode(&message, &mck);
405 std::string qstrt;
406
407 switch(mck.result){
408 case 0:
409 qstrt="ACCEPTED";
410 break;
411 case 1:
412 qstrt="TEMPORARILY_REJECTED";
413 break;
414 case 2:
415 qstrt="DENIED";
416 break;
417 case 3:
418 qstrt="UNSUPPORTED";
419 break;
420 case 4:
421 qstrt="FAILED";
422 break;
423 case 5:
424 qstrt="IN_PROGRESS";
425 break;
426 }
427
428 std::string cmdName;
429 switch(mck.command){
430 case 400:
431 cmdName = "ARM/DISARM";
432 break;
433 case 176:
434 cmdName = "SET_MODE";
435 break;
436 case 246:
437 cmdName = "REBOOT/SHUTDOWN";
438 break;
439 case 519:
440 cmdName = "REQUEST_MAVLINK_VERSION";
441 break;
442 case 520:
443 cmdName = "REQUEST_AUTOPILOT_VERSION";
444 break;
445 case 92:
446 cmdName = "NAV_GUIDED_ENABLE";
447 break;
448 case 21:
449 cmdName = "NAV_LAND";
450 break;
451 case 22:
452 cmdName = "NAV_TAKEOFF";
453 break;
454 case 192:
455 cmdName = "DO_REPOSITION";
456 break;
457 default:
458 cmdName = "ID: "+ std::to_string(mck.command);
459 break;
460 }
461
462 std::cout<<"Drone #"<<CopterID<<": "<<"Command "<<cmdName<<" "<<qstrt<<std::endl;
463 break;
464 }
465
466
467 }
468 }
469
470
471 void stringToLower(std::string& str)
472 {
473 std::transform(str.begin(), str.end(), str.begin(), [](char& c){
474 return std::tolower(c);
475 });
476 }
477
478 void SendMsg(mavlink_message_t mess){
479 unsigned int length = mavlink_msg_to_send_buffer((uint8_t*)buf, &mess);
480 if(length>0){
481 buf[length]='0';
482 udp.SendTo((const char *)buf,length,TargetIP,TargetPort);
483 }
484
485 }
486
487 void SendHeartbeat(){
488 mavlink_message_t mess;
489 mavlink_heartbeat_t MavHartt;
490 MavHartt.autopilot = MAV_AUTOPILOT_INVALID;
491 MavHartt.base_mode = 0;
492 MavHartt.custom_mode = 0;
493 MavHartt.system_status = MAV_STATE_ACTIVE;
494 MavHartt.type = MAV_TYPE_GCS;
495 mavlink_msg_heartbeat_encode(mavState.sysID, mavState.compID, &mess, &MavHartt);
496 SendMsg(mess);
497 }
498
499 void SendMavCmdLong(uint16_t command, float param1, float param2=0, float param3=0,float param4=0,float param5=0,float param6=0,float param7=0)
500 {
501 mavlink_message_t mess;
502 mavlink_command_long_t command_long;
503 command_long.target_system = mavState.TargetSysID;
504 command_long.target_component = mavState.TargetCompID;
505 command_long.confirmation = 0;
506 command_long.command = command;
507 command_long.param1 = param1;
508 command_long.param2 = param2;
509 command_long.param3 = param3;
510 command_long.param4 = param4;
511 command_long.param5 = param5;
512 command_long.param6 = param6;
513 command_long.param7 = param7;
514 mavlink_msg_command_long_encode(mavState.sysID, mavState.compID, &mess, &command_long);
515 SendMsg(mess);
516 }
517
518
519 void SendMavArm(int isArm)
520 {
521 // arm
522 if (isArm) {
523 SendMavCmdLong(MAV_CMD_COMPONENT_ARM_DISARM, 1);
524 }
525 // disarm
526 else {
527 SendMavCmdLong(MAV_CMD_COMPONENT_ARM_DISARM, 0, 21196.0f);
528 }
529 }
530
531 // Send MAVLink command to PX4 to change flight mode
532 // https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_MODE
533 void SendSetMode(int mainMode, int customMode=0)
534 {
535 uint16_t baseMode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
536 SendMavCmdLong(MAV_CMD_DO_SET_MODE, baseMode, mainMode, customMode);
537 }
538
539 void SendPositionTarget(uint16_t type_mask, uint8_t coordinate, float *data){
540 mavlink_message_t mess;
541 if (coordinate == MAV_FRAME_LOCAL_NED) {
542 mavlink_set_position_target_local_ned_t m_target_ned;
543 //m_target_ned.time_boot_ms = SGetCurrentTime();
544 m_target_ned.target_system = mavState.TargetSysID;
545 m_target_ned.target_component = mavState.TargetCompID;
546 m_target_ned.coordinate_frame = coordinate;
547 m_target_ned.type_mask = type_mask;
548 m_target_ned.x = data[0];
549 m_target_ned.y = data[1];
550 // from vision frame to ned
551 m_target_ned.z = data[2];
552 m_target_ned.vx = data[3];
553 m_target_ned.vy = data[4];
554 // from vision frame to ned
555 m_target_ned.vz = data[5];
556 m_target_ned.afx = data[6];
557 m_target_ned.afy = data[7];
558 // from vision frame to ned
559 m_target_ned.afz = data[8];
560 m_target_ned.yaw = data[11];
561 // from vision frame to ned
562 m_target_ned.yaw_rate = data[14];
563 // from vision frame to ned
564 // mavState.rotate(m_target_ned.x, m_target_ned.y);
565 // mavState.rotate(m_target_ned.vx, m_target_ned.vy);
566 // mavState.rotate(m_target_ned.afx, m_target_ned.afy);
567
568 mavlink_msg_set_position_target_local_ned_encode(mavState.sysID, mavState.compID, &mess, &m_target_ned);
569 }
570 else if (coordinate == MAV_FRAME_GLOBAL_INT){
571 mavlink_set_position_target_global_int_t m_target_global;
572 //m_target_global.time_boot_ms = SGetCurrentTime();
573 m_target_global.target_system = mavState.TargetSysID;
574 m_target_global.target_component = mavState.TargetCompID;
575 m_target_global.coordinate_frame = coordinate;
576 m_target_global.type_mask = type_mask;
577 m_target_global.lat_int = (int32_t)(data[0]*1e7);
578 m_target_global.lon_int = (int32_t)(data[1]*1e7);
579 m_target_global.alt = data[2];
580 m_target_global.vx = data[3];
581 m_target_global.vy = data[4];
582 m_target_global.vz = data[5];
583 m_target_global.afx = data[6];
584 m_target_global.afy = data[7];
585 m_target_global.afz = data[8];
586 m_target_global.yaw = data[11];
587 m_target_global.yaw_rate = data[14];
588 mavlink_msg_set_position_target_global_int_encode(mavState.sysID, mavState.compID, &mess, &m_target_global);
589 }
590 SendMsg(mess);
591 }
592
593
594 void SendAttitudeTarget(uint8_t type_mask, float *data){
595 mavlink_message_t mess;
596 mavlink_set_attitude_target_t m_target_att;
597 //m_target_att.time_boot_ms = SGetCurrentTime();
598 m_target_att.target_system = mavState.TargetSysID;
599 m_target_att.target_component = mavState.TargetCompID;
600 m_target_att.type_mask = type_mask;
601
602 float roll = data[9];
603 float pitch = data[10];
604 float yaw = data[11];
605 float sp2 = sin(pitch/2);
606 float sy2 = sin(yaw/2);
607 float cr2 = cos(roll/2);
608 float cp2 = cos(pitch/2);
609 float cy2 = cos(yaw/2);
610 float sr2 = sin(roll/2);
611
612 float qx = sp2*sy2*cr2+cp2*cy2*sr2;
613 float qy = sp2*cy2*cr2+cp2*sy2*sr2;
614 float qz = cp2*sy2*cr2-sp2*cy2*sr2;
615 float qw = cp2*cy2*cr2-sp2*sy2*sr2;
616
617 m_target_att.q[0] = qw;
618 m_target_att.q[1] = qx;
619 m_target_att.q[2] = qy;
620 m_target_att.q[3] = qz;
621 m_target_att.body_roll_rate = data[12];
622 m_target_att.body_pitch_rate = data[13];
623 m_target_att.body_yaw_rate = data[14];
624 m_target_att.thrust = data[15];
625 mavlink_msg_set_attitude_target_encode(mavState.sysID, mavState.compID, &mess, &m_target_att);
626 SendMsg(mess);
627 }
628
629 void SendParamInt(std::string id, int value){
630 mavlink_message_t mess;
631 mavlink_param_set_t param;
632
633 param.target_system = mavState.TargetSysID;
634 param.target_component = mavState.TargetCompID;
635 param.param_value = float(value)/7.13622e+44; // A Change is required.
636 param.param_type = MAV_PARAM_TYPE_INT32;
637 std::strcpy(param.param_id, id.c_str());
638
639 mavlink_msg_param_set_encode(mavState.sysID, mavState.compID, &mess, &param);
640 SendMsg(mess);
641 }
642
643 void SendParamFloat(std::string id, float value){
644 mavlink_message_t mess;
645 mavlink_param_set_t param;
646
647 param.target_system = mavState.TargetSysID;
648 param.target_component = mavState.TargetCompID;
649 param.param_value = value;
650 param.param_type = MAV_PARAM_TYPE_REAL32;
651 std::strcpy(param.param_id, id.c_str());
652
653 mavlink_msg_param_set_encode(mavState.sysID, mavState.compID, &mess, &param);
654 SendMsg(mess);
655 }
656
657 void SendRccTarget(float *data)
658 {
659 mavlink_message_t mess;
660 mavlink_rc_channels_override_t rcc;
661 uint16_t middle_rc = 1500;
662
663 rcc.target_system = mavState.TargetSysID;
664 rcc.target_component = mavState.TargetCompID;
665 rcc.chan1_raw = (uint16_t)data[13];
666 rcc.chan2_raw = (uint16_t)data[14];
667 rcc.chan3_raw = (uint16_t)data[16];
668 rcc.chan4_raw = (uint16_t)data[15];
669 //cout << rcc.chan1_raw <<"\t" << rcc.chan3_raw << endl;
670 rcc.chan5_raw = middle_rc;
671 rcc.chan6_raw = middle_rc;
672 rcc.chan7_raw = middle_rc;
673 rcc.chan8_raw = middle_rc;
674 mavlink_msg_rc_channels_override_encode(mavState.sysID, mavState.compID, &mess, &rcc);
675
676 SendMsg(mess);
677
678 mavlink_manual_control_t manual;
679 manual.target = mavState.sysID;
680 manual.x = (rcc.chan2_raw-1500)*2;
681 manual.y = (rcc.chan1_raw-1500)*2;
682 manual.z = rcc.chan3_raw-1000;
683 manual.r = (rcc.chan4_raw-1500)*2;
684 manual.buttons = 0;
685 mavlink_msg_manual_control_encode(mavState.sysID, mavState.compID, &mess, &manual);
686 SendMsg(mess);
687 }
688
689
690
691 void SendVisionPosition(uint64_t time_usec, float x, float y, float z, float roll, float pitch, float yaw)
692 {
693 mavlink_message_t mess;
694 mavlink_vision_position_estimate_t vision_position;
695 vision_position.usec = time_usec;
696 vision_position.x = x;
697 vision_position.y = y;
698 vision_position.z = z;
699 vision_position.roll = roll;
700 vision_position.pitch = pitch;
701 vision_position.yaw = yaw;
702
703 mavlink_msg_vision_position_estimate_encode(mavState.sysID, mavState.compID, &mess, &vision_position);
704 //std::cout<<std::to_string(time_usec)<<", "<<std::to_string(mavState.sysID)<<", "<<std::to_string(mavState.compID)<<", "<<std::to_string(mess.len)<<", "<<std::to_string(mess.seq)<<", "<<vision_position.x<<", "<<vision_position.y<<", "<<vision_position.z<<", "<<vision_position.yaw<<std::endl;
705 SendMsg(mess);
706 }
707
708
709 // y0 -> Time stamp sec for pos msg
710 // y1 -> Time stamp usec for pos msg
711 // t_pos_msg = y0 + y1 / 1000000.0
712 // y2-y4 -> Pos_x,Pos_y,Pos_z in ned, unit m
713 // y5-y8 -> Quat (w,x,y,z) for vehicle attitude
714 // y9 -> Time stamp sec for vel msg
715 // y10 -> Time stamp usec for vel msg
716 // t_vel_msg = y9 + y10 / 1000000.0
717 // y11-y13 -> vel_x,vel_y,vel_z in ned, unit m/s
718 // y14 -> Time stamp sec for acc msg
719 // y15 -> Time stamp usec for acc msg
720 // y16-y18 -> acc_x,acc_y,acc_z in ned, unit m/s^2
721 // y19-y21 -> Euler (roll pitch yaw) ang from vehicle Quat
722 // y22 -> tracker->has_data, is there any vrpn message received.
723 // y23 -> tracker->has_pos, is the vrpn pos message received.
724 // 24-29 -> reserve for future use
725 void Send3DShow(double y[30])
726 {
727 SOut2Simulator m_show3d;
728 uint64_t time_usec = y[0]*1000000+y[1];
729 if(m_start_time==0){
730 m_start_time=time_usec;
731 }
732 double runTime = (time_usec-m_start_time)/1000000.0; // 时间戳
733 m_show3d.checksum=123456789;
734 m_show3d.copterID = CopterID;
735 m_show3d.runnedTime = runTime;
736 m_show3d.vehicleType = 600251; // 显示飞机
737 for (int i = 0; i < 3; i++) {
738 m_show3d.PosE[i] = y[2+i];
739 m_show3d.AngEuler[i] = y[19+i];
740 m_show3d.VelE[i]= y[11+i];
741 m_show3d.PosGPS[i]=0;
742 m_show3d.RateB[i]=0;
743 m_show3d.AccB[i]=y[16+i];
744 m_show3d.AngQuatern[i]=y[5+i];
745 }
746 m_show3d.AngQuatern[3]=y[8];
747
748 // 仿真超过1s,且高度大于0.2,才开启螺旋桨
749 if(m_show3d.runnedTime>1 && m_show3d.PosE[2]<-0.1){
750 for (int i = 0; i < 4; i++) {
751 m_show3d.MotorRPMS[i] = 500; //单位RPM
752 m_show3d.MotorRPMS[4+i] = 0;
753 }
754 }
755
756 // 发送到RflySim3D用于三维显示
757 udp.SendTo((const char *)&m_show3d,sizeof(m_show3d),"127.0.0.1",20010);
758
759 }
760
761
762 // void SendVisionOdometry(uint64_t time_usec, float pos[3],float vel[3],float quat[4],float rate[3], bool isReset=false)
763 // {
764 // mavlink_message_t mess;
765 // mavlink_odometry_t odo;
766
767 // static int resetCont=0;
768
769 // /**
770 // * PX4 expects the body's linear velocity in the local frame,
771 // * the linear velocity is rotated from the odom child_frame to the
772 // * local NED frame. The angular velocity needs to be expressed in the
773 // * body (fcu_frd) frame.
774 // */
775 // uint8_t frame_id=MAV_FRAME_LOCAL_FRD;
776
777
778 // /**
779 // * Supported local frame of reference is MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_FRD
780 // * The supported sources of the data/tesimator type are MAV_ESTIMATOR_TYPE_VISION,
781 // * MAV_ESTIMATOR_TYPE_VIO and MAV_ESTIMATOR_TYPE_MOCAP
782 // *
783 // * @note Regarding the local frames of reference, the appropriate EKF_AID_MASK
784 // * should be set in order to match a frame aligned (NED) or not aligned (FRD)
785 // * with true North
786 // */
787 // uint8_t child_frame_id=MAV_FRAME_LOCAL_FRD;
788
789 // odo.time_usec = time_usec;
790 // odo.x=pos[0];/*< [m] X Position*/
791 // odo.y=pos[1];/*< [m] Y Position*/
792 // odo.z=pos[2];/*< [m] Z Position*/
793
794 // for(int i=0;i<4;i++){
795 // odo.q[i]=quat[i]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/
796 // }
797
798 // odo.vx=vel[0]; /*< [m/s] X linear speed*/
799 // odo.vy=vel[1]; /*< [m/s] Y linear speed*/
800 // odo.vz=vel[2]; /*< [m/s] Z linear speed*/
801
802 // odo.rollspeed=rate[0]; /*< [rad/s] Roll angular speed*/
803 // odo.pitchspeed=rate[1]; /*< [rad/s] Pitch angular speed*/
804 // odo.yawspeed=rate[2]; /*< [rad/s] Yaw angular speed*/
805
806 // float covariance[21]={0};
807 // covariance[0]=NAN; //set NAN to disable pose_covariance
808
809 // odo.estimator_type=MAV_ESTIMATOR_TYPE_VIO;
810
811 // if(isReset){ //self add if need reset.
812 // resetCont++;
813 // }
814 // odo.reset_counter=resetCont;
815
816 // mavlink_msg_odometry_encode(mavState.sysID, mavState.compID, &mess, &odo);
817 // SendMsg(mess);
818 // }
819
820 void setFlightMode_px4(PX4_FLIGHTMODE newMode, uint32_t& outCustomMode){
821 px4_custom_mode outdata;
822 outdata.data = 0;
823 switch (newMode)
824 {
825 case PX4_FLIGHTMODE_MANUAL:
826 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
827 outdata.sub_mode = 0;
828 break;
829 case PX4_FLIGHTMODE_ALT:
830 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTL;
831 outdata.sub_mode = 0;
832 break;
833 case PX4_FLIGHTMODE_POS:
834 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL;
835 outdata.sub_mode = 0;
836 break;
837 case PX4_FLIGHTMODE_TAKEOFF:
838 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
839 outdata.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
840 break;
841 case PX4_FLIGHTMODE_LAND:
842 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
843 outdata.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LAND;
844 break;
845 case PX4_FLIGHTMODE_MISSION:
846 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
847 outdata.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
848 break;
849 case PX4_FLIGHTMODE_RTL:
850 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
851 outdata.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTL;
852 break;
853
854 case PX4_FLIGHTMODE_STABILIZED:
855 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_STABILIZED;
856 outdata.sub_mode = 0;
857 break;
858
859 case PX4_FLIGHTMODE_OFFBOARD:
860 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_OFFBOARD;
861 outdata.sub_mode = 0;
862 break;
863
864 case PX4_FLIGHTMODE_AUTO_READY:
865 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
866 outdata.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
867 break;
868
869 case PX4_FLIGHTMODE_AUTO_LOITER:
870 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
871 outdata.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
872 break;
873
874 default:
875 break;
876 }
877 outCustomMode = outdata.data;
878 }
879
880 void getFlightMode_px4(uint32_t inCustomMode, PX4_FLIGHTMODE& outMode){
881 px4_custom_mode indata;
882 indata.data = inCustomMode;
883 //qDebug()<<inCustomMode<<indata.main_mode<<indata.sub_mode;
884 if (indata.main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL){
885 outMode = PX4_FLIGHTMODE_MANUAL;
886 }
887 else if (indata.main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL){
888 outMode = PX4_FLIGHTMODE_ALT;
889 }
890 else if (indata.main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL){
891 outMode = PX4_FLIGHTMODE_POS;
892 }
893 else if (indata.main_mode == PX4_CUSTOM_MAIN_MODE_OFFBOARD){
894 outMode = PX4_FLIGHTMODE_OFFBOARD;
895 }
896 else if (indata.main_mode == PX4_CUSTOM_MAIN_MODE_STABILIZED){
897 outMode = PX4_FLIGHTMODE_STABILIZED;
898 }
899 else if (indata.main_mode == PX4_CUSTOM_MAIN_MODE_AUTO)
900 {
901 if (indata.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_MISSION){
902 outMode = PX4_FLIGHTMODE_MISSION;
903 }
904 else if (indata.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF){
905 outMode = PX4_FLIGHTMODE_TAKEOFF;
906 }
907 else if (indata.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_LAND){
908 outMode = PX4_FLIGHTMODE_LAND;
909 }
910 else if (indata.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_RTL){
911 outMode = PX4_FLIGHTMODE_RTL;
912 }
913 else if (indata.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_READY){
914 outMode = PX4_FLIGHTMODE_AUTO_READY;
915 }
916 else if (indata.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_LOITER){
917 outMode = PX4_FLIGHTMODE_AUTO_LOITER;
918 }
919 }
920 }
921
922 std::string getFlightModeName_px4(PX4_FLIGHTMODE fm){
923
924 std::string qstr="";
925 switch (fm)
926 {
927 case 1:
928 qstr="Manual Mode";
929 break;
930 case 2:
931 qstr="Altitude Mode";
932 break;
933 case 3:
934 qstr="Position Mode";
935 break;
936 case 4:
937 qstr="Takeoff Mode";
938 break;
939 case 5:
940 qstr="Land Mode";
941 break;
942 case 6:
943 qstr="Auto Mode";
944 break;
945 case 7:
946 qstr="RTL Mode";
947 break;
948 case 8:
949 qstr="Stablized Mode";
950 break;
951 case 9:
952 qstr="Offboard Mode";
953 break;
954 case 10:
955 qstr="Auto Ready Mode";
956 break;
957 case 11:
958 qstr="Auto Loiter Mode";
959 break;
960 default:
961 qstr="Other Mode";
962 break;
963 }
964 return qstr;
965
966 }
967
968 bool isBitTrue(uint32_t value, int bitIndex) {
969 return (value & (1U << bitIndex)) != 0;
970 }
971
972 // input vector, input dim, sim time (s)
973 void SendMavlinkFull(double **u, double t){
974
975 if(offCtrlState==0){
976 SendVelNED(0,0,0,0);
977 offLastTime=t;
978 offCtrlState=1;
979 }
980 if(offCtrlState==1){
981 SendVelNED(0,0,0,0);
982 if(t-offLastTime>1.1){
983 sendMavEnableGuided(true);
984 offLastTime=t;
985 offCtrlState=2;
986 }
987 }
988 if(offCtrlState==2){
989 if(t-offLastTime>1.1){
990 SendMavArm(true);
991 offCtrlState=3;
992 }
993 }
994 if(offCtrlState==3){
995
996 inHILCMDData hil;
997 //inData.time_boot_ms = 123;
998 hil.time_boot_ms = (uint32_t)*u[0];
999 hil.copterID=(uint32_t)*u[1];
1000 hil.modes=(uint32_t)*u[2];
1001 hil.flags=(uint32_t)*u[3];
1002 for(int j=0;j<11;j++){
1003 hil.ctrls[j]=(float)*u[4+j];
1004 }
1005 uint16_t type_mask = hil.modes & 0xFFF;
1006 uint8_t coordinate_frame = hil.flags & 0xFF;
1007 sendMavOffboardCmd(type_mask,coordinate_frame,hil.ctrls[0],hil.ctrls[1],hil.ctrls[2],hil.ctrls[3],hil.ctrls[4],hil.ctrls[5],hil.ctrls[6],hil.ctrls[7],hil.ctrls[8],hil.ctrls[9],hil.ctrls[10]);
1008
1009 }
1010
1011 }
1012
1013
1014 // input vector, input dim, sim time (s)
1015 void SendMavlinkSimple(double **u, double t){
1016
1017 if(offCtrlState==0){
1018 SendVelNED(0,0,0,0);
1019 offLastTime=t;
1020 offCtrlState=1;
1021 }
1022 if(offCtrlState==1){
1023 SendVelNED(0,0,0,0);
1024 if(t-offLastTime>1.1){
1025 sendMavEnableGuided(true);
1026 offLastTime=t;
1027 offCtrlState=2;
1028 }
1029 }
1030 if(offCtrlState==2){
1031 if(t-offLastTime>1.1){
1032 SendMavArm(true);
1033 offCtrlState=3;
1034 }
1035 }
1036 if(offCtrlState==3){
1037 int ctrlMode=(int)*u[0];
1038 float ctrls[4];
1039
1040 if(ctrlMode <0){ // no Data send mode
1041 return;
1042 }
1043
1044 // the input len is numIn
1045 for(int j=0; j<4; j++){ // numIn-2 for controls
1046 ctrls[j] = (float)*u[1+j];
1047 }
1048
1049 SendOffSimp(ctrlMode,ctrls);
1050 }
1051
1052 }
1053
1054 // idx=0 1 2 for rfly_ctrl rfly_ctrl1 rfly_ctrl2 msg to Simulink Controller
1055 // u[1], flags, related to isEnCtrl
1056 // u[2], mode, related to idx
1057 // u[8-23], controls, total 16 elements
1058 // The meaning of u[1], u[8-23] can be user defined
1059 void sendHILCtrlMessage(double **u, double t)
1060 {
1061 uint8_t modes=1;
1062 uint64_t flags=(uint64_t)*u[1];
1063 double idx=(double)*u[2];
1064 if(idx<0.5){
1065 modes=1; // for rfly_ctrl msg
1066 }else if(idx<1.5){
1067 modes=101; // for rfly_ctrl1 msg
1068 }else{
1069 modes=201; // for rfly_ctrl2 msg
1070 }
1071
1072 mavlink_hil_actuator_controls_t hilctrl;
1073 hilctrl.mode = modes;
1074 hilctrl.flags = flags;
1075 for(int i=0;i<16;i++){
1076 hilctrl.controls[i]=(float)*u[i+8];
1077 }
1078 mavlink_message_t mess;
1079 mavlink_msg_hil_actuator_controls_encode(mavState.sysID, mavState.compID, &mess, &hilctrl);
1080 SendMsg(mess);
1081 }
1082
1083
1084 // input vector, input dim, sim time (s)
1085 void SendMavlinkReal(double **u, double t){
1086
1087 inRealflyData ird;
1088 ird.cmdBitmap = (uint32_t)*u[1];
1089 ird.typeMask = (uint16_t)*u[2];
1090
1091 // the input len is numIn
1092 for(int j=0; j<20; j++){ // numIn-8 for controls
1093 ird.controls[j] = (float)*u[8+j];
1094 }
1095
1096 //
1097 if (isBitTrue(ird.cmdBitmap, 0)){
1098 //
1099 if (isBitTrue(ird.cmdBitmap, 2))
1100 SendMavArm(1);
1101 else if (isBitTrue(ird.cmdBitmap, 7))
1102 SendMavArm(0);
1103
1104 // Offboard
1105 if (isBitTrue(ird.cmdBitmap, 3)){
1106 SendSetMode(PX4_CUSTOM_MAIN_MODE_OFFBOARD);
1107 }
1108 // Mannual
1109 if (isBitTrue(ird.cmdBitmap, 28)){
1110 SendSetMode(PX4_CUSTOM_MAIN_MODE_MANUAL);
1111 }
1112 // Alt
1113 if (isBitTrue(ird.cmdBitmap, 29)){
1114 SendSetMode(PX4_CUSTOM_MAIN_MODE_ALTCTL);
1115 }
1116 // Position
1117 if (isBitTrue(ird.cmdBitmap, 30)){
1118 SendSetMode(PX4_CUSTOM_MAIN_MODE_POSCTL);
1119 }
1120 // AUTO
1121 if (isBitTrue(ird.cmdBitmap, 31)) {
1122 SendSetMode(MAV_MODE_FLAG_AUTO_ENABLED, PX4_CUSTOM_SUB_MODE_AUTO_LOITER);
1123 }
1124 }
1125
1126 // send Offboard
1127 if (isBitTrue(ird.cmdBitmap, 16)) {
1128 uint8_t coordinate = MAV_FRAME_LOCAL_NED;
1129 if (isBitTrue(ird.cmdBitmap, 18))
1130 coordinate = MAV_FRAME_GLOBAL_INT;
1131 else if (isBitTrue(ird.cmdBitmap, 19))
1132 coordinate = MAV_FRAME_BODY_NED;
1133 SendPositionTarget(ird.typeMask, coordinate, ird.controls);
1134 }
1135 else if (isBitTrue(ird.cmdBitmap, 17)){
1136 SendAttitudeTarget(ird.typeMask, ird.controls);
1137 }
1138 else if (isBitTrue(ird.cmdBitmap, 23)){
1139 if (!isRcc){
1140 SendParamInt("NAV_RCL_ACT", 0);
1141 SendParamInt("NAV_DLL_ACT", 0);
1142 isRcc = true;
1143 SendSetMode(PX4_CUSTOM_MAIN_MODE_MANUAL);
1144 }
1145 SendRccTarget(ird.controls);
1146 }
1147
1148 }
1149
1150 void mavlinkSetCmd(uint16_t command,float param1=0,float param2=0,float param3=0){
1151 SendMavCmdLong(command,param1,param2,param3);
1152 }
1153
1154 void sendMavSetParam(char param_id[], float param_value, MAV_PARAM_TYPE param_type)
1155 {
1156
1157 mavlink_param_set_t ps;
1158 ps.target_system = mavState.TargetSysID;
1159 ps.target_component = mavState.TargetCompID;
1160 ps.param_value = param_value;
1161 ps.param_type = param_type;
1162 for(int i=0;i<16;i++){
1163 ps.param_id[i] = param_id[i];
1164 }
1165 mavlink_message_t mess;
1166 mavlink_msg_param_set_encode(mavState.sysID, mavState.compID, &mess, &ps);
1167
1168 }
1169
1170
1171 void sendMavEnableGuided(bool isEnable)
1172 {
1173 if(isEnable){
1174 setMavModel(PX4_CUSTOM_MAIN_MODE_OFFBOARD);
1175 char cmd[17] = "NAV_RCL_ACT";
1176 sendMavSetParam(cmd,0,MAV_PARAM_TYPE_INT32);
1177 char cmd1[17] = "NAV_DLL_ACT";
1178 sendMavSetParam(cmd1,0,MAV_PARAM_TYPE_INT32);
1179 char cmd2[17] = "COM_RCL_EXCEPT";
1180 sendMavSetParam(cmd2,4/7.1362e+44,MAV_PARAM_TYPE_INT32);
1181 }else{
1182 //mavlinkSetCmd(MAV_CMD_NAV_GUIDED_ENABLE,false);
1183 setMavModel(PX4_CUSTOM_MAIN_MODE_MANUAL);
1184 }
1185 }
1186 void setMavModel(PX4_CUSTOM_MAIN_MODE mianMode){
1187 uint8_t basemode=static_cast<uint8_t>(MAV_MODE_FLAG::MAV_MODE_FLAG_CUSTOM_MODE_ENABLED);
1188
1189 mavlinkSetCmd(MAV_CMD_DO_SET_MODE,basemode,mianMode);
1190 }
1191
1192 void setMavModel(PX4_CUSTOM_MAIN_MODE mianMode,PX4_CUSTOM_SUB_MODE_AUTO custMode){
1193 uint8_t basemode=static_cast<uint8_t>(MAV_MODE_FLAG::MAV_MODE_FLAG_CUSTOM_MODE_ENABLED);
1194 mavlinkSetCmd(MAV_CMD_DO_SET_MODE,basemode,mianMode,custMode);
1195 }
1196
1197 void sendMavOffboardCmd(uint16_t type_mask, uint8_t coordinate_frame, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
1198 {
1199 mavlink_set_position_target_local_ned_t m_target_ned;
1200 //m_target_ned.time_boot_ms = QDateTime::currentDateTime().currentMSecsSinceEpoch();
1201 m_target_ned.target_system = mavState.TargetSysID;
1202 m_target_ned.target_component = mavState.TargetCompID;
1203 m_target_ned.coordinate_frame = coordinate_frame;
1204 m_target_ned.type_mask = type_mask;
1205 m_target_ned.x = x;
1206 m_target_ned.y = y;
1207 m_target_ned.z = z;
1208 m_target_ned.vx = vx;
1209 m_target_ned.vy = vy;
1210 m_target_ned.vz = vz;
1211 m_target_ned.afx = afx;
1212 m_target_ned.afy = afy;
1213 m_target_ned.afz = afz;
1214 m_target_ned.yaw = yaw;
1215 m_target_ned.yaw_rate = yaw_rate;
1216
1217 mavlink_message_t mess;
1218 mavlink_msg_set_position_target_local_ned_encode(mavState.sysID, mavState.compID, &mess, &m_target_ned);
1219 SendMsg(mess);
1220 }
1221
1222
1223 void SendOffSimp(int ctrlMode,float controls[4]={0}){
1224 float ctrls[11] = {0};
1225 uint8_t coordinate_frame = 0;
1226 uint16_t type_mask = 0;
1227 switch (ctrlMode)
1228 {
1229 case 0: // Earth vel Ctrl
1230 coordinate_frame = MAV_FRAME_LOCAL_NED;
1231 type_mask = 7 | 7 << 6 | 1 << 10;
1232 ctrls[3] = controls[0];
1233 ctrls[4] = controls[1];
1234 ctrls[5] = controls[2];
1235 ctrls[10] = controls[3];
1236 break;
1237 case 1: //body vel ctrl
1238 coordinate_frame = MAV_FRAME_BODY_NED;
1239 type_mask = 7 | 7 << 6 | 1 << 10;
1240 ctrls[3] = controls[0];
1241 ctrls[4] = controls[1];
1242 ctrls[5] = controls[2];
1243 ctrls[10] = controls[3];
1244 break;
1245
1246 case 2: // earth pos ctrl
1247 coordinate_frame = MAV_FRAME_LOCAL_NED;
1248 type_mask = 7 << 3 | 7 << 6 | 1 << 11;
1249 ctrls[0] = controls[0];
1250 ctrls[1] = controls[1];
1251 ctrls[2] = controls[2];
1252 ctrls[9] = controls[3];
1253 break;
1254 case 3: // body pos ctrl
1255 coordinate_frame = MAV_FRAME_BODY_NED;
1256 type_mask = 7 << 3 | 7 << 6 | 1 << 11;
1257 ctrls[0] = controls[0];
1258 ctrls[1] = controls[1];
1259 ctrls[2] = controls[2];
1260 ctrls[9] = controls[3];
1261 break;
1262
1263 case 6: // body pos ctrl
1264 coordinate_frame = MAV_FRAME_LOCAL_NED;
1265 type_mask = 7 | 7 << 3 | 1 << 10 | 1 << 11;
1266 ctrls[6] = controls[0];
1267 ctrls[7] = controls[1];
1268 ctrls[8] = controls[2];
1269 break;
1270
1271 case 7: //
1272 coordinate_frame = MAV_FRAME_LOCAL_NED;
1273 type_mask = 7 | 7 << 3 | 1 << 11;
1274 ctrls[6] = controls[0];
1275 ctrls[7] = controls[1];
1276 ctrls[8] = controls[2];
1277 ctrls[9] = controls[3];
1278 break;
1279
1280 case 8: //
1281 coordinate_frame = MAV_FRAME_LOCAL_NED;
1282 type_mask = 7 | 7 << 3 | 1 << 10;
1283 ctrls[6] = controls[0];
1284 ctrls[7] = controls[1];
1285 ctrls[8] = controls[2];
1286 ctrls[10] = controls[3];
1287 break;
1288
1289 case 13:
1290 {
1291 coordinate_frame = 1;
1292 type_mask = 448;
1293 float vel = controls[0];
1294 float alt = controls[1];
1295 float yaw = controls[2];
1296
1297 ctrls[2] = alt;
1298 ctrls[3] = yaw;
1299 ctrls[4] = vel;
1300 break;
1301 }
1302
1303 default:
1304 break;
1305 }
1306
1307 sendMavOffboardCmd(type_mask,coordinate_frame,ctrls[0],ctrls[1],ctrls[2],ctrls[3],ctrls[4],ctrls[5],ctrls[6],ctrls[7],ctrls[8],ctrls[9],ctrls[10]);
1308
1309 }
1310
1311 void SendVelNED(float vx=0,float vy=0,float vz=0,float yawrate=0){
1312 float ctrls[4]={vx,vy,vz,yawrate};
1313 SendOffSimp(0,ctrls);
1314 }
1315
1316 // Self check program...
1317 bool SelfCheckProgram(double t){
1318 //std::cout<<"checking"<<std::endl;
1319 //-1:faild, 0 inited, 2. get local pos, 3. can offboard, 4. can armed, 5. checkPassed
1320
1321 // Send this can get px4 info for any valid local ip.
1322 // if (t-lastHeartbeatTime >= 1) {
1323 // SendHeartbeat();
1324 // lastHeartbeatTime = t;
1325 // }
1326 if((SelfCheckMainState==0) && t>2){ //Connection check
1327 if(mavState.isHeartRec){
1328 std::cout<<"Drone #"<<CopterID<<": Checking mavlink connection successfully."<<std::endl;
1329 mavState.selfCheckState=1;
1330 SelfCheckMainState=1; //go to mode 1.
1331 }
1332 }
1333
1334 if(SelfCheckMainState==1){
1335 if(mavState.isLocalNed){
1336 std::cout<<"Drone #"<<CopterID<<": Checking local pos successfully."<<std::endl;
1337 mavState.selfCheckState=2;
1338 SelfCheckMainState=2; //go to mode 2.
1339 }
1340 }
1341
1342 if(SelfCheckMainState==2){
1343 // send offboard vel=0
1344 SendVelNED(0,0,0,0);
1345
1346 if(SelfCheckSubState==0){
1347 lastTime=t; //Record sim time.
1348 SelfCheckSubState=1;
1349 }
1350 if(SelfCheckSubState==1){
1351 sendMavEnableGuided(true);
1352 SelfCheckSubState=2;
1353 lastTime=t; //Record sim time.
1354 }
1355 if(SelfCheckSubState==2){
1356 if(t-lastTime>1){
1357 if(mavState.isOffboard){
1358 std::cout<<"Drone #"<<CopterID<<": Checking offboard successfully."<<std::endl;
1359 mavState.selfCheckState=3;
1360 SelfCheckMainState=3; //go to mode 3.
1361 SelfCheckSubState=0;
1362 }
1363 else{
1364 SelfCheckSubState=1;
1365 }
1366 }
1367 }
1368 }
1369
1370 if(SelfCheckMainState==3){
1371 // send offboard vel=0
1372 SendVelNED(0,0,0,0);
1373
1374 if(SelfCheckSubState==0){
1375 lastTime=t; //Record sim time.
1376 // send arm cmd
1377 SendMavArm(true);
1378 SelfCheckSubState=1;
1379 }
1380
1381 if(SelfCheckSubState==1){
1382 if(t-lastTime>1){
1383 if(mavState.isArmed){
1384 std::cout<<"Drone #"<<CopterID<<": Checking arm successfully."<<std::endl;
1385 mavState.selfCheckState=4;
1386 SelfCheckMainState=4; //go to mode 4.
1387 }
1388 SelfCheckSubState = 0;
1389 }
1390 }
1391 }
1392
1393 if(SelfCheckMainState==4){
1394 SendVelNED(0,0,0,0);
1395
1396 if(SelfCheckSubState==0){
1397 lastTime=t; //Record sim time.
1398 SelfCheckSubState=1;
1399 sendMavEnableGuided(false);
1400 SendMavArm(false);
1401 }
1402
1403 if(SelfCheckSubState==1){
1404 if(t-lastTime>1){
1405 if(!mavState.isArmed && !mavState.isOffboard){
1406 std::cout<<"Drone #"<<CopterID<<": Checking passed."<<std::endl;
1407 mavState.selfCheckState=5;
1408 SelfCheckMainState=5; //go to mode 5
1409 }
1410 SelfCheckSubState=0;
1411 }
1412 }
1413 }
1414
1415 if(SelfCheckMainState==5){
1416 return true;
1417 }
1418 return false;
1419 }
1420};
定义 rfly_udp.h:306
定义 rfly_mavlink.h:75
定义 rfly_data.h:93
定义 rfly_data.h:291
定义 rfly_data.h:228
定义 rfly_data.h:266
定义 rfly_mavlink.h:59