Data_Drone.cpp 36.1 KB
Newer Older
1
2
3
4
5
6
7
8
/**
 * @brief Class that model a drone
 * 
 * @author Sylvain Colomer
 * @date 23/04/19
 * @version 1.0
 */

9
10
#include <chrono>
#include <ctime>    
11
12
13
14
15
16
17

#include <iostream>
#include <string>

using namespace std;


18
19
20
21
22
23
24
25
26
27
28
29
30
#include "../include/Data_Drone.h"


//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% CONTRUCTOR %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

/**
 * Default constructor. Initialize var to first value
 */
Drone::Drone()
{

}

31
32
Drone::Drone(std::string serialPort_path, int serialPort_baudrate)
{
33
    communication=DRONE_SERIAL;
34
    cout<<"Data_Drone  "<< serialPort_path<<"\n";
35
36
37
    serial1 = std::shared_ptr<Serial_Port>(new Serial_Port(serialPort_path, serialPort_baudrate));
}

38
39
40
41
42
43
44
45
void Drone::open(char  *serialPort_path, int serialPort_baudrate)
{
    communication=DRONE_SERIAL;
    cout<<"Data_Drone  "<< serialPort_path<<"\n";
    serial1 = std::shared_ptr<Serial_Port>(new Serial_Port(serialPort_path, serialPort_baudrate));
}


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

Drone::~Drone()
{
    serial1.get()->close_serial();
}

//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% COMMUNICATION %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

int Drone::read_message(mavlink_message_t &message)
{
    if(communication == DRONE_SERIAL)
    {
    return serial1.get()->read_message(message);
    }
    return 1;
}

int Drone::write_message(mavlink_message_t message)
{
    if(communication == DRONE_SERIAL)
    {
        return serial1.get()->write_message(message);
    }
    else if(communication == DRONE_WIFI)
    {
        return 1;
    }
    return 1;
}

//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% INITIALISATION %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

int Drone::init_communication()
{
    if(communication==DRONE_SERIAL)
    {
        return Drone::serial1.get()->open_serial();
    }

    return 0;
}
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
/*
void Drone::send_setpoint_velocity(float vx, float vy, float vz) {

		/* Documentation start from bit 1 instead 0,
		 * but implementation PX4 Firmware #1151 starts from 0
		 */
	//	uint16_t ignore_all_except_v_xyz = (7<<6)|(7<<0);

		// ENU->NED. Issue #49.
	/*	set_position_target_local_ned(std::chrono::system_clock::now(),
				MAV_FRAME_LOCAL_NED,
				ignore_all_except_v_xyz,
				0.0, 0.0, 0.0,
				vy, vx, -vz,
				0.0, 0.0, 0.0);
	} 
	
*/
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
/**
 * Initialisation of a drone 
 */
int Drone::init_parameters(uint limit)
{
    mavlink_message_t mavlink_message;
    bool flag_test = true;
    bool flag_success = true;
    uint counter=0;
    std::string buffer1="";

    while(flag_test)
    {
        
        flag_success = serial1.get()->read_message(mavlink_message);
        if(flag_success)
        {
            system_id = mavlink_message.sysid;
            component_id = mavlink_message.compid;
            
            flag_test=false;
        }
        
        if(counter >= limit) //Computation limit test
        {
            //Display_IHM::getInstanceOf().printLog("-> Error, no drone detected");
            return 1;
        }
        counter++;
        usleep(1000);
    }   

    return 0;
}


//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% CONTROL %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

/**
 * Arm with 1, un arm with 0
 */
