DroneXControllerService.cpp 88.9 KB
Newer Older
1
2
3
//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
//
//    This file is part of D-FaLL-System.
pragash1's avatar
pragash1 committed
4
//
5
6
7
8
//    D-FaLL-System is free software: you can redistribute it and/or modify
//    it under the terms of the GNU General Public License as published by
//    the Free Software Foundation, either version 3 of the License, or
//    (at your option) any later version.
pragash1's avatar
pragash1 committed
9
//
10
11
12
13
//    D-FaLL-System is distributed in the hope that it will be useful,
//    but WITHOUT ANY WARRANTY; without even the implied warranty of
//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
//    GNU General Public License for more details.
pragash1's avatar
pragash1 committed
14
//
15
16
//    You should have received a copy of the GNU General Public License
//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
pragash1's avatar
pragash1 committed
17
//
18
19
20
21
22
23
24
25
26
27
//
//    ----------------------------------------------------------------------------------
//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
//
//
//    DESCRIPTION:
pragash1's avatar
pragash1 committed
28
//    Place for students to implement their controller
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
//
//    ----------------------------------------------------------------------------------





// INCLUDE THE HEADER
#include "nodes/DroneXControllerService.h"





//    ----------------------------------------------------------------------------------
//    FFFFF  U   U  N   N   CCCC  TTTTT  III   OOO   N   N
//    F      U   U  NN  N  C        T     I   O   O  NN  N
//    FFF    U   U  N N N  C        T     I   O   O  N N N
//    F      U   U  N  NN  C        T     I   O   O  N  NN
//    F       UUU   N   N   CCCC    T    III   OOO   N   N
//
//    III M   M PPPP  L     EEEEE M   M EEEEE N   N TTTTT   A   TTTTT III  OOO  N   N
//     I  MM MM P   P L     E     MM MM E     NN  N   T    A A    T    I  O   O NN  N
//     I  M M M PPPP  L     EEE   M M M EEE   N N N   T   A   A   T    I  O   O N N N
//     I  M   M P     L     E     M   M E     N  NN   T   AAAAA   T    I  O   O N  NN
//    III M   M P     LLLLL EEEEE M   M EEEEE N   N   T   A   A   T   III  OOO  N   N
//    ----------------------------------------------------------------------------------
pragash1's avatar
pragash1 committed
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193




// REMINDER OF THE NAME OF USEFUL CLASS VARIABLE
// // > Mass of the Crazyflie quad-rotor, in [grams]
// float m_mass_CF_grams;
// // > Mass of the letters to be lifted, in [grams]
// float m_mass_E_grams;
// float m_mass_T_grams;
// float m_mass_H_grams;
// // > Total mass of the Crazyflie plus whatever it is carrying, in [grams]
// float m_mass_total_grams;
// // Thickness of the object at pick-up and put-down, in [meters]
// // > This should also account for extra height due to
// //   the surface where the object is
// float m_thickness_of_object_at_pickup;
// float m_thickness_of_object_at_putdown;
// // (x,y) coordinates of the pickup location
// std::vector<float> m_pickup_coordinates_xy(2);
// // (x,y) coordinates of the drop off location
// std::vector<float> m_dropoff_coordinates_xy_for_E(2);
// std::vector<float> m_dropoff_coordinates_xy_for_T(2);
// std::vector<float> m_dropoff_coordinates_xy_for_H(2);
// // Length of the string from the Crazyflie
// // to the end of the DroneX, in [meters]
// float m_dronex_string_length;
// // > The setpoints for (x,y,z) position and yaw angle, in that order
// float m_setpoint[4] = {0.0,0.0,0.4,0.0};
// float m_setpoint_for_controller[4] = {0.0,0.0,0.4,0.0};
// // > Small adjustments to the x-y setpoint
// float m_xAdjustment = 0.0f;
// float m_yAdjustment = 0.0f;
// // Boolean for whether to limit rate of change of the setpoint
// bool m_shouldSmoothSetpointChanges = true;
// // Max setpoint change per second
// float m_max_setpoint_change_per_second_horizontal;
// float m_max_setpoint_change_per_second_vertical;
// float m_max_setpoint_change_per_second_yaw_degrees;
// float m_max_setpoint_change_per_second_yaw_radians;
// // Frequency at which the controller is running
// float m_vicon_frequency;


// A FEW EXTRA COMMENTS ABOUT THE MOST IMPORTANT VARIABLES

// Variable name:    m_setpoint
// Description:
// This is a float array of length 4. It specifies a location
// in space where you want the drone to be. The 4 element are:
// >> m_setpoint[0]   The x-poistion in [meters]
// >> m_setpoint[1]   The y-poistion in [meters]
// >> m_setpoint[2]   The z-poistion in [meters]
// >> m_setpoint[3]   The yaw heading angle in [radians]


// Variable name:    m_setpoint_for_controller
// Description:
// Similar to the variable "m_setpoint" this is also float array
// of length 4 that specifies an (x,y,z,yaw) location. The
// difference it that this variable specifies the location where
// the low-level controller is guiding the drone to be.
// HINT: to make changes the "m_setpoint" variable, you can edit
// the function named "perControlCycleOperations" so that the
// "m_setpoint_for_controller" changes by a maximum amount at
// each cycle of the contoller



// THIS FUNCTION IS CALLED AT "m_vicon_frequency" HERTZ.
// IT CAN BE USED TO ADJUST THINGS IN "REAL TIME".
// For example, the equation:
// >> m_max_setpoint_change_per_second_horizontal / m_vicon_frequency
// will convert the "change per second" to a "change per cycle".

