MpcControllerService.cpp 58.2 KB
Newer Older
beuchatp's avatar
beuchatp committed
1
//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
roangel's avatar
roangel committed
2
//
3
4
5
//    This file is part of D-FaLL-System.
//    
//    D-FaLL-System is free software: you can redistribute it and/or modify
roangel's avatar
roangel committed
6
7
8
//    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.
9
10
//    
//    D-FaLL-System is distributed in the hope that it will be useful,
roangel's avatar
roangel committed
11
12
13
//    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.
14
//    
roangel's avatar
roangel committed
15
//    You should have received a copy of the GNU General Public License
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
//    
//
//    ----------------------------------------------------------------------------------
//    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:
//    Place for students to implement their controller
//
//    ----------------------------------------------------------------------------------
31
32


33
34
35
36
37
38
39
40
41
42
43
44
45
46



//    ----------------------------------------------------------------------------------
//    III  N   N   CCCC  L      U   U  DDDD   EEEEE   SSSS
//     I   NN  N  C      L      U   U  D   D  E      S
//     I   N N N  C      L      U   U  D   D  EEE     SSS
//     I   N  NN  C      L      U   U  D   D  E          S
//    III  N   N   CCCC  LLLLL   UUU   DDDD   EEEEE  SSSS
//    ----------------------------------------------------------------------------------

// These various headers need to be included so that this controller service can be
// connected with the D-FaLL system.

47
48
49
50
//some useful libraries
#include <math.h>
#include <stdlib.h>
#include "ros/ros.h"
roangel's avatar
roangel committed
51
#include <ros/package.h>
52

53
54
#include <ctime>

55
56
57
58
59
//the generated structs from the msg-files have to be included
#include "d_fall_pps/ViconData.h"
#include "d_fall_pps/Setpoint.h"
#include "d_fall_pps/ControlCommand.h"
#include "d_fall_pps/Controller.h"
roangel's avatar
roangel committed
60
#include "d_fall_pps/DebugMsg.h"
61
#include "d_fall_pps/CustomControllerYAML.h"
62

63
64
65
// Include the Parameter Service shared definitions
#include "nodes/ParameterServiceDefinitions.h"

66
67
#include <std_msgs/Int32.h>

68
#include "MPC_functions.h"
69

70
71
using namespace std;

72
73
74
75
76
77
78
79
80
81
82

//    ----------------------------------------------------------------------------------
//    DDDD   EEEEE  FFFFF  III  N   N  EEEEE   SSSS
//    D   D  E      F       I   NN  N  E      S
//    D   D  EEE    FFF     I   N N N  EEE     SSS
//    D   D  E      F       I   N  NN  E          S
//    DDDD   EEEEE  F      III  N   N  EEEEE  SSSS
//    ----------------------------------------------------------------------------------

// These constants are defined to make the code more readable and adaptable.

83
// Universal constants
84
#define PI 3.1415926535
roangel's avatar
roangel committed
85

86
// These constants define the modes that can be used for controller the Crazyflie 2.0,
87
88
89
90
91
92
93
94
95
96
97
98
99
// the constants defined here need to be in agreement with those defined in the
// firmware running on the Crazyflie 2.0.
// The following is a short description about each mode:
// MOTOR_MODE    In this mode the Crazyflie will apply the requested 16-bit per motor
//               command directly to each of the motors
// RATE_MODE     In this mode the Crazyflie will apply the requested 16-bit per motor
//               command directly to each of the motors, and additionally request the
//               body frame roll, pitch, and yaw angular rates from the PID rate
//               controllers implemented in the Crazyflie 2.0 firmware.
// ANGE_MODE     In this mode the Crazyflie will apply the requested 16-bit per motor
//               command directly to each of the motors, and additionally request the
//               body frame roll, pitch, and yaw angles from the PID attitude
//               controllers implemented in the Crazyflie 2.0 firmware.
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114

#define CF_COMMAND_TYPE_MOTOR   6
#define CF_COMMAND_TYPE_RATE    7
#define CF_COMMAND_TYPE_ANGLE   8

#define ESTIMATOR_METHOD_FINITE_DIFFERENCE          1
#define ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION   2   // (DEFAULT)
#define ESTIMATOR_METHOD_QUADROTOR_MODEL_BASED      3

int estimator_method = ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION;

// Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
bool shouldDisplayDebugInfo = false;

float estimator_frequency = 200;
115

116
117
118
119
120
121
122
123
124
125
126
127
// These constants define the controller used for computing the response in the
// "calculateControlOutput" function
// The following is a short description about each mode:
// LQR_RATE_MODE      LQR controller based on the state vector:
//                    [position,velocity,angles]
//
// LQR_ANGLE_MODE     LQR controller based on the state vector:
//                    [position,velocity]
//
#define LQR_RATE_MODE   1   // (DEFAULT)
#define LQR_ANGLE_MODE  2

128
// Namespacing the package
129
130
using namespace d_fall_pps;

131

132
133
134
135
136
137
138
139
//    ----------------------------------------------------------------------------------
//    V   V    A    RRRR   III    A    BBBB   L      EEEEE   SSSS
//    V   V   A A   R   R   I    A A   B   B  L      E      S
//    V   V  A   A  RRRR    I   A   A  BBBB   L      EEE     SSS
//     V V   AAAAA  R  R    I   AAAAA  B   B  L      E          S
//      V    A   A  R   R  III  A   A  BBBB   LLLLL  EEEEE  SSSS
//    ----------------------------------------------------------------------------------

140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158

// THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
// > For the (x,y,z) position
std::vector<float> PMKF_Ahat_row1_for_positions (2,0.0);
std::vector<float> PMKF_Ahat_row2_for_positions (2,0.0);
std::vector<float> PMKF_Kinf_for_positions      (2,0.0);
// > For the (roll,pitch,yaw) angles
std::vector<float> PMKF_Ahat_row1_for_angles    (2,0.0);
std::vector<float> PMKF_Ahat_row2_for_angles    (2,0.0);
std::vector<float> PMKF_Kinf_for_angles         (2,0.0);

std::vector<float> gainMatrixRollRate_Nested            (3,0.0);
std::vector<float> gainMatrixPitchRate_Nested           (3,0.0);
std::vector<float> gainMatrixYawRate_Nested             (3,0.0);

float current_xzy_rpy_measurement[6];
float previous_xzy_rpy_measurement[6];