146
147
int Drone::command_arm(int param1)
{
148
149
150
151
152
153
154
155
156
    //Message buffer
	mavlink_message_t message;
    mavlink_command_long_t command;
    command=mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_COMPONENT_ARM_DISARM;
    command.confirmation = false;
    command.param1           = param1;
157
	command.param2           = 21196;     //21196;  Force Arm/disarm  0 // ????
158
159
160

    mavlink_msg_command_long_encode(255, 1, &message, &command);

161
162
    if(param1 >0)
    {
163
        //Display_IHM::getInstanceOf().printLog("ARMING");
164
165
166
167
168
169
170
171
172
    }else
    {
        //Display_IHM::getInstanceOf().printLog("STOP ARMING");
    }

    return write_message(message);
}


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
int Drone::make_mode(int param1)
{
    //Message buffer
	mavlink_message_t message;
    mavlink_command_long_t command;
    command=mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_DO_SET_MODE;
 //   command.confirmation = false;
    command.param1           = 193;
	command.param2           = 1;     //21196;   // ????
	command.param3 = 0;
    mavlink_msg_command_long_encode(255, 1, &message, &command);

    if(param1 >0)
    {
        //Display_IHM::getInstanceOf().printLog("ARMING");
    }else
    {
        //Display_IHM::getInstanceOf().printLog("STOP ARMING");
    }

    return write_message(message);
}



int Drone::make_command_msg_rate(int param1)
{	
	
	float interval_us = 0.0f;


        
  
    //Message buffer
	mavlink_message_t message;
    mavlink_command_long_t command;
    command=mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
    command.param1           = 1; //rate
	command.param2           = 1; //intervall en us


    mavlink_msg_command_long_encode(255, 1, &message, &command);

    if(param1 >0)
    {
        //Display_IHM::getInstanceOf().printLog("ARMING");
    }else
    {
        //Display_IHM::getInstanceOf().printLog("STOP ARMING");
    }

    return write_message(message);
}



235
int Drone::waypoint(float param5, float param6, float param7)
236
237
238
239
240
241
242
243
{
    //Message buffer
	mavlink_message_t message;
    mavlink_command_long_t command;
    command=mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_NAV_WAYPOINT;
244
245
    command.confirmation = true;
    command.param1           = 100;  //Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing) min : 0 (seconds)
246
247
248
	command.param2           = 0;	//Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)  min 0 (m)
	command.param3           = 0;	//0 to pass through the WP, if > 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. (m)
	command.param4           = 0;	//Desired yaw angle at waypoint (rotary wing). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). (deg)
249
250
251
	command.param5           = param5;	//Latitude (m)
	command.param6           = param6;	//Longitude
	command.param7           = param7;	//Altitude
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
    mavlink_msg_command_long_encode(255, 1, &message, &command);
    return write_message(message);
}

int Drone::waypointforback(float param6)
{
    //Message buffer
	mavlink_message_t message;
    mavlink_command_long_t command;
    command=mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_NAV_WAYPOINT;
    command.confirmation = false;
    command.param1           = 0;  //Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing) min : 0 (seconds)
	command.param2           = 0;	//Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)  min 0 (m)
	command.param3           = 0;	//0 to pass through the WP, if > 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. (m)
	command.param4           = 0;	//Desired yaw angle at waypoint (rotary wing). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). (deg)
//	command.param5           = 0;	//Latitude (m)
	command.param6           = 0;	//Longitude
//	command.param7           = 0;	//Altitude
    mavlink_msg_command_long_encode(255, 1, &message, &command);
    return write_message(message);
}

int Drone::waypointupdown(float param7)
{
    //Message buffer
	mavlink_message_t message;
    mavlink_command_long_t command;
    command=mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_NAV_WAYPOINT;
    command.confirmation = false;
    command.param1           = 0;  //Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing) min : 0 (seconds)
	command.param2           = 0;	//Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)  min 0 (m)
	command.param3           = 0;	//0 to pass through the WP, if > 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. (m)
	command.param4           = 0;	//Desired yaw angle at waypoint (rotary wing). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). (deg)
//	command.param5           = 0;	//Latitude (m)
//	command.param6           = 0;	//Longitude
	command.param7           = 0;	//Altitude
    mavlink_msg_command_long_encode(255, 1, &message, &command);
    return write_message(message);
}