void perControlCycleOperations()
{
	if (m_shouldSmoothSetpointChanges)
	{
		for(int i = 0; i < 4; ++i)
		{
			float max_for_this_coordinate;
			// FILLE IN THE STATE INERTIAL ESTIMATE TO BE USED FOR CONTROL
			switch (i)
			{
				case 0:
					max_for_this_coordinate = m_max_setpoint_change_per_second_horizontal / m_vicon_frequency;
					break;
				case 1:
					max_for_this_coordinate = m_max_setpoint_change_per_second_horizontal / m_vicon_frequency;
					break;
				case 2:
					max_for_this_coordinate = m_max_setpoint_change_per_second_vertical / m_vicon_frequency;
					break;
				case 3:
					max_for_this_coordinate = m_max_setpoint_change_per_second_yaw_radians / m_vicon_frequency;
					break;
				// Handle the exception
				default:
					max_for_this_coordinate = 0.0f;
					break;
			}

			// Compute the difference in setpoint
			float setpoint_difference = m_setpoint[i] - m_setpoint_for_controller[i];

			// Clip the difference to the maximum
			if (setpoint_difference > max_for_this_coordinate)
			{
				setpoint_difference = max_for_this_coordinate;
			}
			else if (setpoint_difference < -max_for_this_coordinate)
			{
				setpoint_difference = -max_for_this_coordinate;
			}

			// Update the setpoint of the controller
			m_setpoint_for_controller[i] += setpoint_difference;
		}

	}
	else
	{
		m_setpoint_for_controller[0] = m_setpoint[0];
		m_setpoint_for_controller[1] = m_setpoint[1];
		m_setpoint_for_controller[2] = m_setpoint[2];
		m_setpoint_for_controller[3] = m_setpoint[3];
	}
}








void buttonPressed_take_off(){
pragash1's avatar
pragash1 committed
194

195
	//if(flying_state == DRONEX_STATE_GROUND || flying_state == DRONEX_STATE_ON_MOTHERSHIP){
pragash1's avatar
pragash1 committed
196
197
		ROS_INFO("[DRONEX CONTROLLER-DroneXControllerService] Taking off...");
		flying_state = DRONEX_STATE_TAKING_OFF;
198
199
200
	//}else{
	//	ROS_ERROR("Cannot change to DRONEX_STATE_TAKING_OFF");
	//}
pragash1's avatar
pragash1 committed
201
202
203
}

void buttonPressed_land(){
204
	//if(flying_state == DRONEX_STATE_HOVER){
mastefan's avatar
mastefan committed
205
206
		ROS_INFO("[DRONEX CONTROLLER-DroneXControllerService] Start flight-sequence LA...");
		// OLD:flying_state = DRONEX_STATE_LAND_ON_MOTHERSHIP;
207
		// NEW:
208
		flightSequence = SEQUENCE_LAND_ON_MOTHERSHIP;
pragash1's avatar
pragash1 committed
209
210
}

pragash1's avatar
pragash1 committed
211
212
213
void buttonPressed_abort(){
	ROS_INFO("[DRONEX CONTROLLER-DroneXControllerService] Abort Mission!");
	flying_state = DRONEX_STATE_LAND_ON_GROUND;
mastefan's avatar
mastefan committed
214
215
216

	// reset start position
	savedStartCoordinates = false;
pragash1's avatar
pragash1 committed
217
218
}

219
220
void buttonPressed_integrator_on(){
	ROS_INFO("[DRONEX CONTROLLER-DroneXControllerService] Turn ON integrator");
maruggv's avatar
maruggv committed
221
	integratorFlag = DRONEX_INTEGRATOR_ON;
222
223
224
225
}

void buttonPressed_integrator_off(){
	ROS_INFO("[DRONEX CONTROLLER-DroneXControllerService] Turn OFF integrator");
maruggv's avatar
maruggv committed
226
	integratorFlag = DRONEX_INTEGRATOR_OFF;
227
228
229
230
}

void buttonPressed_integrator_reset(){
	ROS_INFO("[DRONEX CONTROLLER-DroneXControllerService] RESET integrator to zero");
maruggv's avatar
maruggv committed
231
	integratorFlag = DRONEX_INTEGRATOR_RESET;
232
233
}

234
235
236
237
238
239
240
241
242

void buttonPressed_follow_trajectory(){
	ROS_INFO("[DRONEX CONTROLLER-DroneXControllerService] FOLLOW trajectory");
	flightSequence = SEQUENCE_NONE;
	flying_state = DRONEX_FOLLOW_TRAJECTORY;
	total_time_since_start = 0;
	trajectory_x_radius = 0;
	trajectory_y_radius = 0;
	trajectory_start_time = ros::Time::now().toSec();
mastefan's avatar
mastefan committed
243
	ROS_INFO_STREAM("trajectory start time: " << trajectory_start_time);
244
245
246
247
248
249
250
251
252
253
254
255
256
257
}


void buttonPressed_reset(){
	ROS_INFO("[DRONEX CONTROLLER-DroneXControllerService] RESET");

}







258
void integratorCallback (const Setpoint& integrParams ) {
259
260
261
    integrator_sum_XYZ[0] = integrParams.x;
    integrator_sum_XYZ[1] = integrParams.y;
    integrator_sum_XYZ[2] = integrParams.z;
262
263
}

264
265
266
267
268
269
270
void WeightParamCallback (const Setpoint& weightParam ) {
    // TODO for changing yaml: set weight in yaml OR just set m_mass_CF_grams?
    // m_mass_CF_grams = weightParam.x;

}

void PitchBaselineParamCallback(const Setpoint& pitchAngleParam ) {
271
    // TODO
272
273
274
}


275
276


pragash1's avatar
pragash1 committed
277
278


279
280
281
282
283
284