159
160
// Variables for controller
float cf_mass;                       // Crazyflie mass in grams
161
std::vector<float> motorPoly(3);     // Coefficients of the 16-bit command to thrust conversion
162
163
164
float control_frequency;             // Frequency at which the controller is running
float gravity_force;                 // The weight of the Crazyflie in Newtons, i.e., mg

165
float previous_stateErrorInertial[9];     // The location error of the Crazyflie at the "previous" time step
166

167
std::vector<float>  setpoint{0.0,0.0,0.4,0.0};     // The setpoints for (x,y,z) position and yaw angle, in that order
168

roangel's avatar
roangel committed
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
// Variables for MPC:

Eigen::MatrixXd P(N_x,N_x);
Eigen::MatrixXd Q(N_x,N_x);
Eigen::MatrixXd R(N_u,N_u);

Eigen::VectorXd X_ref;
Eigen::VectorXd U_ref;

std::vector<MatrixAtype> A_tray;
std::vector<MatrixBtype> B_tray;
std::vector<VectorXtype> g_tray;

std::vector<VectorXtype> X_tray;
std::vector<VectorUtype> U_tray;

185
186
187
188
Eigen::VectorXd U_0;



roangel's avatar
roangel committed
189
190
191
192
193
194
params_t params;

VectorXtype x0;

int N = 5;

195

196
// ROS Publisher for debugging variables
roangel's avatar
roangel committed
197
198
ros::Publisher debugPublisher;

199

200
// Variable for the namespaces for the paramter services
201
// > For the paramter service of this agent
202
std::string namespace_to_own_agent_parameter_service;
203
// > For the parameter service of the coordinator
204
std::string namespace_to_coordinator_parameter_service;
205

206
207
208
// The ID of this agent, i.e., the ID of this compute
int my_agentID = 0;

209

210
// RELEVANT NOTES ABOUT THE VARIABLES DECLARE HERE:
211
// The "CrazyflieData" type used for the "request" variable is a
212
213
214
215
216
217
218
219
220
221
222
// structure as defined in the file "CrazyflieData.msg" which has the following
// properties:
//     string crazyflieName              The name given to the Crazyflie in the Vicon software
//     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
223

224
225
226
227




228
229
230
231
232
233
234
235
236
237
238
239
240
//    ----------------------------------------------------------------------------------
//    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
//
//    PPPP   RRRR    OOO   TTTTT   OOO   TTTTT  Y   Y  PPPP   EEEEE   SSSS
//    P   P  R   R  O   O    T    O   O    T     Y Y   P   P  E      S
//    PPPP   RRRR   O   O    T    O   O    T      Y    PPPP   EEE     SSS
//    P      R  R   O   O    T    O   O    T      Y    P      E          S
//    P      R   R   OOO     T     OOO     T      Y    P      EEEEE  SSSS
//    ----------------------------------------------------------------------------------
241

242
243
244
245
246
// These function prototypes are not strictly required for this code to complile, but
// adding the function prototypes here means the the functions can be written below in
// any order. If the function prototypes are not included then the function need to
// written below in an order that ensure each function is implemented before it is
// called from another function, hence why the "main" function is at the bottom.
247

248
249
250
// CONTROLLER COMPUTATIONS
bool calculateControlOutput(Controller::Request &request, Controller::Response &response);

251
252
// CONVERSION FROM THRUST IN NEWTONS TO 16-BIT COMMAND
float computeMotorPolyBackward(float thrust);
253

254
255
// SETPOINT CHANGE CALLBACK
void setpointCallback(const Setpoint& newSetpoint);
256

257
// LOAD PARAMETERS
258
259
260
float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
int getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
261
262
263
264
void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length);
int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val);
bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name);

265
266
267
268
void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
void fetchYamlParameters(ros::NodeHandle& nodeHandle);
void processFetchedParameters();
//void customYAMLasMessageCallback(const CustomControllerYAML& newCustomControllerParameters);
269

270
void angleControlledCrazyflie(float stateInertial[12], float input_angle[4], Controller::Response &response);
271
272
273
void perform_estimator_update_state_interial(Controller::Request &request, float (&stateInertialEstimate)[12]);
void performEstimatorUpdate_forStateInterial_viaFiniteDifference(float (&stateInertialEstimate)[12]);
void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter(float (&stateInertialEstimate)[12]);
274

275
void initialize_MPC_variables(int N, VectorXtype x0);
276
277


278
279
280
281
282
283
284
285
286
287
288
289
290
//    ----------------------------------------------------------------------------------
//    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
//    ----------------------------------------------------------------------------------
roangel's avatar
roangel committed
291

292

roangel's avatar
roangel committed
293
294


roangel's avatar
roangel committed
295

296
//    ------------------------------------------------------------------------------
297
//     OOO   U   U  TTTTT  EEEEE  RRRR
298
299
300
301
302
303
304
305
306
307
308
//    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
//    ----------------------------------------------------------------------------------
roangel's avatar
roangel committed
309

310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
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
391
392
393
394
// This function is the callback that is linked to the "CustomController" 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
// 
// IMPORTANT NOTES FOR "onboardControllerType"  AND AXIS CONVENTIONS
// > The allowed values for "onboardControllerType" are in the "Defines" section at the
//   top of this file, they are MOTOR_MODE, RATE_MODE, OR ANGLE_MODE.
// > In the PPS exercise we will only use the RATE_MODE.
// > In RATE_MODE the ".roll", ".ptich", and ".yaw" properties of "response.ControlCommand"
//   specify the angular rate in [radians/second] that will be requested from the
//   PID controllers running in the Crazyflie 2.0 firmware.
// > In RATE_MODE the ".motorCmd1" to ".motorCmd4" properties of "response.ControlCommand"
//   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).
// > In RATE_MODE the axis convention for the roll, pitch, and yaw body rates returned
//   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)
//       \____/                       \____/
//
395
//
396
397
//
// This function WILL NEED TO BE edited for successful completion of the PPS exercise
398