int Drone::go_to()
{
    //Message buffer
	mavlink_message_t message;
    mavlink_command_long_t command;
    command=mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_DO_REPOSITION;
    command.confirmation = false;
    command.param1           = -1;
	command.param4           = NAN;
	command.param5           = 0;
	command.param6           = 0;
	command.param7           = 1;


    mavlink_msg_command_long_encode(255, 1, &message, &command);

   
    return write_message(message);
}


322
323
324
325
326
327
328
329
330
331

int Drone::return_to_launch(int param1)
{
    //Message buffer
	mavlink_message_t message;
    mavlink_command_long_t command;
    command=mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_NAV_RETURN_TO_LAUNCH;
332
  //  command.param1           = param1;
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355

    mavlink_msg_command_long_encode(255, 1, &message, &command);

    if(param1 >0)
    {
        //Display_IHM::getInstanceOf().printLog("ARMING");
    }else
    {
        //Display_IHM::getInstanceOf().printLog("STOP ARMING");
    }

    return write_message(message);
}

int Drone::take_off() 
{
    //Message buffer
    mavlink_message_t message;
    mavlink_command_long_t command;
	printf("===========================  take_off Demande au drone de monter en altitude \n");
    command = mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
356
    command.command = MAV_CMD_NAV_TAKEOFF;  
357
    command.confirmation = true ;
358
  //  command.param1 = 245;  //Minimum pitch (if airspeed sensor present), desired pitch without sensor
359
360
361
	command.param2 = 1e+06;
	command.param3 = NAN; 
	command.param4 = NAN; //Yaw angle (if magnetometer present), ignored without magnetometer. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).
362
363
364
365
	command.param5 =NAN ;  //global_position_int.lat; // local_position_ned.x;	//Latitude
	command.param6 =NAN; //global_position_int.lon; //local_position_ned.y;    //longitude 
	printf("departure alt = %d \n",departure_alt);
	command.param7 = 1 ; // 10m altitude
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
	
	
    mavlink_msg_command_long_encode(255, 1, &message, &command);
	
	cout <<"param1"<<command.param1<<"param2"<<command.param2<<"param3"<<command.param3<<"param4 "<<command.param4<<"param5 "<<command.param5<<"param6 "<<command.param6<<"param7 "<<command.param7<<endl;



    return  write_message(message);
}
int Drone::take_off_vtol() 
{
    //Message buffer
    mavlink_message_t message;
    mavlink_command_long_t command;
	printf("===========================  take_off Demande au drone de monter en altitude \n");
    command = mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_NAV_VTOL_TAKEOFF;  
    command.confirmation = true ;
   // command.param1 = 0;  //Pitch
	//command.param2 = VTOL_TRANSITION_HEADING;
	//command.param3 = 0;
390
391
	command.param4 = NAN; //YAW
	command.param5 = gps_raw_int.lat;  //global_position_int.lat; // local_position_ned.x;	//Latitude
392
	command.param6 = gps_raw_int.lon; //global_position_int.lon; //local_position_ned.y;    //longitude 
393
394
395
396
397
398
399
400
	printf("departure alt = %d \n",departure_alt);
	command.param7 = departure_alt+1000; // 10m altitude

    mavlink_msg_command_long_encode(255, 1, &message, &command);

    return  write_message(message);
}

401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
int Drone::followhold() 
{
    //Message buffer
    mavlink_message_t message;
    mavlink_command_long_t command;
	printf("===========================  take_off Demande au drone de monter en altitude \n");
    command = mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_DO_FOLLOW;  
    command.confirmation = true ;
    command.param1 = 0;  //Hold mode
	//command.param2 = VTOL_TRANSITION_HEADING;
	//command.param3 = 0;
	command.param4 = 2; //Altitude mode: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home.
	command.param5 = departure_alt+1000; // 10m altitudeAltitude above home. (used if mode=2)
	//command.param6 = gps_raw_int.lon; //global_position_int.lon; //local_position_ned.y;    //longitude 
	printf("departure alt = %d \n",departure_alt);
	command.param7 = 1; //Time to land in which the MAV should go to the default position hold mode after a message RX timeout.

    mavlink_msg_command_long_encode(255, 1, &message, &command);

    return  write_message(message);
}