//    ------------------------------------------------------------------------------
pragash1's avatar
pragash1 committed
285
//     OOO   U   U  TTTTT  EEEEE  RRRR
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
//    O   O  U   U    T    E      R   R
//    O   O  U   U    T    EEE    RRRR
//    O   O  U   U    T    E      R  R
//     OOO    UUU     T    EEEEE  R   R
//
//     CCCC   OOO   N   N  TTTTT  RRRR    OOO   L           L       OOO    OOO   PPPP
//    C      O   O  NN  N    T    R   R  O   O  L           L      O   O  O   O  P   P
//    C      O   O  N N N    T    RRRR   O   O  L           L      O   O  O   O  PPPP
//    C      O   O  N  NN    T    R  R   O   O  L           L      O   O  O   O  P
//     CCCC   OOO   N   N    T    R   R   OOO   LLLLL       LLLLL   OOO    OOO   P
//    ----------------------------------------------------------------------------------

// This function is the callback that is linked to the "DroneXController" service that
// is advertised in the main function. This must have arguments that match the
// "input-output" behaviour defined in the "Controller.srv" file (located in the "srv"
// folder)
//
// The arument "request" is a structure provided to this service with the following two
// properties:
// request.ownCrazyflie
// This property is itself a structure of type "CrazyflieData",  which is defined in the
// file "CrazyflieData.msg", and has the following properties
// string crazyflieName
//     float64 x                         The x position of the Crazyflie [metres]
//     float64 y                         The y position of the Crazyflie [metres]
//     float64 z                         The z position of the Crazyflie [metres]
//     float64 roll                      The roll component of the intrinsic Euler angles [radians]
//     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
//     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
// The values in these properties are directly the measurement taken by the Vicon
// motion capture system of the Crazyflie that is to be controlled by this service
//
// request.otherCrazyflies
// This property is an array of "CrazyflieData" structures, what allows access to the
// Vicon measurements of other Crazyflies.
//
// The argument "response" is a structure that is expected to be filled in by this
// service by this function, it has only the following property
// response.ControlCommand
// This property is iteself a structure of type "ControlCommand", which is defined in
// the file "ControlCommand.msg", and has the following properties:
//     float32 roll                      The command sent to the Crazyflie for the body frame x-axis
//     float32 pitch                     The command sent to the Crazyflie for the body frame y-axis
//     float32 yaw                       The command sent to the Crazyflie for the body frame z-axis
//     uint16 motorCmd1                  The command sent to the Crazyflie for motor 1
//     uint16 motorCmd2                  The command sent to the Crazyflie for motor 1
//     uint16 motorCmd3                  The command sent to the Crazyflie for motor 1
//     uint16 motorCmd4                  The command sent to the Crazyflie for motor 1
//     uint8 onboardControllerType       The flag sent to the Crazyflie for indicating how to implement the command
pragash1's avatar
pragash1 committed
337
//
338
339
// IMPORTANT NOTES FOR "onboardControllerType"  AND AXIS CONVENTIONS
// > The allowed values for "onboardControllerType" are in the "Defines" section at the
pragash1's avatar
pragash1 committed
340
341
342
343
344
//   top of this file, they are:
//   CF_COMMAND_TYPE_MOTOR
//   CF_COMMAND_TYPE_RATE
//   CF_COMMAND_TYPE_ANGLE.
// > With CF_COMMAND_TYPE_RATE the ".roll", ".ptich", and ".yaw" properties of "response.ControlCommand"
345
346
//   specify the angular rate in [radians/second] that will be requested from the
//   PID controllers running in the Crazyflie 2.0 firmware.
pragash1's avatar
pragash1 committed
347
// > With CF_COMMAND_TYPE_RATE the ".motorCmd1" to ".motorCmd4" properties of "response.ControlCommand"
348
349
350
//   are the baseline motor commands requested from the Crazyflie, with the adjustment
//   for body rates being added on top of this in the firmware (i.e., as per the code
//   of the "distribute_power" function provided in exercise sheet 2).
pragash1's avatar
pragash1 committed
351
// > With CF_COMMAND_TYPE_RATE the axis convention for the roll, pitch, and yaw body rates returned
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
//   in "response.ControlCommand" should use right-hand coordinate axes with x-forward
//   and z-upwards (i.e., the positive z-axis is aligned with the direction of positive
//   thrust). To assist, teh following is an ASCII art of this convention:
//
// ASCII ART OF THE CRAZYFLIE 2.0 LAYOUT
//
//  > This is a top view,
//  > M1 to M4 stand for Motor 1 to Motor 4,
//  > "CW"  indicates that the motor rotates Clockwise,
//  > "CCW" indicates that the motor rotates Counter-Clockwise,
//  > By right-hand axis convention, the positive z-direction points our of the screen,
//  > This being a "top view" means tha the direction of positive thrust produced
//    by the propellers is also out of the screen.
//
//        ____                         ____
//       /    \                       /    \
//  (CW) | M4 |           x           | M1 | (CCW)
//       \____/\          ^          /\____/
//            \ \         |         / /
//             \ \        |        / /
//              \ \______ | ______/ /
//               \        |        /
//                |       |       |
//        y <-------------o       |
//                |               |
//               / _______________ \
//              / /               \ \
//             / /                 \ \
//        ____/ /                   \ \____
//       /    \/                     \/    \
// (CCW) | M3 |                       | M2 | (CW)
//       \____/                       \____/
//
//
//
// This function WILL NEED TO BE edited for successful completion of the PPS exercise
bool calculateControlOutput(Controller::Request &request, Controller::Response &response)
{

pragash1's avatar
pragash1 committed
391
392
393
	// Keep track of time
	m_time_ticks++;
	m_time_seconds = float(m_time_ticks) / m_vicon_frequency;
394

395

396
397


398
399
	switch(flying_state){
		case DRONEX_STATE_APPROACH:
400
		{
mastefan's avatar
mastefan committed
401
			//ROS_INFO("DRONEX_STATE_APPROACH");
402
403
			dronexSetpoint.x = request.otherCrazyflies[0].x;
			dronexSetpoint.y = request.otherCrazyflies[0].y;
mastefan's avatar
mastefan committed
404
			dronexSetpoint.z = request.otherCrazyflies[0].z + 0.4;//0.6;
mastefan's avatar
mastefan committed
405

406

407
408
409
			ROS_INFO_STREAM("APPROACH: (x,y,z) Difference: ("
				<< request.ownCrazyflie.x-dronexSetpoint.x << ", "
				<< request.ownCrazyflie.y-dronexSetpoint.y << ", "
410
411
				<< request.ownCrazyflie.z-dronexSetpoint.z << ")");

412
413
			if(abs(request.ownCrazyflie.x-dronexSetpoint.x) < tol_approach[0] && abs(request.ownCrazyflie.y-dronexSetpoint.y) < tol_approach[1] &&
				abs(request.ownCrazyflie.z-dronexSetpoint.z) < tol_approach[2] ){
mastefan's avatar
mastefan committed
414
415
416
				approachedFlag = true;
				ROS_INFO("approached");
			}
417
			//setpointCallback(dronexSetpoint);
418
		}
419
420
		break;

421
		case DRONEX_STATE_GROUND:
422
		{
mastefan's avatar
mastefan committed
423
424
			//ROS_INFO("DRONEX_STATE_GROUND");
			// Variable for choosing flight sequence off
425
			flightSequence = SEQUENCE_NONE;
mastefan's avatar
mastefan committed
426
427
428
429
430
431
432
433
434
435

			// Flags of landing sequence reset
			tookOffFlag = false;
			approachedFlag = false;
			//bool landedFlag = true;

			dronexSetpoint.x = request.ownCrazyflie.x;
			dronexSetpoint.y = request.ownCrazyflie.y;
			dronexSetpoint.z = request.ownCrazyflie.z;

436
437
		}
		break;
438

mastefan's avatar
mastefan committed
439
440
441
442
		case DRONEX_STATE_ON_MOTHERSHIP:
		{
			//ROS_INFO("DRONEX_STATE_ON_MOTHERSHIP");
			// Variable for choosing flight sequence off
443
			flightSequence = SEQUENCE_NONE;
mastefan's avatar
mastefan committed
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458

			// Flags of landing sequence reset
			tookOffFlag = false;
			approachedFlag = false;
			//bool landedFlag = true;

			dronexSetpoint.x = request.ownCrazyflie.x;
			dronexSetpoint.y = request.ownCrazyflie.y;
			dronexSetpoint.z = request.ownCrazyflie.z;

		}
		break;

		case DRONEX_STATE_LAND_ON_MOTHERSHIP:
		{
459
			//ROS_INFO("DRONEX_STATE_LAND_ON_MOTHERSHIP");
mastefan's avatar
mastefan committed
460
461
462
			//to land on mothership (17.10. vm)
			dronexSetpoint.x = request.otherCrazyflies[0].x;	//set setpoint to droneX x y and z coordinates
			dronexSetpoint.y = request.otherCrazyflies[0].y;
463
			dronexSetpoint.z = request.otherCrazyflies[0].z + 0.05;
mastefan's avatar
mastefan committed
464
465
466
		}
		break;

pragash1's avatar
pragash1 committed
467
		case DRONEX_STATE_LAND_ON_GROUND:
468
		{
469
			if(tookOffFlag){
470
				ROS_INFO("DRONEX_STATE_LAND_ON_GROUND");
471
				// to land on ground (17.10. vm)
mastefan's avatar
mastefan committed
472
473
				dronexSetpoint.x = request.ownCrazyflie.x;
				dronexSetpoint.y = request.ownCrazyflie.y;
474
475
476
477
				dronexSetpoint.z = 0.0;

				tookOffFlag = false;
			}
pragash1's avatar
pragash1 committed
478

479
480
		}
		break;
mastefan's avatar
mastefan committed
481

482
		case DRONEX_STATE_TAKING_OFF:
483
		{
mastefan's avatar
mastefan committed
484
			//ROS_INFO_STREAM("DRONEX_STATE_TAKING_OFF");
pragash1's avatar
pragash1 committed
485

mastefan's avatar
mastefan committed
486
487
			if(!savedStartCoordinates)
			{
mastefan's avatar
mastefan committed
488
489
				startCoordinateX = request.ownCrazyflie.x; // Nöd sicher öbs das brucht. Idee: Afangscoordinate abspeichere zum in Hover state z ende.
				startCoordinateY = request.ownCrazyflie.y;
mastefan's avatar
mastefan committed
490
				startCoordinateZ = request.ownCrazyflie.z;
491

mastefan's avatar
mastefan committed
492
493
				savedStartCoordinates = true;
				//setpointCallback(dronexSetpoint);
mastefan's avatar
mastefan committed
494
495
496
497
				ROS_INFO_STREAM("DRONEX: saved start Coordinates");
				ROS_INFO_STREAM("x = " << startCoordinateX);
				ROS_INFO_STREAM("y = " << startCoordinateY);
				ROS_INFO_STREAM("z = " << startCoordinateZ);
498

mastefan's avatar
mastefan committed
499
500
501
			}

			dronexSetpoint.x = startCoordinateX;
502
			dronexSetpoint.y = startCoordinateY;
503
			dronexSetpoint.z = startCoordinateZ + 0.4;
504
505
506
507

			ROS_INFO_STREAM("TO: (x,y,z) Difference: ("
				<< request.ownCrazyflie.x-dronexSetpoint.x << ", "
				<< request.ownCrazyflie.y-dronexSetpoint.y << ", "
508
				<< request.ownCrazyflie.z-dronexSetpoint.z << ")");
mastefan's avatar
mastefan committed
509

510
511
			if(abs(request.ownCrazyflie.x-dronexSetpoint.x) < tol_takeoff[0] && abs(request.ownCrazyflie.y-dronexSetpoint.y) < tol_takeoff[1] &&
				abs(request.ownCrazyflie.z-dronexSetpoint.z) < tol_takeoff[2]) {
mastefan's avatar
mastefan committed
512
513
				ROS_INFO("took off");
				tookOffFlag = true;
514
515

				ROS_INFO_STREAM("Entering: DRONEX_STATE_HOVER");
mastefan's avatar
mastefan committed
516
				flying_state = DRONEX_STATE_HOVER;
mastefan's avatar
mastefan committed
517
			}
518
519
520
		}
		break;

mastefan's avatar
mastefan committed
521
		case DRONEX_STATE_HOVER:
522
		{
523
			//ROS_INFO_STREAM("DRONEX_STATE_HOVER");
mastefan's avatar
mastefan committed
524
525
526
527
528
529
			// keep setpoint constant
			/*
			dronexSetpoint.x = dronexSetpoint.x;
			dronexSetpoint.y = dronexSetpoint.y;
			dronexSetpoint.z = dronexSetpoint.z;
			*/
530
531
		}
		break;
mastefan's avatar
mastefan committed
532

533
534
535
536
537
		case DRONEX_FOLLOW_TRAJECTORY:

		break;


538
	} // END switch case
539

mastefan's avatar
mastefan committed
540

541
542


543
	// flightSeqeunce 1: simple approaching and landing on static mothership
544
	if (flightSequence == SEQUENCE_LAND_ON_MOTHERSHIP){
545
		//ROS_INFO_STREAM("Entering: DRONEX_STATE_TAKING_OFF");
mastefan's avatar
mastefan committed
546
		flying_state = DRONEX_STATE_TAKING_OFF;
547

548
549
		//ROS_INFO_STREAM("Flight sequence: Landing on mothership");
		if(tookOffFlag){
550
			//ROS_INFO_STREAM("Entering: DRONEX_STATE_APPROACH");
551
552
553
			flying_state = DRONEX_STATE_APPROACH;

			if(approachedFlag){
554
				ROS_INFO_STREAM("Entering: DRONEX_STATE_LAND_ON_MOTHERSHIP");
555
				flying_state = DRONEX_STATE_LAND_ON_MOTHERSHIP;
mastefan's avatar
mastefan committed
556
557
			}

558
559
		}

560
	}
561

562
/*
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
	// flightSequence 2: approach and land with velocity optimized controller
	// TODO: define SEQUENCE names in .h (maybe rename sequences)
	if (flightSequence == SEQUENCE_2){
		flying_state = DRONEX_STATE_TAKING_OFF;

		if (tookOffFlag){
			// TODO:
			// approach landing zone: maybe a point "behind" the mothership in some angle
			// maybe turn to yaw so that CF points to mothership
			// -> in DRONEX_STATE_APPROACH or own function

			if (approachedFlag){
				// TODO:
				// turn on velocity optimized controller
				// land and turn off motors, when velocity and position requirements met
				// -> define i.e. tol_velocity, tol_land[3]
			}
		}

	}
583
*/
584
585
586

	calculateDroneXVelocity(request);

587
588
	setpointCallback(dronexSetpoint);

589
590
591
	/*dronexSetpoint.x = request.otherCrazyflies[0].x;
	dronexSetpoint.y = request.otherCrazyflies[0].y;
	dronexSetpoint.z = request.otherCrazyflies[0].z + 0.3*/
592

593
	//setpointCallback(dronexSetpoint);
pragash1's avatar
pragash1 committed
594
	// CALL THE FUNCTION FOR PER CYLCE OPERATIONS
pragash1's avatar
pragash1 committed
595

596
	perControlCycleOperations();
pragash1's avatar
pragash1 committed
597

pragash1's avatar
pragash1 committed
598
599
600
601
	// THIS IS THE START OF THE "OUTER" CONTROL LOOP
	// > i.e., this is the control loop run on this laptop
	// > this function is called at the frequency specified
	// > this function performs all estimation and control
602
603


pragash1's avatar
pragash1 committed
604
605
606
607
608
	// PERFORM THE ESTIMATOR UPDATE FOR THE INTERIAL FRAME STATE
	// > After this function is complete the class variable
	//   "current_stateInertialEstimate" is updated and ready
	//   to be used for subsequent controller copmutations
	performEstimatorUpdate_forStateInterial(request);
609
610


611

612
613
614



pragash1's avatar
pragash1 committed
615
616
	// CARRY OUT THE CONTROLLER COMPUTATIONS
	// Call the function that performs the control computations for this mode
617

618
	// Turn motors off if wanted or do LQR-control
619

mastefan's avatar
mastefan committed
620
	if(flying_state == DRONEX_STATE_LAND_ON_GROUND && (request.ownCrazyflie.z < 0.05 )){
mastefan's avatar
mastefan committed
621
622
		ROS_INFO("landed -> DRONEX_STATE_ON_GROUND");
		flying_state = DRONEX_STATE_GROUND;
623
	}
624
	else if(flying_state == DRONEX_STATE_LAND_ON_MOTHERSHIP && 	(abs(request.ownCrazyflie.x - request.otherCrazyflies[0].x) < tol_land[0]) &&
625
																(abs(request.ownCrazyflie.y - request.otherCrazyflies[0].y) < tol_land[1]) &&
626
																(abs(request.ownCrazyflie.z - 0.03 - request.otherCrazyflies[0].z) < tol_land[2]) ){
mastefan's avatar
mastefan committed
627
628
		ROS_INFO("landed -> DRONEX_STATE_ON_MOTHERSHIP");
		flying_state = DRONEX_STATE_ON_MOTHERSHIP;
629
	}
mastefan's avatar
mastefan committed
630
631

	if(flying_state == DRONEX_STATE_GROUND || flying_state == DRONEX_STATE_ON_MOTHERSHIP){
632
633
634
		motorsOFF(response);
	}
	else{
635
		calculateControlOutputDroneX(request, response);
636
637
638
639
640

		// for debugging:
		/*ROS_INFO_STREAM("deltaX to Mothership: " << request.ownCrazyflie.x - request.otherCrazyflies[0].x);
		ROS_INFO_STREAM("deltaY to Mothership: " << request.ownCrazyflie.y - request.otherCrazyflies[0].y);
		ROS_INFO_STREAM("deltaZ to Mothership: " << request.ownCrazyflie.z - request.otherCrazyflies[0].z);*/
pragash1's avatar
pragash1 committed
641
	}
pragash1's avatar
pragash1 committed
642
643
644
645


	// PUBLISH THE CURRENT X,Y,Z, AND YAW (if required)
	if (shouldPublishCurrent_xyz_yaw)
646
	{
pragash1's avatar
pragash1 committed
647
		publish_current_xyz_yaw(request.ownCrazyflie.x,request.ownCrazyflie.y,request.ownCrazyflie.z,request.ownCrazyflie.yaw);
648
649
	}

pragash1's avatar
pragash1 committed
650
651
652
653
654
	// PUBLISH THE DEBUG MESSAGE (if required)
	if (shouldPublishDebugMessage)
	{
		construct_and_publish_debug_message(request,response);
	}
655

mastefan's avatar
mastefan committed
656

pragash1's avatar
pragash1 committed
657
658
659
	// RETURN "true" TO INDICATE THAT THE COMPUTATIONS WERE SUCCESSFUL
	return true;
}
660