399
void angleControlledCrazyflie(float stateInertial[12], float input_angle[4], Controller::Response &response)
beuchatp's avatar
beuchatp committed
400
{
401
402
403
404
    float roll_sp = input_angle[0];
    float pitch_sp = input_angle[1];
    float yaw_sp = input_angle[2];
    float ft_sp = input_angle[3];
beuchatp's avatar
beuchatp committed
405

406
407
408
409
    // initialize variables that will contain w_x, w_y and w_z
	float w_x_sp  = 0;
	float w_y_sp = 0;
	float w_z_sp   = 0;
beuchatp's avatar
beuchatp committed
410
411

	// Create the angle error to use for the inner controller
412
413
414
415
	float angle_error[3] = {
		stateInertial[6] - roll_sp,
		stateInertial[7] - pitch_sp,
        stateInertial[8] - yaw_sp
beuchatp's avatar
beuchatp committed
416
417
	};
	// Perform the "-Kx" LQR computation for the rates and thrust:
418
	for(int i = 0; i < 3; ++i)
419
	{
beuchatp's avatar
beuchatp committed
420
		// BODY FRAME Y CONTROLLER
421
		w_x_sp  -= gainMatrixRollRate_Nested[i]  * angle_error[i];
beuchatp's avatar
beuchatp committed
422
		// BODY FRAME X CONTROLLER
423
		w_y_sp -= gainMatrixPitchRate_Nested[i] * angle_error[i];
beuchatp's avatar
beuchatp committed
424
		// BODY FRAME Z CONTROLLER
425
		w_z_sp -= gainMatrixYawRate_Nested[i]   * angle_error[i];
426
427
	}

428

beuchatp's avatar
beuchatp committed
429
	// UPDATE THE "RETURN" THE VARIABLE NAMED "response"
430

beuchatp's avatar
beuchatp committed
431
432
	// Put the computed rates and thrust into the "response" variable
	// > For roll, pitch, and yaw:
433
434
435
	response.controlOutput.roll  = w_x_sp;
	response.controlOutput.pitch = w_y_sp;
	response.controlOutput.yaw   = w_z_sp;
beuchatp's avatar
beuchatp committed
436
437
438
439
440
441
	// > 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.
	// > NOTE: the "gravity_force_quarter" value was already divided by 4 when
	//         it was loaded/processes from the .yaml file.
442
443
444
445
	response.controlOutput.motorCmd1 = computeMotorPolyBackward(ft_sp/4.0);
	response.controlOutput.motorCmd2 = computeMotorPolyBackward(ft_sp/4.0);
	response.controlOutput.motorCmd3 = computeMotorPolyBackward(ft_sp/4.0);
	response.controlOutput.motorCmd4 = computeMotorPolyBackward(ft_sp/4.0);
beuchatp's avatar
beuchatp committed
446
447
448
449
450
451
452
453

	// 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;

	// Display some details (if requested)
	if (shouldDisplayDebugInfo)
454
	{
455
456
457
458
		ROS_INFO_STREAM("thrust    =" << ft_sp);
		ROS_INFO_STREAM("rollrate  =" << w_x_sp);
		ROS_INFO_STREAM("pitchrate =" << w_y_sp);
		ROS_INFO_STREAM("yawrate   =" << w_z_sp);
459
	}
beuchatp's avatar
beuchatp committed
460
}
461

462
463
int outer_loop_counter = 0;
double raw_input[4];
464

beuchatp's avatar
beuchatp committed
465
466
bool calculateControlOutput(Controller::Request &request, Controller::Response &response)
{
467

468

beuchatp's avatar
beuchatp committed
469
470
471
	// This is the "start" of the outer loop controller, add all your control
	// computation here, or you may find it convienient to create functions
	// to keep you code cleaner
472

beuchatp's avatar
beuchatp committed
473
    // Define a local array to fill in with the state error
474
    float stateInertialEstimate[12];
475

476
	perform_estimator_update_state_interial(request, stateInertialEstimate);
477

478
    // The estimate of the state is inside stateInertialEstimate now. Next, MPC
479
    // Should we convert into body frame for our MPC controller? Let's skip it for now, YAW is going to be zero in our case
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
    // NO, we dont have to convert into body frame, that was only when the linearization was done around hover with yaw = 0.
    // we relinearize in every point

    if(outer_loop_counter == 0)
    {

        // ================= MPC PART ==================

        // Make sure we run it at 50Hz

        // first, we have full state measurement stored in stateInertialEstimate.
        // Apply setpoint change first, and store everything in x0 vector

        x0 << stateInertialEstimate[0] - setpoint[0],
            stateInertialEstimate[1] - setpoint[1],
            stateInertialEstimate[2] - setpoint[2],
            stateInertialEstimate[3],
            stateInertialEstimate[4],
            stateInertialEstimate[5];

        // Do the MPC step:
        U_0 = mympc_varying_another(A_tray, B_tray, g_tray, Q, R, P, N, x0, X_ref, U_ref, 0, 0, 0);
        VectorUtype u = U_0.tail(4); // this is the input to apply next

        // prediction of next N states:
        VectorXtype x_approx_next;
        std::vector<VectorXtype> x_approx_temp;
        x_approx_next << x0;
508

509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
        for(int j = 0; j < N; j++)
        {
            euler_method_forward(F_crazyflie_6_states, 0, params.Ts/4, params.Ts, x_approx_next, U_0.segment(j,N_u), params, x_approx_temp);
            x_approx_next = x_approx_temp.back();
            X_tray[j] = x_approx_next;

            // Now update U_tray using the same loop
            if(j < N-1)
                U_tray[j] = U_0.segment(j+1, N_u);
            else
                U_tray[j] = U_0.segment(j, N_u); // last element of the new U_tray is assumed to be the same as second to last
        }
        // X_tray and U_tray have been completely updated with the new states coming from the new sequence of inputs

        // Relinearize around new trayectory:
        get_matrices_linearization_affine(X_tray, U_tray, params, A_tray, B_tray, g_tray);

        // update the current input to the middle loop
527
528
529
530
        raw_input[0] = u(0);
        raw_input[1] = u(1);
        raw_input[2] = u(2);
        raw_input[3] = u(3);
531
532
533
534
535
536
537
538
539
540
541
542
    }

    outer_loop_counter++;

    // wrap the counter:
    if(outer_loop_counter >= 4) //200 Hz/4 = 50 Hz
        outer_loop_counter = 0;

    // ============= END MPC PART ===============


    // test:
543
    float x0_full_state[12] = {-setpoint[0], -setpoint[1], -setpoint[2], 0, 0, 0, 0, 0, 0, 0, 0, 0};
544

545
    // just for debugging purposes: control z axis with some PD gain, check how the angle setpoint works
546
    float correction_z = -0.82*(0.4 - stateInertialEstimate[2]) - 0.22 * (0 - stateInertialEstimate[5]) + cf_mass/1000*9.8;
547

548
    float input_angle[4] = {-setpoint[0], 0, 0, correction_z};
549

550
    // create a function that takes as input angle references, like a crazyflie entity with input angles
551
552
    // This function has to run at 200Hz
    angleControlledCrazyflie(stateInertialEstimate, input_angle, response);
553
554


555
556
557

    // Return "true" to indicate that the control computation was performed successfully
    return true;
558
559
560
}