428
429
430
431
432
433
434
435
436
437
438
439

int Drone::landing() 
{
    //Message buffer
    mavlink_message_t message;
    mavlink_command_long_t command;
	printf("=============================  landing Demande au drone de faire un landing \n");
    command = mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
     command.command = MAV_CMD_NAV_LAND;  
    command.confirmation = true ;
440
441
442
    command.param1 = 1;			//Minimum target altitude if landing is aborted (0 = undefined/use system default).
	command.param2 = 0;			//Precision land mode. //PRECISION_LAND_MODE
	command.param3 = 0;			//Empty
443
444
445
446
	command.param4 = 1.5;		//Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).
	command.param5 = 1;	//Latitude
	command.param6 = 1;	//Longitude
	command.param7 = 10; 	//Landing altitude (ground level in current frame).
447
448
449
450
451

    mavlink_msg_command_long_encode(255, 1, &message, &command);

    return  write_message(message);
}
452
453
454

//============================================TEST=============================================================

455
456


457
458
459
460
461
462
463
464
465
466
467
int Drone::move_to(float param1, float param2, float param3) 
{
	int16_t xx,yy,zz;
	xx=(int16_t)param1; yy=(int16_t)param2; zz=(int16_t)param3;
    //Message buffer
    mavlink_message_t message;
    mavlink_command_long_t command;
	  // printf("Demande au drone de tourner vers la droite \n");
    command = mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
468
    command.command = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED;
469
    command.confirmation = false;
470
    command.param5 = 1;
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486

    mavlink_msg_command_long_encode(255, 1, &message, &command);

   if(param1 >0)
    {
        //Display_IHM::getInstanceOf().printLog("ARMING");
    }else
    {
        //Display_IHM::getInstanceOf().printLog("STOP ARMING");
    }
    return write_message(message);
}

//===============================================================================================================


487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
int Drone::command_right(float param1) 
{
    //Message buffer
    mavlink_message_t message;
    mavlink_command_long_t command;
	  // printf("Demande au drone de tourner vers la droite \n");
    command = mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_FRAME_BODY_FRD;
    command.confirmation = false;
    command.param1 = param1;

    mavlink_msg_command_long_encode(255, 1, &message, &command);

   if(param1 >0)
    {
        //Display_IHM::getInstanceOf().printLog("ARMING");
    }else
    {
507
508
509
510
511
512
        //Display_IHM::getInstanceOf().printLog("STOP ARMING");
    }

    return write_message(message);
}

513
514
515
516
517



int Drone::command_kill(int param1)
{
518
519
520
521
522
523
524
525
    //Message buffer
	mavlink_message_t message;
    mavlink_command_long_t command;

    command=mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_DO_FLIGHTTERMINATION;
526
    command.confirmation = true;
527
528
529
    command.param1           = param1;

    mavlink_msg_command_long_encode(255, 1, &message, &command);
530
531
    if(param1>0)
    {
532
533
534
535
536
537
538
539
        //Display_IHM::getInstanceOf().printLog("KILL MODE");
    }else{
        //Display_IHM::getInstanceOf().printLog("OUT KILL MODE");
    }

    return write_message(message);
}