661
662
663
664
void crazyfliecontextRefresh(d_fall_pps::CrazyflieContext context){
	area = context.localArea;
	originX = (area.xmin + area.xmax) / 2.0;
	originY = (area.ymin + area.ymax) / 2.0;
665

666
667
	ROS_INFO_STREAM("New OriginX: " << originX << " New OriginY: " << originY);
}
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684


//	State Error Body
//	1)	x Error
//	2)	y Error
//	3)	z Error
//	4)	x dot Error
//	5)	y dot Error
//	6)	z dot Error
//	7)	Roll
//	8)	Pitch
//	9)	yaw
//	10)	Roll dot
//	11)	Pitch dot
//	12)	Yaw dot


685
686
687
// DroneX Controller
void calculateControlOutputDroneX(Controller::Request &request, Controller::Response &response){

688

689
690
691
692
693
694
695
696
697
698
699
700
701


	if(controller_mode == 0){
		// CONVERT THE CURRENT INERTIAL FRAME STATE ESTIMATE, INTO
		// THE BODY FRAME ERROR REQUIRED BY THE CONTROLLER
		// > Define a local array to fill in with the body frame error
		float current_bodyFrameError[12];
		// > Call the function to perform the conversion



		convert_stateInertial_to_bodyFrameError(current_stateInertialEstimate, m_setpoint_for_controller, current_bodyFrameError);

702
		integrator_XYZ(current_bodyFrameError);
703
		calculateControlOutput_viaLQRforRates(current_bodyFrameError,request,response);
704
705
	}else if(controller_mode == 1){

706
707
708
709
710
711
712
713



		// LQR for Angles

		// Read Mothership coordinates
		// x,y,z,yaw
		float ms_coordinates[4];
714
715
716
717
		/*ms_coordinates[0] = request.otherCrazyflies[0].x;
		ms_coordinates[1] = request.otherCrazyflies[0].y;
		ms_coordinates[2] = request.otherCrazyflies[0].z;
		ms_coordinates[3] = request.otherCrazyflies[0].yaw;*/
718

719
		/*ms_coordinates[0] = dronexSetpoint.x;
720
721
		ms_coordinates[1] = dronexSetpoint.y;
		ms_coordinates[2] = dronexSetpoint.z;
722
723
724
725
726
		ms_coordinates[3] = request.otherCrazyflies[0].yaw;*/

		ms_coordinates[0] = m_setpoint_for_controller[0];
		ms_coordinates[1] = m_setpoint_for_controller[1];
		ms_coordinates[2] = m_setpoint_for_controller[2];
727
		ms_coordinates[3] = request.otherCrazyflies[0].yaw;
728
729
730
731
732

		// Load Mothership velocity
		// x dot, y dot, z dot
		float ms_velocity[3];
		ms_velocity[0] = drone_X_vel[0];
733
		ms_velocity[1] = drone_X_vel[1];
734
		ms_velocity[2] = drone_X_vel[2];
735

736
737
738
739
740
741
742


		// CONVERT THE CURRENT INERTIAL FRAME STATE ESTIMATE, INTO
		// THE BODY FRAME ERROR REQUIRED BY THE CONTROLLER
		// > Define a local array to fill in with the body frame error
		float stateErrorBody[12];
		// > Call the function to perform the conversion
743
		convert_stateInertial_to_bodyFrameError(current_stateInertialEstimate, ms_coordinates, stateErrorBody);
744

745
746
747
748

		float rollAngle_forResponse = 0;
		float pitchAngle_forResponse = 0;
		float thrustAdjustment = 0;
749

750
751
752
		// TODO: Do not forget to implement the yawController
		float yawAngle_forResponse = 0;

753
754
755

		integrator_XYZ(stateErrorBody);

756
		// integrator
757

758
759
760
761
762
763
		// BODY FRAME Y CONTROLLER
		rollAngle_forResponse  -= gainIntegratorAngle[0] * integrator_sum_XYZ[1];
		// BODY FRAME X CONTROLLER
		pitchAngle_forResponse -= gainIntegratorAngle[1] * integrator_sum_XYZ[0];
		// > ALITUDE CONTROLLER (i.e., z-controller):
		thrustAdjustment       -= gainIntegratorAngle[2] * integrator_sum_XYZ[2];
764

765

766
767
768
		// Perform the "-Kx" LQR computation for the rates and thrust:
		for(int i = 0; i < 6; ++i){
			// BODY FRAME Y CONTROLLER
mastefan's avatar
mastefan committed
769
			rollAngle_forResponse -= 1.1*gainMatrixRollAngle[i] * stateErrorBody[i];
770
			// BODY FRAME X CONTROLLER
mastefan's avatar
mastefan committed
771
			pitchAngle_forResponse -= 1.1*gainMatrixPitchAngle[i] * stateErrorBody[i];
772
			// BODY FRAME X CONTROLLER
773
			//thrustAdjustment -= gainMatrixThrust_SixStateVector[i] * stateErrorBody[i];
774
775
776

		}

mastefan's avatar
mastefan committed
777
		// Calculate the angle in x-y plane of DroneX for transformation to local coordinates
778
779
		float droneXAngle;
		float ms_velocity_norm = sqrt(pow(ms_velocity[0], 2.0) + pow(ms_velocity[1], 2.0)); //(ms_velocity[0])^2 * (ms_velocity[1])^2);
mastefan's avatar
mastefan committed
780
781
782
783

		if(ms_velocity_norm != 0){
			if (ms_velocity[1] >= 0)
			{
784
				droneXAngle = acos(ms_velocity[0] / ms_velocity_norm);
mastefan's avatar
mastefan committed
785
			}else{
786
				droneXAngle = -acos(ms_velocity[0] / ms_velocity_norm);
mastefan's avatar
mastefan committed
787
788
			}
		}
789

790
		// Calculcate Roll and Pitch Baseline, which comes from the moving mothership
mastefan's avatar
mastefan committed
791
792
		float rollAngle_baseline = 1;
		float pitchAngle_baseline = 1;
793
794

		// TODO
mastefan's avatar
mastefan committed
795
796
		rollAngle_forResponse += rollAngle_baseline * (cos(droneXAngle) * ms_velocity[0]- sin(droneXAngle) * ms_velocity[1]);
		pitchAngle_forResponse += pitchAngle_forResponse * (sin(droneXAngle) * ms_velocity[0] + cos(droneXAngle) * ms_velocity[1]);
797
798
799


		// Calculate the Force Feedforward
800
		float F_in_newtons = (gravity * m_mass_total_grams)/(cos(rollAngle_forResponse)*cos(pitchAngle_forResponse)*1000.0);
801
802
803
804
805
806
807
808
809
810




		// LQR for Rates
		// Calculate the Roll and Pitch Angle error

		float AngleError[3] = {
			stateErrorBody[6] - rollAngle_forResponse,
			stateErrorBody[7] - pitchAngle_forResponse,
811
			stateErrorBody[8]
812
813
814
815
816
817
818
819
820
821
822
		};

		float rollRate_forResponse = 0;
		float pitchRate_forResponse = 0;
		float yawRate_forResponse = 0;
		for(int i = 0; i < 4; i++){
			rollRate_forResponse -= gainMatrixRollRatefromAngle[i] * AngleError[i];
			pitchRate_forResponse -= gainMatrixPitchRatefromAngle[i] * AngleError[i];
			yawRate_forResponse -= gainMatrixYawRatefromAngle[i] * AngleError[i];
		}

mastefan's avatar
mastefan committed
823
		/*for(int i = 0; i < 9; ++i){
824
			thrustAdjustment      -= gainMatrixThrust_NineStateVector[i] * stateErrorBody[i];
mastefan's avatar
mastefan committed
825
826
827
828
		}*/

		for(int i = 0; i < 6; ++i){
			thrustAdjustment      -= gainMatrixThrust_SixStateVector[i] * stateErrorBody[i];
829
830
		}

mastefan's avatar
mastefan committed
831

832
833
834
835
836
		//thrustAdjustment -= F;


		// UPDATE THE "RETURN" THE VARIABLE NAMED "response"

837
838
839
840
841
842
843
844
845
846
847
		// Put the computed rates and thrust into the "response" variable
		// > For roll, pitch, and yaw:
		response.controlOutput.roll  = rollRate_forResponse;
		response.controlOutput.pitch = pitchRate_forResponse;
		response.controlOutput.yaw   = yawRate_forResponse;
		// > For the thrust adjustment we must add the feed-forward thrust to counter-act gravity.
		// > NOTE: remember that the thrust is commanded per motor, so you sohuld
		//         consider whether the "thrustAdjustment" computed by your
		//         controller needed to be divided by 4 or not.
		thrustAdjustment = thrustAdjustment / 4.0;
		// > Compute the feed-forward force
848
		float feed_forward_thrust_per_motor = F_in_newtons / 4.0; //m_mass_total_grams * 9.81/(1000*4);
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
		// > Put in the per motor commands
		response.controlOutput.motorCmd1 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
		response.controlOutput.motorCmd2 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
		response.controlOutput.motorCmd3 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
		response.controlOutput.motorCmd4 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);


		// Specify that this controller is a rate controller
		// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTOR;
		response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
		// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;


		// An alternate debugging technique is to print out data directly to the
		// command line from which this node was launched.
		/*if (shouldDisplayDebugInfo)
		{
			// An example of "printing out" the data from the "request" argument to the
			// command line. This might be useful for debugging.
			ROS_INFO_STREAM("x-coordinate [m]: " << request.ownCrazyflie.x);
			ROS_INFO_STREAM("y-coordinate [m]: " << request.ownCrazyflie.y);
			ROS_INFO_STREAM("z-coordinate [m]: " << request.ownCrazyflie.z);
			ROS_INFO_STREAM("roll       [deg]: " << request.ownCrazyflie.roll);
			ROS_INFO_STREAM("pitch      [deg]: " << request.ownCrazyflie.pitch);
			ROS_INFO_STREAM("yaw        [deg]: " << request.ownCrazyflie.yaw);
			ROS_INFO_STREAM("Delta t      [s]: " << request.ownCrazyflie.acquiringTime);

			// An example of "printing out" the control actions computed.
			ROS_INFO_STREAM("thrustAdjustment = " << thrustAdjustment);
			ROS_INFO_STREAM("controlOutput.roll = " << response.controlOutput.roll);
			ROS_INFO_STREAM("controlOutput.pitch = " << response.controlOutput.pitch);
			ROS_INFO_STREAM("controlOutput.yaw = " << response.controlOutput.yaw);

			// An example of "printing out" the "thrust-to-command" conversion parameters.
			ROS_INFO_STREAM("motorPoly 0:" << motorPoly[0]);
			ROS_INFO_STREAM("motorPoly 0:" << motorPoly[1]);
			ROS_INFO_STREAM("motorPoly 0:" << motorPoly[2]);

			// An example of "printing out" the per motor 16-bit command computed.
			ROS_INFO_STREAM("controlOutput.cmd1 = " << response.controlOutput.motorCmd1);
			ROS_INFO_STREAM("controlOutput.cmd3 = " << response.controlOutput.motorCmd2);
			ROS_INFO_STREAM("controlOutput.cmd2 = " << response.controlOutput.motorCmd3);
			ROS_INFO_STREAM("controlOutput.cmd4 = " << response.controlOutput.motorCmd4);
		}*/
893

894

895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
	}else if(controller_mode == 2){// Trajectory Follower


		//TODO
		// Pragash: I've added this controller mode 2 to implement the trajectory tracking in the future
		// At the moment it's the same as in controller mode 1







		// LQR for Angles

		// Read Mothership coordinates
		// x,y,z,yaw
		float ms_coordinates[4];
		/*ms_coordinates[0] = request.otherCrazyflies[0].x;
		ms_coordinates[1] = request.otherCrazyflies[0].y;
		ms_coordinates[2] = request.otherCrazyflies[0].z;
		ms_coordinates[3] = request.otherCrazyflies[0].yaw;*/

		/*ms_coordinates[0] = dronexSetpoint.x;
		ms_coordinates[1] = dronexSetpoint.y;
		ms_coordinates[2] = dronexSetpoint.z;
		ms_coordinates[3] = request.otherCrazyflies[0].yaw;*/


mastefan's avatar
mastefan committed
924
925
926
927
		// Load Mothership velocity
		// x dot, y dot, z dot
		float ms_velocity[3];

928
929
930
931
932
933
934
935
		if(flying_state == DRONEX_FOLLOW_TRAJECTORY){

			calculateTrajectory();

			ms_coordinates[0] = trajectory_setpoint[0];
			ms_coordinates[1] = trajectory_setpoint[1];
			ms_coordinates[2] = trajectory_setpoint[2];
			ms_coordinates[3] = trajectory_setpoint[3];
mastefan's avatar
mastefan committed
936
937
938
939
940
941
942
943
944
945


			ms_velocity[0] = trajectory_velocity[0];
			ms_velocity[1] = trajectory_velocity[1];
			ms_velocity[2] = trajectory_velocity[2];

			ms_velocity[0] = 0;
			ms_velocity[1] = 0;
			ms_velocity[2] = 0;

946
947
948
949
950
951
952
		}else{
			ms_coordinates[0] = m_setpoint_for_controller[0];
			ms_coordinates[1] = m_setpoint_for_controller[1];
			ms_coordinates[2] = m_setpoint_for_controller[2];
			ms_coordinates[3] = request.otherCrazyflies[0].yaw;


mastefan's avatar
mastefan committed
953
954
955
956
			ms_velocity[0] = drone_X_vel[0];
			ms_velocity[1] = drone_X_vel[1];
			ms_velocity[2] = drone_X_vel[2];
		}
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



		// CONVERT THE CURRENT INERTIAL FRAME STATE ESTIMATE, INTO
		// THE BODY FRAME ERROR REQUIRED BY THE CONTROLLER
		// > Define a local array to fill in with the body frame error
		float stateErrorBody[12];
		// > Call the function to perform the conversion
		convert_stateInertial_to_bodyFrameError(current_stateInertialEstimate, ms_coordinates, stateErrorBody);


		float rollAngle_forResponse = 0;
		float pitchAngle_forResponse = 0;
		float thrustAdjustment = 0;

		// TODO: Do not forget to implement the yawController
		float yawAngle_forResponse = 0;


		integrator_XYZ(stateErrorBody);

		// integrator

		// BODY FRAME Y CONTROLLER
		rollAngle_forResponse  -= gainIntegratorAngle[0] * integrator_sum_XYZ[1];
		// BODY FRAME X CONTROLLER
		pitchAngle_forResponse -= gainIntegratorAngle[1] * integrator_sum_XYZ[0];
		// > ALITUDE CONTROLLER (i.e., z-controller):
		thrustAdjustment       -= gainIntegratorAngle[2] * integrator_sum_XYZ[2];


		// Perform the "-Kx" LQR computation for the rates and thrust:
		for(int i = 0; i < 6; ++i){
			// BODY FRAME Y CONTROLLER
			rollAngle_forResponse -= 1.1*gainMatrixRollAngle[i] * stateErrorBody[i];
			// BODY FRAME X CONTROLLER
			pitchAngle_forResponse -= 1.1*gainMatrixPitchAngle[i] * stateErrorBody[i];
			// BODY FRAME X CONTROLLER
			//thrustAdjustment -= gainMatrixThrust_SixStateVector[i] * stateErrorBody[i];

		}

		// Calculate the angle in x-y plane of DroneX for transformation to local coordinates
		float droneXAngle;
For faster browsing, not all history is shown. View entire blame