beuchatp's avatar
beuchatp committed
561
562
563
564
565
566
567
//    ------------------------------------------------------------------------------
//    EEEEE   SSSS  TTTTT  III  M   M    A    TTTTT  III   OOO   N   N
//    E      S        T     I   MM MM   A A     T     I   O   O  NN  N
//    EEE     SSS     T     I   M M M  A   A    T     I   O   O  N N N
//    E          S    T     I   M   M  AAAAA    T     I   O   O  N  NN
//    EEEEE  SSSS     T    III  M   M  A   A    T    III   OOO   N   N
//    ------------------------------------------------------------------------------
568
569
570
571



void perform_estimator_update_state_interial(Controller::Request &request, float (&stateInertialEstimate)[12])
beuchatp's avatar
beuchatp committed
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
{

	// PUT THE CURRENT MEASURED DATA INTO THE CLASS VARIABLE
	// > for (x,y,z) position
	current_xzy_rpy_measurement[0] = request.ownCrazyflie.x;
	current_xzy_rpy_measurement[1] = request.ownCrazyflie.y;
	current_xzy_rpy_measurement[2] = request.ownCrazyflie.z;
	// > for (roll,pitch,yaw) angles
	current_xzy_rpy_measurement[3] = request.ownCrazyflie.roll;
	current_xzy_rpy_measurement[4] = request.ownCrazyflie.pitch;
	current_xzy_rpy_measurement[5] = request.ownCrazyflie.yaw;


	// FILLE IN THE STATE INERTIAL ESTIMATE TO BE USED FOR CONTROL
	switch (estimator_method)
	{
		// Estimator based on finte differences
		case ESTIMATOR_METHOD_FINITE_DIFFERENCE:
		{
591
592
            // RUN THE FINITE DIFFERENCE ESTIMATOR and fill stateEstimate with result
            performEstimatorUpdate_forStateInterial_viaFiniteDifference(stateInertialEstimate);
beuchatp's avatar
beuchatp committed
593
594
595
596
597
			break;
		}
		// Estimator based on Point Mass Kalman Filter
		case ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION:
		{
598
599
            // RUN THE POINT MASS KALMAN FILTER ESTIMATOR and fill stateEstimate with result
            performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter(stateInertialEstimate);
beuchatp's avatar
beuchatp committed
600
601
602
603
604
605
606
			break;
		}
		// Handle the exception
		default:
		{
			// Display that the "estimator_method" was not recognised
			ROS_INFO_STREAM("[DEMO CONTROLLER] ERROR: in the 'calculateControlOutput' function of the 'DemoControllerService': the 'estimator_method' is not recognised.");
607
608
			// Transfer the finite difference estimate by default and fill stateEstimate with result
            performEstimatorUpdate_forStateInterial_viaFiniteDifference(stateInertialEstimate);
beuchatp's avatar
beuchatp committed
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
			break;
		}
	}


	// NOW THAT THE ESTIMATORS HAVE ALL BEEN RUN, PUT THE CURRENT
	// MEASURED DATA INTO THE CLASS VARIABLE FOR THE PREVIOUS
	// > for (x,y,z) position
	previous_xzy_rpy_measurement[0] = current_xzy_rpy_measurement[0];
	previous_xzy_rpy_measurement[1] = current_xzy_rpy_measurement[1];
	previous_xzy_rpy_measurement[2] = current_xzy_rpy_measurement[2];
	// > for (roll,pitch,yaw) angles
	previous_xzy_rpy_measurement[3] = current_xzy_rpy_measurement[3];
	previous_xzy_rpy_measurement[4] = current_xzy_rpy_measurement[4];
	previous_xzy_rpy_measurement[5] = current_xzy_rpy_measurement[5];
}

626
void performEstimatorUpdate_forStateInterial_viaFiniteDifference(float (&stateInertialEstimate)[12])
beuchatp's avatar
beuchatp committed
627
628
629
{
	// PUT IN THE CURRENT MEASUREMENT DIRECTLY
	// > for (x,y,z) position
630
631
632
	stateInertialEstimate[0]  = current_xzy_rpy_measurement[0];
	stateInertialEstimate[1]  = current_xzy_rpy_measurement[1];
	stateInertialEstimate[2]  = current_xzy_rpy_measurement[2];
beuchatp's avatar
beuchatp committed
633
	// > for (roll,pitch,yaw) angles
634
635
636
	stateInertialEstimate[6]  = current_xzy_rpy_measurement[3];
	stateInertialEstimate[7]  = current_xzy_rpy_measurement[4];
	stateInertialEstimate[8]  = current_xzy_rpy_measurement[5];
beuchatp's avatar
beuchatp committed
637
638
639

	// COMPUTE THE VELOCITIES VIA FINITE DIFFERENCE
	// > for (x,y,z) velocities
640
641
642
	stateInertialEstimate[3]  = (current_xzy_rpy_measurement[0] - previous_xzy_rpy_measurement[0]) * estimator_frequency;
	stateInertialEstimate[4]  = (current_xzy_rpy_measurement[1] - previous_xzy_rpy_measurement[1]) * estimator_frequency;
	stateInertialEstimate[5]  = (current_xzy_rpy_measurement[2] - previous_xzy_rpy_measurement[2]) * estimator_frequency;
beuchatp's avatar
beuchatp committed
643
	// > for (roll,pitch,yaw) velocities
644
645
646
	stateInertialEstimate[9]  = (current_xzy_rpy_measurement[3] - previous_xzy_rpy_measurement[3]) * estimator_frequency;
	stateInertialEstimate[10] = (current_xzy_rpy_measurement[4] - previous_xzy_rpy_measurement[4]) * estimator_frequency;
	stateInertialEstimate[11] = (current_xzy_rpy_measurement[5] - previous_xzy_rpy_measurement[5]) * estimator_frequency;
beuchatp's avatar
beuchatp committed
647
648
649
650
}