540
/*int Drone::command_setModeGuided(float param1)
541
{
542
543
544
545
546
547
548
    //Message buffer
	mavlink_message_t message;
    mavlink_command_long_t command;
    command=mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command          = MAV_CMD_NAV_GUIDED_ENABLE;
549
    command.confirmation     = true; //false;
550
551
552
    command.param1           = param1; // flag >0.5 => start, <0.5 => stop

    mavlink_msg_command_long_encode(255, 1, &message, &command);
553
554
    if(param1>0)
    {
555
556
557
558
559
560
561
        //Display_IHM::getInstanceOf().printLog("GUIDED MODE");
    }else{
        //Display_IHM::getInstanceOf().printLog("OUT GUIDED MODE");
    }

    return write_message(message);
}
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
/*
 * set_landing()
{
	// Prepare command for landing
	mavlink_command_long_t com = { 0 };
	com.target_system    = system_id;
	com.target_component = autopilot_id;
	com.command          = MAV_CMD_NAV_LAND;
	com.confirmation     = true;
	com.param1           = (float) flag; // flag >0.5 => start, <0.5 => stop

	// Encode
	mavlink_message_t message;
	mavlink_msg_command_long_encode(system_id, companion_id, &message, &com);

	// Send the message
	int len = serial_port->write_message(message);

	// Done!
	return;
}*/
583

584
585
int Drone::command_directControl(float x, float y, float z, float r)
{
586
	mavlink_message_t message;
587
588
589
	int16_t xx,yy,zz,rr;
	xx=(int16_t)x; yy=(int16_t)y; zz=(int16_t)z; rr=(int16_t)r;
  //  mavlink_msg_manual_control_pack(255, 1, &message, 1, 0, xx, yy, zz, rr);
590
591
592
593
        mavlink_msg_manual_control_pack(255, 1, &message, 1, xx, yy, zz, rr,1); //xx :  Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. 
															//yy : Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. 
															//zz : Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle.
															//rr : Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. 
594
595
596
597
598
599

  cout<<"command_directControl  : "<<xx<<" "<<yy<<" "<<zz<<" "<<rr<<" "<<endl;
  return write_message(message);
// return 1;
}

600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
int Drone::battery_check(float x)
{
	cout<<"current_consumed :"<<battery_status.current_consumed<<endl;
	cout<<"=========================================="<<endl;
	cout<<"energy_consumed :"<<battery_status.energy_consumed<<endl;
	cout<<"=========================================="<<endl;
	cout<<"temperature :"<<battery_status.temperature<<endl;
	cout<<"=========================================="<<endl;
	cout<<"voltages :"<<battery_status.voltages[10]<<endl;
	cout<<"=========================================="<<endl;
	cout<<"current_battery :"<<battery_status.current_battery<<endl;
	cout<<"=========================================="<<endl;
	cout<<"battery_function :"<<battery_status.battery_function<<endl;
	cout<<"=========================================="<<endl;
	cout<<"type :"<<battery_status.type<<endl;
	cout<<"=========================================="<<endl;
	cout<<"battery_remaining :"<<battery_status.battery_remaining<<endl;
	cout<<"=========================================="<<endl;
	cout<<"time_remaining :"<<battery_status.time_remaining<<endl;
	cout<<"=========================================="<<endl;
	cout<<"charge_state :"<<battery_status.charge_state<<endl;

}
int Drone::move_drone_to(float vx, float vy, float vz)
{
	mavlink_message_t message;
	uint8_t system_id = 255;
	uint8_t component_id = 1;
	
	uint32_t time_boot_ms = 1000;
	uint8_t target_system = 1;
	uint8_t target_component = 1;
	uint8_t coordinate_frame = MAV_FRAME_LOCAL_NED; //Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 
	uint16_t mask = 0b0000111111000111; // only speed enabled //itmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored.
	float x =0 ; //	X Position in NED frame in meters 
	float y = 0; // 	Y Position in NED frame in meters 
	float z =0; // 	Z Position in NED frame in meters   (note, altitude is negative in NED) 
	float vvx = vx; //	X velocity in NED frame in meter / s	
	float vvy = vy; //Y velocity in NED frame in meter / s	
	float vvz = vz; //Z velocity in NED frame in meter / s 
	float ax = 0; //X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N 
	float ay = 0; //Y  acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N 
	float az = 0; // Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N 
	float yaw = 1.5; //yaw setpoint in rad 
	float  yaw_rate = 0; //yaw rate setpoint in rad/s 
   mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, &message, time_boot_ms,target_system,target_component, coordinate_frame , mask, x,y,z, vvx, vvy, vvz, ax,ay,az, yaw, yaw_rate);
 //uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
                  //             uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask,
                        //        float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
 // cout<<"command_directControl  : "<<xx<<" "<<yy<<" "<<zz<<" "<<rr<<" "<<endl;
  return write_message(message);
