117 std::string TargetIP;
122 char buf[MAX_BUF_LEN+1];
125 double GpsOrin[3]={0};
128 int SelfCheckMainState=0;
129 int SelfCheckSubState=0;
134 double offLastTime=0;
137 uint64_t m_start_time = 0;
149 int recvlen=udp.RecvNoblock(buf,RecvIP,RecvPort,MAX_BUF_LEN);
151 mavlink_message_t message;
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);
157 onMavLinkMessage(message);
169 void onMavLinkMessage(mavlink_message_t message){
171 switch (message.msgid){
172 case MAVLINK_MSG_ID_HEARTBEAT:{
173 mavlink_heartbeat_t MavHartt;
174 mavlink_msg_heartbeat_decode(&message, &MavHartt);
176 if (MavHartt.custom_mode == 0)
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;
185 mavState.base_mode = MavHartt.base_mode;
186 mavState.custom_mode = MavHartt.custom_mode;
187 mavState.system_status = MavHartt.system_status;
189 if(mavState.system_status==3){
190 mavState.isStanby=
true;
192 mavState.isStanby=
false;
195 if(mavState.system_status==4){
196 mavState.isActive=
true;
198 mavState.isActive=
false;
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;
207 if(mavState.isArmed){
208 mavState.isArmed =
false;
209 std::cout<<
"Drone #"<<CopterID<<
": "<<
"PX4 Disamed. "<<std::endl;
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;
220 if(fm==PX4_FLIGHTMODE_OFFBOARD){
221 mavState.isOffboard=
true;
224 mavState.isOffboard=
false;
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;
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;
242 if(mavState.sysStatus.load>900){
243 if (!mavState.isHighLoad){
244 mavState.isHighLoad=
true;
245 std::cout<<
"Drone #"<<CopterID<<
": "<<
"High CPU load."<<std::endl;
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;
258 case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:{
259 mavlink_extended_sys_state_t mss;
260 mavlink_msg_extended_sys_state_decode(&message, &mss);
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;
269 case MAV_LANDED_STATE_IN_AIR:
270 std::cout<<
"Drone #"<<CopterID<<
": "<<
"In air."<<std::endl;
272 case MAV_LANDED_STATE_TAKEOFF:
273 std::cout<<
"Drone #"<<CopterID<<
": "<<
"Takeoff."<<std::endl;
275 case MAV_LANDED_STATE_LANDING:
276 std::cout<<
"Drone #"<<CopterID<<
": "<<
"Landing."<<std::endl;
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;
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;
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;
312 case MAVLINK_MSG_ID_ATTITUDE:{
313 mavlink_attitude_t att;
314 mavlink_msg_attitude_decode(&message, &att);
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;
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;
338 case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:{
339 mavlink_global_position_int_t gp;
340 mavlink_msg_global_position_int_decode(&message, &gp);
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;
354 case MAVLINK_MSG_ID_GPS_RAW_INT:{
356 mavlink_gps_raw_int_t gri;
357 mavlink_msg_gps_raw_int_decode(&message, &gri);
359 data.fix_type = gri.fix_type;
361 data.satellites_visible = gri.satellites_visible;
365 case MAVLINK_MSG_ID_ESTIMATOR_STATUS:{
368 mavlink_estimator_status_t es;
369 mavlink_msg_estimator_status_decode(&message, &es);
372 data.pos_horiz_accuracy = es.pos_horiz_accuracy;
373 data.pos_vert_accuracy = es.pos_vert_accuracy;
379 case MAVLINK_MSG_ID_HOME_POSITION:{
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;
388 mavState.isGpsHome=
true;
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;
402 case MAVLINK_MSG_ID_COMMAND_ACK:{
403 mavlink_command_ack_t mck;
404 mavlink_msg_command_ack_decode(&message, &mck);
412 qstrt=
"TEMPORARILY_REJECTED";
431 cmdName =
"ARM/DISARM";
434 cmdName =
"SET_MODE";
437 cmdName =
"REBOOT/SHUTDOWN";
440 cmdName =
"REQUEST_MAVLINK_VERSION";
443 cmdName =
"REQUEST_AUTOPILOT_VERSION";
446 cmdName =
"NAV_GUIDED_ENABLE";
449 cmdName =
"NAV_LAND";
452 cmdName =
"NAV_TAKEOFF";
455 cmdName =
"DO_REPOSITION";
458 cmdName =
"ID: "+ std::to_string(mck.command);
462 std::cout<<
"Drone #"<<CopterID<<
": "<<
"Command "<<cmdName<<
" "<<qstrt<<std::endl;
471 void stringToLower(std::string& str)
473 std::transform(str.begin(), str.end(), str.begin(), [](
char& c){
474 return std::tolower(c);
478 void SendMsg(mavlink_message_t mess){
479 unsigned int length = mavlink_msg_to_send_buffer((uint8_t*)buf, &mess);
482 udp.SendTo((
const char *)buf,length,TargetIP,TargetPort);
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);
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)
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);
519 void SendMavArm(
int isArm)
523 SendMavCmdLong(MAV_CMD_COMPONENT_ARM_DISARM, 1);
527 SendMavCmdLong(MAV_CMD_COMPONENT_ARM_DISARM, 0, 21196.0f);
533 void SendSetMode(
int mainMode,
int customMode=0)
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);
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;
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];
551 m_target_ned.z = data[2];
552 m_target_ned.vx = data[3];
553 m_target_ned.vy = data[4];
555 m_target_ned.vz = data[5];
556 m_target_ned.afx = data[6];
557 m_target_ned.afy = data[7];
559 m_target_ned.afz = data[8];
560 m_target_ned.yaw = data[11];
562 m_target_ned.yaw_rate = data[14];
568 mavlink_msg_set_position_target_local_ned_encode(mavState.sysID, mavState.compID, &mess, &m_target_ned);
570 else if (coordinate == MAV_FRAME_GLOBAL_INT){
571 mavlink_set_position_target_global_int_t m_target_global;
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);
594 void SendAttitudeTarget(uint8_t type_mask,
float *data){
595 mavlink_message_t mess;
596 mavlink_set_attitude_target_t m_target_att;
598 m_target_att.target_system = mavState.TargetSysID;
599 m_target_att.target_component = mavState.TargetCompID;
600 m_target_att.type_mask = type_mask;
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);
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;
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);
629 void SendParamInt(std::string
id,
int value){
630 mavlink_message_t mess;
631 mavlink_param_set_t param;
633 param.target_system = mavState.TargetSysID;
634 param.target_component = mavState.TargetCompID;
635 param.param_value = float(value)/7.13622e+44;
636 param.param_type = MAV_PARAM_TYPE_INT32;
637 std::strcpy(param.param_id,
id.c_str());
639 mavlink_msg_param_set_encode(mavState.sysID, mavState.compID, &mess, ¶m);
643 void SendParamFloat(std::string
id,
float value){
644 mavlink_message_t mess;
645 mavlink_param_set_t param;
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());
653 mavlink_msg_param_set_encode(mavState.sysID, mavState.compID, &mess, ¶m);
657 void SendRccTarget(
float *data)
659 mavlink_message_t mess;
660 mavlink_rc_channels_override_t rcc;
661 uint16_t middle_rc = 1500;
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];
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);
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;
685 mavlink_msg_manual_control_encode(mavState.sysID, mavState.compID, &mess, &manual);
691 void SendVisionPosition(uint64_t time_usec,
float x,
float y,
float z,
float roll,
float pitch,
float yaw)
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;
703 mavlink_msg_vision_position_estimate_encode(mavState.sysID, mavState.compID, &mess, &vision_position);
725 void Send3DShow(
double y[30])
728 uint64_t time_usec = y[0]*1000000+y[1];
730 m_start_time=time_usec;
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;
743 m_show3d.AccB[i]=y[16+i];
744 m_show3d.AngQuatern[i]=y[5+i];
746 m_show3d.AngQuatern[3]=y[8];
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;
752 m_show3d.MotorRPMS[4+i] = 0;
757 udp.SendTo((
const char *)&m_show3d,
sizeof(m_show3d),
"127.0.0.1",20010);
825 case PX4_FLIGHTMODE_MANUAL:
826 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
827 outdata.sub_mode = 0;
829 case PX4_FLIGHTMODE_ALT:
830 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTL;
831 outdata.sub_mode = 0;
833 case PX4_FLIGHTMODE_POS:
834 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL;
835 outdata.sub_mode = 0;
837 case PX4_FLIGHTMODE_TAKEOFF:
838 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
839 outdata.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
841 case PX4_FLIGHTMODE_LAND:
842 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
843 outdata.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LAND;
845 case PX4_FLIGHTMODE_MISSION:
846 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
847 outdata.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
849 case PX4_FLIGHTMODE_RTL:
850 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
851 outdata.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTL;
854 case PX4_FLIGHTMODE_STABILIZED:
855 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_STABILIZED;
856 outdata.sub_mode = 0;
859 case PX4_FLIGHTMODE_OFFBOARD:
860 outdata.main_mode = PX4_CUSTOM_MAIN_MODE_OFFBOARD;
861 outdata.sub_mode = 0;
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;
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;
877 outCustomMode = outdata.data;
880 void getFlightMode_px4(uint32_t inCustomMode, PX4_FLIGHTMODE& outMode){
882 indata.data = inCustomMode;
884 if (indata.main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL){
885 outMode = PX4_FLIGHTMODE_MANUAL;
887 else if (indata.main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL){
888 outMode = PX4_FLIGHTMODE_ALT;
890 else if (indata.main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL){
891 outMode = PX4_FLIGHTMODE_POS;
893 else if (indata.main_mode == PX4_CUSTOM_MAIN_MODE_OFFBOARD){
894 outMode = PX4_FLIGHTMODE_OFFBOARD;
896 else if (indata.main_mode == PX4_CUSTOM_MAIN_MODE_STABILIZED){
897 outMode = PX4_FLIGHTMODE_STABILIZED;
899 else if (indata.main_mode == PX4_CUSTOM_MAIN_MODE_AUTO)
901 if (indata.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_MISSION){
902 outMode = PX4_FLIGHTMODE_MISSION;
904 else if (indata.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF){
905 outMode = PX4_FLIGHTMODE_TAKEOFF;
907 else if (indata.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_LAND){
908 outMode = PX4_FLIGHTMODE_LAND;
910 else if (indata.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_RTL){
911 outMode = PX4_FLIGHTMODE_RTL;
913 else if (indata.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_READY){
914 outMode = PX4_FLIGHTMODE_AUTO_READY;
916 else if (indata.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_LOITER){
917 outMode = PX4_FLIGHTMODE_AUTO_LOITER;
922 std::string getFlightModeName_px4(PX4_FLIGHTMODE fm){
931 qstr=
"Altitude Mode";
934 qstr=
"Position Mode";
949 qstr=
"Stablized Mode";
952 qstr=
"Offboard Mode";
955 qstr=
"Auto Ready Mode";
958 qstr=
"Auto Loiter Mode";
968 bool isBitTrue(uint32_t value,
int bitIndex) {
969 return (value & (1U << bitIndex)) != 0;
973 void SendMavlinkFull(
double **u,
double t){
982 if(t-offLastTime>1.1){
983 sendMavEnableGuided(
true);
989 if(t-offLastTime>1.1){
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];
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]);
1015 void SendMavlinkSimple(
double **u,
double t){
1017 if(offCtrlState==0){
1018 SendVelNED(0,0,0,0);
1022 if(offCtrlState==1){
1023 SendVelNED(0,0,0,0);
1024 if(t-offLastTime>1.1){
1025 sendMavEnableGuided(
true);
1030 if(offCtrlState==2){
1031 if(t-offLastTime>1.1){
1036 if(offCtrlState==3){
1037 int ctrlMode=(int)*u[0];
1045 for(
int j=0; j<4; j++){
1046 ctrls[j] = (float)*u[1+j];
1049 SendOffSimp(ctrlMode,ctrls);
1059 void sendHILCtrlMessage(
double **u,
double t)
1062 uint64_t flags=(uint64_t)*u[1];
1063 double idx=(double)*u[2];
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];
1078 mavlink_message_t mess;
1079 mavlink_msg_hil_actuator_controls_encode(mavState.sysID, mavState.compID, &mess, &hilctrl);
1085 void SendMavlinkReal(
double **u,
double t){
1088 ird.cmdBitmap = (uint32_t)*u[1];
1089 ird.typeMask = (uint16_t)*u[2];
1092 for(
int j=0; j<20; j++){
1093 ird.controls[j] = (float)*u[8+j];
1097 if (isBitTrue(ird.cmdBitmap, 0)){
1099 if (isBitTrue(ird.cmdBitmap, 2))
1101 else if (isBitTrue(ird.cmdBitmap, 7))
1105 if (isBitTrue(ird.cmdBitmap, 3)){
1106 SendSetMode(PX4_CUSTOM_MAIN_MODE_OFFBOARD);
1109 if (isBitTrue(ird.cmdBitmap, 28)){
1110 SendSetMode(PX4_CUSTOM_MAIN_MODE_MANUAL);
1113 if (isBitTrue(ird.cmdBitmap, 29)){
1114 SendSetMode(PX4_CUSTOM_MAIN_MODE_ALTCTL);
1117 if (isBitTrue(ird.cmdBitmap, 30)){
1118 SendSetMode(PX4_CUSTOM_MAIN_MODE_POSCTL);
1121 if (isBitTrue(ird.cmdBitmap, 31)) {
1122 SendSetMode(MAV_MODE_FLAG_AUTO_ENABLED, PX4_CUSTOM_SUB_MODE_AUTO_LOITER);
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);
1135 else if (isBitTrue(ird.cmdBitmap, 17)){
1136 SendAttitudeTarget(ird.typeMask, ird.controls);
1138 else if (isBitTrue(ird.cmdBitmap, 23)){
1140 SendParamInt(
"NAV_RCL_ACT", 0);
1141 SendParamInt(
"NAV_DLL_ACT", 0);
1143 SendSetMode(PX4_CUSTOM_MAIN_MODE_MANUAL);
1145 SendRccTarget(ird.controls);
1150 void mavlinkSetCmd(uint16_t command,
float param1=0,
float param2=0,
float param3=0){
1151 SendMavCmdLong(command,param1,param2,param3);
1154 void sendMavSetParam(
char param_id[],
float param_value, MAV_PARAM_TYPE param_type)
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];
1165 mavlink_message_t mess;
1166 mavlink_msg_param_set_encode(mavState.sysID, mavState.compID, &mess, &ps);
1171 void sendMavEnableGuided(
bool 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);
1183 setMavModel(PX4_CUSTOM_MAIN_MODE_MANUAL);
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);
1189 mavlinkSetCmd(MAV_CMD_DO_SET_MODE,basemode,mianMode);
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);
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)
1199 mavlink_set_position_target_local_ned_t m_target_ned;
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;
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;
1217 mavlink_message_t mess;
1218 mavlink_msg_set_position_target_local_ned_encode(mavState.sysID, mavState.compID, &mess, &m_target_ned);
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;
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];
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];
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];
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];
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];
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];
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];
1291 coordinate_frame = 1;
1293 float vel = controls[0];
1294 float alt = controls[1];
1295 float yaw = controls[2];
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]);
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);
1317 bool SelfCheckProgram(
double t){
1326 if((SelfCheckMainState==0) && t>2){
1327 if(mavState.isHeartRec){
1328 std::cout<<
"Drone #"<<CopterID<<
": Checking mavlink connection successfully."<<std::endl;
1329 mavState.selfCheckState=1;
1330 SelfCheckMainState=1;
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;
1342 if(SelfCheckMainState==2){
1344 SendVelNED(0,0,0,0);
1346 if(SelfCheckSubState==0){
1348 SelfCheckSubState=1;
1350 if(SelfCheckSubState==1){
1351 sendMavEnableGuided(
true);
1352 SelfCheckSubState=2;
1355 if(SelfCheckSubState==2){
1357 if(mavState.isOffboard){
1358 std::cout<<
"Drone #"<<CopterID<<
": Checking offboard successfully."<<std::endl;
1359 mavState.selfCheckState=3;
1360 SelfCheckMainState=3;
1361 SelfCheckSubState=0;
1364 SelfCheckSubState=1;
1370 if(SelfCheckMainState==3){
1372 SendVelNED(0,0,0,0);
1374 if(SelfCheckSubState==0){
1378 SelfCheckSubState=1;
1381 if(SelfCheckSubState==1){
1383 if(mavState.isArmed){
1384 std::cout<<
"Drone #"<<CopterID<<
": Checking arm successfully."<<std::endl;
1385 mavState.selfCheckState=4;
1386 SelfCheckMainState=4;
1388 SelfCheckSubState = 0;
1393 if(SelfCheckMainState==4){
1394 SendVelNED(0,0,0,0);
1396 if(SelfCheckSubState==0){
1398 SelfCheckSubState=1;
1399 sendMavEnableGuided(
false);
1403 if(SelfCheckSubState==1){
1405 if(!mavState.isArmed && !mavState.isOffboard){
1406 std::cout<<
"Drone #"<<CopterID<<
": Checking passed."<<std::endl;
1407 mavState.selfCheckState=5;
1408 SelfCheckMainState=5;
1410 SelfCheckSubState=0;
1415 if(SelfCheckMainState==5){