651
void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter(float (&stateInertialEstimate)[12])
beuchatp's avatar
beuchatp committed
652
653
654
655
656
657
{
	// PERFORM THE KALMAN FILTER UPDATE STEP
	// > First take a copy of the estimator state
	float temp_PMKFstate[12];
	for(int i = 0; i < 12; ++i)
	{
658
		temp_PMKFstate[i]  = stateInertialEstimate[i];
beuchatp's avatar
beuchatp committed
659
660
661
	}
	// > Now perform update for:
	// > x position and velocity:
662
663
	stateInertialEstimate[0] = PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[0] + PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[3] + PMKF_Kinf_for_positions[0]*current_xzy_rpy_measurement[0];
	stateInertialEstimate[3] = PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[0] + PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[3] + PMKF_Kinf_for_positions[1]*current_xzy_rpy_measurement[0];
beuchatp's avatar
beuchatp committed
664
	// > y position and velocity:
665
666
	stateInertialEstimate[1] = PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[1] + PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[4] + PMKF_Kinf_for_positions[0]*current_xzy_rpy_measurement[1];
	stateInertialEstimate[4] = PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[1] + PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[4] + PMKF_Kinf_for_positions[1]*current_xzy_rpy_measurement[1];
beuchatp's avatar
beuchatp committed
667
	// > z position and velocity:
668
669
	stateInertialEstimate[2] = PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[2] + PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[5] + PMKF_Kinf_for_positions[0]*current_xzy_rpy_measurement[2];
	stateInertialEstimate[5] = PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[2] + PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[5] + PMKF_Kinf_for_positions[1]*current_xzy_rpy_measurement[2];
beuchatp's avatar
beuchatp committed
670
671

	// > roll  position and velocity:
672
673
	stateInertialEstimate[6]  = PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[6] + PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[9]  + PMKF_Kinf_for_angles[0]*current_xzy_rpy_measurement[3];
	stateInertialEstimate[9]  = PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[6] + PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[9]  + PMKF_Kinf_for_angles[1]*current_xzy_rpy_measurement[3];
beuchatp's avatar
beuchatp committed
674
	// > pitch position and velocity:
675
676
	stateInertialEstimate[7]  = PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[7] + PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[10] + PMKF_Kinf_for_angles[0]*current_xzy_rpy_measurement[4];
	stateInertialEstimate[10] = PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[7] + PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[10] + PMKF_Kinf_for_angles[1]*current_xzy_rpy_measurement[4];
beuchatp's avatar
beuchatp committed
677
	// > yaw   position and velocity:
678
679
	stateInertialEstimate[8]  = PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[8] + PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[11] + PMKF_Kinf_for_angles[0]*current_xzy_rpy_measurement[5];
	stateInertialEstimate[11] = PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[8] + PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[11] + PMKF_Kinf_for_angles[1]*current_xzy_rpy_measurement[5];
beuchatp's avatar
beuchatp committed
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



//    ------------------------------------------------------------------------------
//    N   N  EEEEE  W     W   TTTTT   OOO   N   N        CCCC  M   M  DDDD
//    NN  N  E      W     W     T    O   O  NN  N       C      MM MM  D   D
//    N N N  EEE    W     W     T    O   O  N N N  -->  C      M M M  D   D
//    N  NN  E       W W W      T    O   O  N  NN       C      M   M  D   D
//    N   N  EEEEE    W W       T     OOO   N   N        CCCC  M   M  DDDD
//
//     CCCC   OOO   N   N  V   V  EEEEE  RRRR    SSSS  III   OOO   N   N
//    C      O   O  NN  N  V   V  E      R   R  S       I   O   O  NN  N
//    C      O   O  N N N  V   V  EEE    RRRR    SSS    I   O   O  N N N
//    C      O   O  N  NN   V V   E      R  R       S   I   O   O  N  NN
//     CCCC   OOO   N   N    V    EEEEE  R   R  SSSS   III   OOO   N   N
//    ----------------------------------------------------------------------------------

// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
float computeMotorPolyBackward(float thrust)
{
    return (-motorPoly[1] + sqrt(motorPoly[1] * motorPoly[1] - 4 * motorPoly[2] * (motorPoly[0] - thrust))) / (2 * motorPoly[2]);
706
707
}

708

709
Eigen::IOFormat CleanFmt(4, 0, ", ", "\n", "[", "]");
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728


//    ----------------------------------------------------------------------------------
//    N   N  EEEEE  W     W        SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
//    NN  N  E      W     W       S      E        T    P   P  O   O   I   NN  N    T
//    N N N  EEE    W     W        SSS   EEE      T    PPPP   O   O   I   N N N    T
//    N  NN  E       W W W            S  E        T    P      O   O   I   N  NN    T
//    N   N  EEEEE    W W         SSSS   EEEEE    T    P       OOO   III  N   N    T
//
//     GGG   U   U  III        CCCC    A    L      L      BBBB     A     CCCC  K   K
//    G   G  U   U   I        C       A A   L      L      B   B   A A   C      K  K
//    G      U   U   I        C      A   A  L      L      BBBB   A   A  C      KKK
//    G   G  U   U   I        C      AAAAA  L      L      B   B  AAAAA  C      K  K
//     GGGG   UUU   III        CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
//    ----------------------------------------------------------------------------------

// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
void setpointCallback(const Setpoint& newSetpoint)
{
729
    std::cout << "testing cout" << std::endl;
roangel's avatar
roangel committed
730
731
732
733
    setpoint[0] = newSetpoint.x;
    setpoint[1] = newSetpoint.y;
    setpoint[2] = newSetpoint.z;
    setpoint[3] = newSetpoint.yaw;
734

735
    // ================= MPC PART ==================
736
737


738
    // Make sure we run it at 50Hz
739

740
741
    // first, we have full state measurement stored in stateInertialEstimate.
    // Apply setpoint change first, and store everything in x0 vector
742

743
    double stateInertialEstimate[12] = {0};
744

745
746
747
748
749
750
751
752
    x0 << -stateInertialEstimate[0] + setpoint[0],
        -stateInertialEstimate[1] + setpoint[1],
        -stateInertialEstimate[2] + setpoint[2],
        stateInertialEstimate[3],
        stateInertialEstimate[4],
        stateInertialEstimate[5];

    initialize_MPC_variables(N, x0);
753

754
755
756
757
    clock_t begin_time = clock();



758
759
760
    // Do the MPC step:
    U_0 = mympc_varying_another(A_tray, B_tray, g_tray, Q, R, P, N, x0, X_ref, U_ref, 0, 0, 0);
    VectorUtype u = U_0.tail(4); // this is the input to apply next
761

762
763
764
765
    // prediction of next N states:
    VectorXtype x_approx_next;
    std::vector<VectorXtype> x_approx_temp;
    x_approx_next << x0;
766

767
    for(int j = 0; j < N; j++)
768
    {
769
770
771
772
773
774
775
776
777
778
779
        euler_method_forward(F_crazyflie_6_states, 0, params.Ts/4, params.Ts, x_approx_next, U_0.segment(j,N_u), params, x_approx_temp);
        x_approx_next = x_approx_temp.back();
        X_tray[j] = x_approx_next;

        // Now update U_tray using the same loop
        if(j < N-1)
            U_tray[j] = U_0.segment(j+1, N_u);
        else
            U_tray[j] = U_0.segment(j, N_u); // last element of the new U_tray is assumed to be the same as second to last
    }
    // X_tray and U_tray have been completely updated with the new states coming from the new sequence of inputs
780

781
782
    // Relinearize around new trayectory:
    get_matrices_linearization_affine(X_tray, U_tray, params, A_tray, B_tray, g_tray);
783

784
785
786
787
788
    // update the current input to the middle loop
    raw_input[0] = u(0);
    raw_input[1] = u(1);
    raw_input[2] = u(2);
    raw_input[3] = u(3);
789

790
791
792
793
794
795
796
797
    clock_t end_time = clock();
    double elapsed_secs = double(end_time - begin_time) / CLOCKS_PER_SEC;


    // std::cout << "U_0 for this setpoint, 1 step MPC" << std::endl;
    // std::cout << U_0.format(CleanFmt) << std::endl;

    std::cout << "elapsed secs: " << elapsed_secs << std::endl;
798

799
    // testzone:
800

801
802
    // VectorXtype x_vec;
    // x_vec.setZero();
803

804
805
    // VectorUtype u_vec;
    // u_vec << 0, 0, 0, cf_mass/1000*9.81;
806

807
808
    // MatrixAtype A;
    // MatrixBtype B;
809

810
811
812
    // MatrixAtype A_d;
    // MatrixBtype B_d;
    // VectorXtype g_d;
813

814
815
816
    // params.m = cf_mass/1000.0;
    // params.g = 9.81;
    // params.Ts = 1/50.0;
817

818
819
    // // linearization_fast_euler_6_states(x_vec, u_vec, params, A, B);
    // // discretization_affine(A, B, x_vec, u_vec, params, A_d, B_d, g_d);
820

821
822
    // std::vector<VectorXtype> X_tray;
    // std::vector<VectorUtype> U_tray;
823

824
825
826
827
    // for(int i = 0; i < 5; i++)
    // {
    //     VectorXtype x_temp;
    //     VectorUtype u_temp;
828

829
830
    //     x_temp << i, 0, 0.4, 0, 0, 0;
    //     u_temp << i, 0, 0, params.m*params.g;
831

832
833
834
    //     X_tray.push_back(x_temp);
    //     U_tray.push_back(u_temp);
    // }
835

836
837
838
    // std::vector<MatrixAtype> A_tray;
    // std::vector<MatrixBtype> B_tray;
    // std::vector<VectorXtype> g_tray;
roangel's avatar
roangel committed
839

840
    // get_matrices_linearization_affine(X_tray, U_tray, params, A_tray, B_tray, g_tray);
roangel's avatar
roangel committed
841

842
843
844
845
846
    // for(int i = 0; i < A_tray.size(); i++)
    // {
    //     std::cout << "index matrix" << i << std::endl;
    //     std::cout << A_tray[i] << std::endl;
    // }
roangel's avatar
roangel committed
847

848
849
850
    // // debug
    // Eigen::IOFormat OctaveFmt(Eigen::StreamPrecision, 0, ", ", ";\n", "", "", "[", "]");
    // Eigen::IOFormat CleanFmt(4, 0, ", ", "\n", "[", "]");
roangel's avatar
roangel committed
851
852
853



854
    // // std::cout << A.format(OctaveFmt) << std::endl;
roangel's avatar
roangel committed
855

856
    // // std::cout << B.format(OctaveFmt) << std::endl;
roangel's avatar
roangel committed
857

858
    // // debug of euler method function:
roangel's avatar
roangel committed
859

860
861
862
863
864
    // std::vector<VectorXtype> x_out;
    // VectorXtype x0;
    // VectorUtype u;
    // x0 << 0, 0, 0, 0, 0, 0;
    // u << 0, 0, 0, params.m*params.g*2;
roangel's avatar
roangel committed
865

866
    // euler_method_forward(F_crazyflie_6_states, 0, params.Ts/4, params.Ts, x0, u, params, x_out);
roangel's avatar
roangel committed
867

868
869
870
871
872
    // for(int i = 0; i < x_out.size(); i++)
    // {
    //     std::cout << "xout index:" << i << std::endl;
    //     std::cout << x_out[i] << std::endl;
    // }
roangel's avatar
roangel committed
873

874
875
876
877
    // Eigen::MatrixXd Sx_test;
    // Eigen::MatrixXd Su_test;
    // Eigen::MatrixXd Sg_test;
    // int N = 5;
878

879
    // funSxSuSg_varying_affine(A_tray, B_tray, N, Sx_test, Su_test, Sg_test);
880

881
882
    // std::cout << "Sx test:" << std::endl << std::endl;
    // std::cout << Sx_test<< std::endl;
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
916
917
    // std::cout << "Su test:" << std::endl << std::endl;
    // // std::cout << Su_test<< std::endl;
    // std::cout << Su_test.format(CleanFmt) << std::endl;

    // std::cout << "Sg test:" << std::endl << std::endl;
    // // std::cout << Su_test<< std::endl;
    // std::cout << Sg_test.format(CleanFmt) << std::endl;

    // Eigen::MatrixXd Qbar;
    // Eigen::MatrixXd Rbar;

    // VectorXtype p_vec;
    // p_vec << 3, 3, 3, 2, 2, 2;
    // VectorXtype q_vec;
    // q_vec << 1, 1, 1, 4, 4, 4;

    // VectorUtype r_vec;
    // r_vec << 1, 1, 1, 4;

    // Eigen::MatrixXd P = p_vec.asDiagonal();
    // Eigen::MatrixXd Q = q_vec.asDiagonal();
    // Eigen::MatrixXd R = r_vec.asDiagonal();

    // funQbar(Q, P, N, Qbar);

    // std::cout << "Qbar test:" << std::endl << std::endl;
    // // std::cout << Su_test<< std::endl;
    // std::cout << Qbar.format(CleanFmt) << std::endl;

    // funRbar(R,N, Rbar);

    // std::cout << "Rbar test:" << std::endl << std::endl;
    // // std::cout << Su_test<< std::endl;
    // std::cout << Rbar.format(CleanFmt) << std::endl;
918

919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
    // Eigen::VectorXd X_ref(N_x*(N+1));
    // Eigen::VectorXd U_ref(N_u*N);

    // VectorXtype x_ref;
    // VectorUtype u_ref;
    // x_ref << 0,0,0,0,0,0;
    // u_ref << 0,0,0,params.m*params.g;

    // for(int i = 0; i < N+1; i++)
    // {
    //     X_ref.segment(i*N_x, N_x) = x_ref;
    //     if(i < N)
    //         U_ref.segment(i*N_u, N_u) = u_ref;
    // }

    // Eigen::VectorXd U_0 = mympc_varying_another(A_tray, B_tray, g_tray, Q, R, P, N, x0, X_ref, U_ref, 0, 0, 0);
935
936
}

937
void initialize_MPC_variables(int N, VectorXtype x0)
roangel's avatar
roangel committed
938
{
939

roangel's avatar
roangel committed
940
941
942
943
944
945
946
947
948
949
    // params:
    params.m = cf_mass/1000.0;
    params.g = 9.81;
    params.Ts = 1/50.0;

    // Initialize initial state, 6 states
    VectorUtype u_temp;
    u_temp << 0, 0, 0, params.m*params.g;

    // X_tray and U_tray
950
951
    X_tray.clear();
    U_tray.clear();
roangel's avatar
roangel committed
952
953
954
955
956
957
    for(int i = 0; i < N; i++)
    {
        X_tray.push_back(x0);
        U_tray.push_back(u_temp);
    }

958
    // cout << "filled X_tray and U_tray:" << endl;
959

960
961
962
    // cout << "X_tray:" << endl;
    // for(int i=0; i < X_tray.size(); i++)
    //     cout << X_tray[i].format(CleanFmt) << endl;
963

964
965
966
    // cout << "U_tray:" << endl;
    // for(int i=0; i < U_tray.size(); i++)
    //     cout << U_tray[i].format(CleanFmt) << endl;
967

roangel's avatar
roangel committed
968
969
970
    // fill A_tray, B_tray, g_tray with initial values
    get_matrices_linearization_affine(X_tray, U_tray, params, A_tray, B_tray, g_tray);

971
    // cout << "filled A_tray  B_tray and g_tray:" << endl;
972

973
974
975
    // cout << "A_tray:" << endl;
    // for(int i=0; i < A_tray.size(); i++)
    //     cout << A_tray[i].format(CleanFmt) << endl;
976

977
978
979
    // cout << "B_tray:" << endl;
    // for(int i=0; i < B_tray.size(); i++)
    //     cout << B_tray[i].format(CleanFmt) << endl;
980

981
982
983
    // cout << "g_tray:" << endl;
    // for(int i=0; i < g_tray.size(); i++)
    //     cout << g_tray[i].format(CleanFmt) << endl;
984

roangel's avatar
roangel committed
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
1012
1013
1014
1015
1016
    VectorXtype q_vec;
    q_vec << 5000, 5000, 5000, 500, 500, 500;
    VectorUtype r_vec;
    r_vec << 2000, 2000, 10000, 150000;

    Q = q_vec.asDiagonal();
    R = r_vec.asDiagonal();

    P <<97395, 0    , 0     , 12731, 0    , 0    ,
        0    , 97395, 0     , 0    , 12731, 0    ,
        0    , 0    , 124811, 0    , 0    , 31321,
        12731, 0    , 0     , 7027 , 0    , 0    ,
        0    , 12731, 0     , 0    , 7027 , 0    ,
        0    , 0    , 31321 , 0    , 0    , 22707;

    // X_ref and U_ref. These don't change at all
    X_ref.resize(N_x*(N+1));
    U_ref.resize(N_u*N);

    VectorXtype x_ref;
    x_ref << 0,0,0,0,0,0;
    VectorUtype u_ref;
    u_ref << 0,0,0,params.m*params.g;

    for(int i = 0; i < N+1; i++)
    {
        X_ref.segment(i*N_x, N_x) = x_ref;
        if(i < N)
            U_ref.segment(i*N_u, N_u) = u_ref;
    }
}

1017

1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033


//    ----------------------------------------------------------------------------------
//    L       OOO     A    DDDD
//    L      O   O   A A   D   D
//    L      O   O  A   A  D   D
//    L      O   O  AAAAA  D   D
//    LLLLL   OOO   A   A  DDDD
//
//    PPPP     A    RRRR     A    M   M  EEEEE  TTTTT  EEEEE  RRRR    SSSS
//    P   P   A A   R   R   A A   MM MM  E        T    E      R   R  S
//    PPPP   A   A  RRRR   A   A  M M M  EEE      T    EEE    RRRR    SSS
//    P      AAAAA  R  R   AAAAA  M   M  E        T    E      R  R       S
//    P      A   A  R   R  A   A  M   M  EEEEE    T    EEEEE  R   R  SSSS
//    ----------------------------------------------------------------------------------

1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045

// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
{
	// Extract from the "msg" for which controller the and from where to fetch the YAML
	// parameters
	int controller_to_fetch_yaml = msg.data;

	// Switch between fetching for the different controllers and from different locations
	switch(controller_to_fetch_yaml)
	{

1046
		// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
1047
		case FETCH_YAML_MPC_CONTROLLER_FROM_OWN_AGENT:
1048
		{
1049
			// Let the user know that this message was received
1050
			ROS_INFO("[MPC CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this agent.");
1051
			// Create a node handle to the parameter service running on this agent's machine
1052
			ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
1053
			// Call the function that fetches the parameters
1054
1055
			fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
			break;
1056
		}
1057

1058
		// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
1059
		case FETCH_YAML_MPC_CONTROLLER_FROM_COORDINATOR:
1060
1061
		{
			// Let the user know that this message was received
1062
			ROS_INFO("[MPC CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
1063
			// Create a node handle to the parameter service running on the coordinator machine
1064
			ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service);
1065
1066
1067
1068
1069
			// Call the function that fetches the parameters
			fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
			break;
		}

1070
		default:
1071
		{
1072
			// Let the user know that the command was not relevant
1073
1074
			//ROS_INFO("The CustomControllerService received the message that YAML parameters were (re-)loaded");
			//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
1075
			break;
1076
		}
1077
1078
1079
1080
	}
}


1081
// This function CAN BE edited for successful completion of the PPS exercise, and the
1082
// use of parameters fetched from the YAML file is highly recommended to make tuning of
1083
// your controller easier and quicker.
1084
void fetchYamlParameters(ros::NodeHandle& nodeHandle)
1085
{
1086
	// Here we load the parameters that are specified in the CustomController.yaml file
1087

1088
	// Add the "CustomController" namespace to the "nodeHandle"
1089
	ros::NodeHandle nodeHandle_for_MpcController(nodeHandle, "MpcController");
1090

1091
	// > The mass of the crazyflie
1092
	cf_mass = getParameterFloat(nodeHandle_for_MpcController , "mass");
1093

1094
1095
	// Display one of the YAML parameters to debug if it is working correctly
	//ROS_INFO_STREAM("DEBUGGING: mass leaded from loacl file = " << cf_mass );
1096

1097
1098
	// > The frequency at which the "computeControlOutput" is being called, as determined
	//   by the frequency at which the Vicon system provides position and attitude data
1099
	control_frequency = getParameterFloat(nodeHandle_for_MpcController, "control_frequency");
1100

1101
1102
	// > The co-efficients of the quadratic conversation from 16-bit motor command to
	//   thrust force in Newtons
1103
	getParameterFloatVector(nodeHandle_for_MpcController, "motorPoly", motorPoly, 3);
1104

1105
1106

	// DEBUGGING: Print out one of the parameters that was loaded
1107
	ROS_INFO_STREAM("[MPC CONTROLLER] DEBUGGING: the fetched CustomController/mass = " << cf_mass);
1108

1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
1120
1121
1122
1123
1124
    getParameterFloatVector(nodeHandle_for_MpcController, "gainMatrixRollRate_Nested",             gainMatrixRollRate_Nested,             3);
	getParameterFloatVector(nodeHandle_for_MpcController, "gainMatrixPitchRate_Nested",            gainMatrixPitchRate_Nested,            3);
	getParameterFloatVector(nodeHandle_for_MpcController, "gainMatrixYawRate_Nested",              gainMatrixYawRate_Nested,              3);


    // THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
	// > For the (x,y,z) position
	getParameterFloatVector(nodeHandle_for_MpcController, "PMKF_Ahat_row1_for_positions",  PMKF_Ahat_row1_for_positions,  2);
	getParameterFloatVector(nodeHandle_for_MpcController, "PMKF_Ahat_row2_for_positions",  PMKF_Ahat_row2_for_positions,  2);
	getParameterFloatVector(nodeHandle_for_MpcController, "PMKF_Kinf_for_positions"     ,  PMKF_Kinf_for_positions     ,  2);
	// > For the (roll,pitch,yaw) angles
	getParameterFloatVector(nodeHandle_for_MpcController, "PMKF_Ahat_row1_for_angles",  PMKF_Ahat_row1_for_angles,  2);
	getParameterFloatVector(nodeHandle_for_MpcController, "PMKF_Ahat_row2_for_angles",  PMKF_Ahat_row2_for_angles,  2);
	getParameterFloatVector(nodeHandle_for_MpcController, "PMKF_Kinf_for_angles"     ,  PMKF_Kinf_for_angles     ,  2);


1125
1126
1127
	// Call the function that computes details an values that are needed from these
	// parameters loaded above
	processFetchedParameters();
1128
1129
1130
1131
1132
1133
}


// This function CAN BE edited for successful completion of the PPS exercise, and the
// use of parameters loaded from the YAML file is highly recommended to make tuning of
// your controller easier and quicker.
1134
void processFetchedParameters()
1135
1136
1137
1138
{
    // Compute the feed-forward force that we need to counteract gravity (i.e., mg)
    // > in units of [Newtons]
    gravity_force = cf_mass * 9.81/(1000*4);
1139
    // DEBUGGING: Print out one of the computed quantities
1140
	ROS_INFO_STREAM("[MPC CONTROLLER] DEBUGGING: thus the graity force = " << gravity_force);
1141
}
1142

1143

1144

1145
1146
1147
1148
1149
1150
1151
//    ----------------------------------------------------------------------------------
//     GGGG  EEEEE  TTTTT  PPPP     A    RRRR     A    M   M   ( )
//    G      E        T    P   P   A A   R   R   A A   MM MM  (   )
//    G      EEE      T    PPPP   A   A  RRRR   A   A  M M M  (   )
//    G   G  E        T    P      AAAAA  R  R   AAAAA  M   M  (   )
//     GGGG  EEEEE    T    P      A   A  R   R  A   A  M   M   ( )
//    ----------------------------------------------------------------------------------
1152
1153


1154
// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
1155
1156
1157
1158
1159
1160
1161
1162
1163
1164
1165
float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
{
    float val;
    if(!nodeHandle.getParam(name, val))
    {
        ROS_ERROR_STREAM("missing parameter '" << name << "'");
    }
    return val;
}
// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length)
1166
1167
1168
1169
1170
1171
1172
1173
1174
{
    if(!nodeHandle.getParam(name, val)){
        ROS_ERROR_STREAM("missing parameter '" << name << "'");
    }
    if(val.size() != length) {
        ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
    }
}
// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
1175
int getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
1176
{
1177
    int val;
1178
1179
1180
1181
1182
1183
1184
    if(!nodeHandle.getParam(name, val))
    {
        ROS_ERROR_STREAM("missing parameter '" << name << "'");
    }
    return val;
}
// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
1185
void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length)
1186
{
1187
1188
1189
1190
1191
1192
1193
1194
1195
1196
1197
1198
1199
1200
1201
1202
1203
1204
1205
1206
1207
1208
1209
1210
    if(!nodeHandle.getParam(name, val)){
        ROS_ERROR_STREAM("missing parameter '" << name << "'");
    }
    if(val.size() != length) {
        ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
    }
}
// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val)
{
    if(!nodeHandle.getParam(name, val)){
        ROS_ERROR_STREAM("missing parameter '" << name << "'");
    }
    return val.size();
}
// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
{
    bool val;
    if(!nodeHandle.getParam(name, val))
    {
        ROS_ERROR_STREAM("missing parameter '" << name << "'");
    }
    return val;
1211
}