// return 1;
}

int Drone::request_home_position(float x, float y, float z)
{
	mavlink_message_t message;
    mavlink_command_long_t command;
	printf("===========================  REQUEST_HOME_POSITION \n");
    command = mavlink_newCommand();
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_GET_HOME_POSITION;  
    command.confirmation = true ;
   
   
   	printf("===========================  HOME_POSITION_OBTAINED \n");

	
	
}
int Drone::get_home_x(float x)
{
	printf("===========================  X_POSITION \n");
	mavlink_message_t message;
	mavlink_msg_home_position_get_x(&message);
	printf("===========================  X_POSITION_OBTAINED \n");

}

680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730



//static uint8_t mavlink_msg_manual_control_get_target individual autopilot specifications for details.| Empty| Empty| Empty| Empty|  */
//MANUAL_CONTROL
//RC_CHANNELS_OVERRIDE


//   MAV_CMD_SET_GUIDED_SUBMODE_STANDARD=4000, /* This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocites along all three axes.
//   MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate.  Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude|  */
 //  MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty|  */
//ds.command = 213; //MAV_CMD_DO_SET_POSITION_YAW_THRUST;
//   MAV_CMD_NAV_LAND=21, /* Land at location |Abort Alt| Empty| Empty| Desired yaw angle| Latitude| Longitude| Altitude|  */
//   MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty|  */

int Drone::command_left(float param1) 
{
    //Message buffer
    mavlink_message_t message;
    mavlink_command_long_t command;
	// printf("Demande au drone de tourner vers la gauche \n");
    command = mavlink_newCommand();
    command.target_system = (uint8_t) 1;
    command.target_component = (uint8_t) 1;
  //  command.command = MAV_CMD_DO_ORBIT;
    command.confirmation = (uint8_t) 0;
    command.param1 = (int16_t) param1;

    mavlink_msg_command_long_encode(255, 1, &message, &command);

    return  write_message(message);
}



int Drone::command_down(float param1) 
{
    //Message buffer
    mavlink_message_t message;
    mavlink_command_long_t command;
	// printf("Demande au drone de descendre \n");
    command = mavlink_newCommand();
    command.target_system = (uint8_t) 1;
    command.target_component = (uint8_t) 1;
    //command.command = MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT;
    command.confirmation = (uint8_t) 0;
    command.param1 = (int16_t) param1;

    mavlink_msg_command_long_encode(255, 1, &message, &command);

    return  write_message(message);
731
732
}

733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
int Drone::command_pow(float param1) 
{
    //Message buffer
    mavlink_message_t message;
    mavlink_command_long_t command;
	// printf("Demande augmentation de la puissance \n");
    command = mavlink_newCommand();
    command.target_system = (uint8_t) 1;
    command.target_component = (uint8_t) 1;
    //command.command = MAV_CMD_COMPONENT_ARM_DISARM;
    command.confirmation = (uint8_t) 0;
    command.param1 = (int16_t) param1;

    mavlink_msg_command_long_encode(255, 1, &message, &command);
	
    return  write_message(message);
}

//void MockLink::_sendRCChannels(void) 
//{
   // mavlink_message_t   msg;

    // mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
       //                               _vehicleComponentId,
       //                               _mavlinkChannel,
       //                               &msg,
       //                               0,                     // time_boot_ms
       //                               16,                    // chancount
       //                               1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500,   // channel 1-8
       //                               1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500,   // channel 9-16
       //                               UINT16_MAX, UINT16_MAX,
       //                               0);                    // rssi

    //respondWithMavlinkMessage(msg);
// }




772
773
// %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% ? %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

774
775
mavlink_command_long_t Drone::mavlink_newCommand()
{
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
    mavlink_command_long_t com;
    com.target_system = 0;
    com.target_component = 0.;
    com.command = 0;
    com.confirmation = false;
    com.param1=0; 
    com.param2=0; 
    com.param3=0; 
    com.param4=0; 
    com.param5=0; 
    com.param6=0; 
    com.param7=0;
    return com;
}

791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
/*
PARAM_REQUEST_LIST 
Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html

mavlink_param_union_t param;
int32_t integer = 20000;
param.param_int32 = integer;
param.type = MAV_PARAM_TYPE_INT32;

// Then send the param by providing the float bytes to the send function
mavlink_msg_param_set_send(xxx, xxx, param.param_float, param.type, xxx);

??????   mavlink_msg_param_set_send ( 255, 1,  20000, MAV_PARAM_TYPE_INT32, ????)

static inline void mavlink_msg_param_set_send( mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type)
*/
/**
 * @brief Send a param_set message
 * @param chan MAVLink channel to send the message   : 255
 *
 * @param target_system  System ID  : 1 
 * @param target_component  Component ID
 * @param param_id  Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
 * @param param_value  Onboard parameter value
 * @param param_type  Onboard parameter type.
 */


/*
 You need to assign base_mode, main_mode, and sub_mode.
For instance, in order to trigger ‘position’ flight mode, you can use the following pymavlink code. I think that it will be same in dronekit code.

master.mav.command_long_send ( master.target_system, master.target_component, mavutil.mavlink.MAV_CMD_DO_SET_MODE, 0, base_mode, main_mode, sub_mode, 0, 0, 0, 0)

sub_mode is only defined for the AUTO_MOD

master.mav.command_long_send( master.target_system, master.target_component, mavutil.mavlink.MAV_CMD_DO_SET_MODE, 0, 217, 3, 0, 0, 0, 0, 0)
 
    Manual: base_mode:217, main_mode:1, sub_mode:0
    Stabilized: base_mode:209, main_mode:7, sub_mode:0
    Acro: base_mode:209, main_mode:5, sub_mode:0
    Rattitude: base_mode:193, main_mode:8, sub_mode:0
    Altitude: base_mode:193, main_mode:2, sub_mode:0
    Offboard: base_mode:209, main_mode:6, sub_mode:0
    Position: base_mode:209, main_mode:3, sub_mode:0
    Hold: base_mode:217, main_mode:4, sub_mode:3
    Missition: base_mode:157, main_mode:4, sub_mode:4
    Return: base_mode:157, main_mode:4, sub_mode:5
    Follow me: base_mode:157, main_mode:4, sub_mode:8
*/

842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
/*
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
{
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;

    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;

    // Note: the safety flag is not needed in future versions of the PX4 Firmware
    //       but want to be rather safe than sorry.
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
    uint8_t custom_sub_mode = 0;

    switch (flight_mode) {
        case FlightMode::Hold:
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
            break;
        case FlightMode::ReturnToLaunch:
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
            break;
        case FlightMode::Takeoff:
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
            break;
        case FlightMode::Land:
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
            break;
        case FlightMode::Mission:
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
            break;
        case FlightMode::FollowMe:
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
            break;
        case FlightMode::Offboard:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
            break;
        case FlightMode::Manual:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
            break;
        case FlightMode::Posctl:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
            break;
        case FlightMode::Altctl:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
            break;
        case FlightMode::Rattitude:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
            break;
        case FlightMode::Acro:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
            break;
        case FlightMode::Stabilized:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
            break;
        default:
            LogErr() << "Unknown Flight mode.";
            MavlinkCommandSender::CommandLong empty_command{};
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
    }

    MavlinkCommandSender::CommandLong command{};

    command.command = MAV_CMD_DO_SET_MODE;
    command.params.param1 = float(mode);
    command.params.param2 = float(custom_mode);
    command.params.param3 = float(custom_sub_mode);
    command.target_component_id = component_id;

    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
}
*/
//int Drone::command_setMode(Drone_mode my_mode)

 int Drone::command_setMode(Drone_mode my_mode)
916
{
917
918
919
920
921
922
923
924
925
926
927
928
929
930
    const uint8_t flag_safety_armed = MAV_MODE_FLAG_SAFETY_ARMED; // = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
    const uint8_t flag_hitl_enabled = MAV_MODE_FLAG_HIL_ENABLED; // = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;

    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
//	Drone_mode my_mode;
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
    //  but want to be rather safe than sorry.
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
    uint8_t custom_sub_mode = 0;	
    
   FlightMode flight_mode = FlightMode::Hold;
   custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
   
   /*  switch(my_mode)
931
    {
932
        case DRONE_OFF: 
933
934
        //We must reset all value to 0			
            Drone::mode=flight_mode;
935
936
937
938
939
940
941
942
        break;

        case DRONE_MANUAL_DIRECT: 
            if(remote_x!=0 && remote_y!=0 && remote_z!=0 && remote_r!=0){
                ////Display_IHM::getInstanceOf().printLog("Server: command refused");
                //beep();
            }else{
                //Display_IHM::getInstanceOf().printLog("Server: mode manual_direct");
943
                Drone::mode=flight_mode;
944
945
946
947
948
949
            }
        break;

        default:
        break;
    }
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
         return 0;
*/
	
//	FlightMode flight_mode = FlightMode::Hold;

    switch (flight_mode) {
        case FlightMode::Hold:
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
            break;
        case FlightMode::ReturnToLaunch:
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
            break;
        case FlightMode::Takeoff:
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
            break;
        case FlightMode::Land:
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
            break;
        case FlightMode::Mission:
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
            break;
        case FlightMode::FollowMe:
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
            break;
        case FlightMode::Offboard:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
            break;
        case FlightMode::Manual:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
            break;
        case FlightMode::Posctl:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
            break;
        case FlightMode::Altctl:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
            break;
        case FlightMode::Rattitude:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
            break;
        case FlightMode::Acro:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
            break;
        case FlightMode::Stabilized:
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
            break;
        default:
            cout << "Unknown Flight mode.";
        //    MavlinkCommandSender::CommandLong empty_command{};
        //    return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
    }
	mavlink_message_t message;
    mavlink_command_long_t command;
    command = mavlink_newCommand();    
    command.target_system = 1;
    command.target_component = 1;
    command.command = MAV_CMD_DO_SET_MODE;
    command.param1 = float(mode);
    command.param2 = float(custom_mode);
    command.param3 = float(custom_sub_mode);
    //command.command = MAV_CMD_COMPONENT_ARM_DISARM;
    mavlink_msg_command_long_encode(255, 1, &message, &command);
    return  write_message(message);
1012
}
1013

1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030

 //   MavlinkCommandSender::CommandLong command{};

    //Message buffer





  //  return std::make_pair<>(MavlinkCommandSender::Result::Success, command);

///==========================================================================

	
   


1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
1050
1051
/*
toggle_offboard_control( bool flag )
{
	// Prepare command for off-board mode
	mavlink_command_long_t com;
	com.target_system    = system_id;
	com.target_component = autopilot_id;
	com.command          = MAV_CMD_NAV_GUIDED_ENABLE;
	com.confirmation     = true;
	com.param1           = (float) flag; // flag >0.5 => start, <0.5 => stop

	// Encode
	mavlink_message_t message;
	mavlink_msg_command_long_encode(system_id, companion_id, &message, &com);

	// Send the message
	int len = serial_port->write_message(message);

	// Done!
	return len;
}*/