DemoControllerService.h 19.1 KB
Newer Older
Paul Beuchat's avatar
Paul Beuchat committed
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
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
56
57
58
//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
//
//    This file is part of D-FaLL-System.
//    
//    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.
//    
//    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.
//    
//    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/>.
//    
//
//    ----------------------------------------------------------------------------------
//    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
//
//    ----------------------------------------------------------------------------------





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

//some useful libraries
#include <math.h>
#include <stdlib.h>
#include "ros/ros.h"
#include <ros/package.h>

//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"
#include "d_fall_pps/DebugMsg.h"
59
#include "d_fall_pps/CustomButton.h"
Paul Beuchat's avatar
Paul Beuchat committed
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

#include <std_msgs/Int32.h>





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

// Universal constants
#define PI 3.1415926535

// These constants define the modes that can be used for controller the Crazyflie 2.0,
// 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.
94
95
96
97
#define CF_COMMAND_TYPE_MOTOR   6
#define CF_COMMAND_TYPE_RATE    7
#define CF_COMMAND_TYPE_ANGLE   8

Paul Beuchat's avatar
Paul Beuchat committed
98
99
100
101

// These constants define the controller used for computing the response in the
// "calculateControlOutput" function
// The following is a short description about each mode:
102
103
104
105
106
107
108
109
110
111
//
// LQR_MODE_MOTOR     LQR controller based on the state vector:
//                    [position,velocity,angles,angular velocity]
//                    commands per motor thrusts
//
// LQR_MODE_ACTUATOR  LQR controller based on the state vector:
//                    [position,velocity,angles,angular velocity]
//                    commands actuators of total force and bodz torques
//
// LQR_MODE_RATE      LQR controller based on the state vector:
Paul Beuchat's avatar
Paul Beuchat committed
112
113
//                    [position,velocity,angles]
//
114
// LQR_MODE_ANGLE     LQR controller based on the state vector:
Paul Beuchat's avatar
Paul Beuchat committed
115
116
//                    [position,velocity]
//
117
118
119
120
121
122
#define CONTROLLER_MODE_LQR_MOTOR               1
#define CONTROLLER_MODE_LQR_ACTUATOR            2
#define CONTROLLER_MODE_LQR_RATE                3   // (DEFAULT)
#define CONTROLLER_MODE_LQR_ANGLE               4
#define CONTROLLER_MODE_LQR_ANGLE_RATE_NESTED   5
#define CONTROLLER_MODE_ANGLE_RESPONSE_TEST     6
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146


// These constants define the method used for estimating the Inertial
// frame state.
// All methods are run at all times, this flag indicates which estimate
// is passed onto the controller.
// The following is a short description about each mode:
//
// ESTIMATOR_METHOD_FINITE_DIFFERENCE
//       Takes the poisition and angles directly as measured,
//       and estimates the velocities as a finite different to the
//       previous measurement
//
// ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION
//       Uses a 2nd order random walk estimator independently for
//       each of (x,y,z,roll,pitch,yaw)
//
// ESTIMATOR_METHOD_QUADROTOR_MODEL_BASED
//       Uses the model of the quad-rotor and the previous inputs
//
#define ESTIMATOR_METHOD_FINITE_DIFFERENCE          1
#define ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION   2   // (DEFAULT)
#define ESTIMATOR_METHOD_QUADROTOR_MODEL_BASED      3

Paul Beuchat's avatar
Paul Beuchat committed
147
148

// Constants for feching the yaml paramters
149
150
151
152
//#define FETCH_YAML_SAFE_CONTROLLER_AGENT         1
#define FETCH_YAML_DEMO_CONTROLLER_AGENT         2
//#define FETCH_YAML_SAFE_CONTROLLER_COORDINATOR   3
#define FETCH_YAML_DEMO_CONTROLLER_COORDINATOR   4
Paul Beuchat's avatar
Paul Beuchat committed
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168

// Namespacing the package
using namespace d_fall_pps;





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

169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
// VARIABLES FOR SOME "ALMOST CONSTANTS"
// > Mass of the Crazyflie quad-rotor, in [grams]
float cf_mass;
// > Coefficients of the 16-bit command to thrust conversion
std::vector<float> motorPoly(3);
// The weight of the Crazyflie in [Newtons], i.e., mg
float gravity_force;
// One quarter of the "gravity_force"
float gravity_force_quarter;




// VARIABLES FOR THE CONTROLLER

184
185
186
// Frequency at which the controller is running
float vicon_frequency;

187
188
189
190
191
192
// Frequency at which the controller is running
float control_frequency;


// > The setpoints for (x,y,z) position and yaw angle, in that order
float setpoint[4] = {0.0,0.0,0.4,0.0};
Paul Beuchat's avatar
Paul Beuchat committed
193
194
195
196
197




// The controller type to run in the "calculateControlOutput" function
198
int controller_mode = CONTROLLER_MODE_LQR_RATE;
199
200


201
// The LQR Controller parameters for "CONTROLLER_MODE_LQR_MOTOR"
202
203
204
205
std::vector<float> gainMatrixMotor1 (12,0.0);
std::vector<float> gainMatrixMotor2 (12,0.0);
std::vector<float> gainMatrixMotor3 (12,0.0);
std::vector<float> gainMatrixMotor4 (12,0.0);
Paul Beuchat's avatar
Paul Beuchat committed
206

207
// The LQR Controller parameters for "CONTROLLER_MODE_LQR_ACTUATOR"
208
209
210
211
std::vector<float> gainMatrixThrust_TwelveStateVector (12,0.0);
std::vector<float> gainMatrixRollTorque               (12,0.0);
std::vector<float> gainMatrixPitchTorque              (12,0.0);
std::vector<float> gainMatrixYawTorque                (12,0.0);
212

213
// The LQR Controller parameters for "CONTROLLER_MODE_LQR_RATE"
214
215
216
217
std::vector<float> gainMatrixThrust_NineStateVector (9,0.0);
std::vector<float> gainMatrixRollRate               (9,0.0);
std::vector<float> gainMatrixPitchRate              (9,0.0);
std::vector<float> gainMatrixYawRate                (9,0.0);
Paul Beuchat's avatar
Paul Beuchat committed
218

219
// The LQR Controller parameters for "CONTROLLER_MODE_LQR_ANGLE"
220
221
222
223
std::vector<float> gainMatrixThrust_SixStateVector (6,0.0);
std::vector<float> gainMatrixRollAngle             (6,0.0);
std::vector<float> gainMatrixPitchAngle            (6,0.0);

224
// The LQR Controller parameters for "CONTROLLER_MODE_LQR_ANGLE_RATE_NESTED"
225
226
227
228
229
230
231
232
std::vector<float> gainMatrixThrust_SixStateVector_50Hz (6,0.0);
std::vector<float> gainMatrixRollAngle_50Hz             (6,0.0);
std::vector<float> gainMatrixPitchAngle_50Hz            (6,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);

233
int   lqr_angleRateNested_counter = 4;
234
235
236
237
float lqr_angleRateNested_prev_thrustAdjustment = 0.0;
float lqr_angleRateNested_prev_rollAngle        = 0.0;
float lqr_angleRateNested_prev_pitchAngle       = 0.0;
float lqr_angleRateNested_prev_yawAngle         = 0.0;
238

239
240
241
242
243
244
245
246
247
248
249
250
// The LQR Controller parameters for "CONTROLLER_MODE_ANGLE_RESPONSE_TEST"
int   angleResponseTest_counter = 4;
float angleResponseTest_prev_thrustAdjustment = 0.0;
float angleResponseTest_prev_rollAngle        = 0.0;
float angleResponseTest_prev_pitchAngle       = 0.0;
float angleResponseTest_prev_yawAngle         = 0.0;
float angleResponseTest_pitchAngle_degrees;
float angleResponseTest_pitchAngle_radians;
float angleResponseTest_distance_meters;



251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279

// The 16-bit command limits
float cmd_sixteenbit_min;
float cmd_sixteenbit_max;


// VARIABLES FOR THE ESTIMATOR

// Frequency at which the controller is running
float estimator_frequency;

// > A flag for which estimator to use:
int estimator_method = ESTIMATOR_METHOD_FINITE_DIFFERENCE;
// > The current state interial estimate,
//   for use by the controller
float current_stateInertialEstimate[12];

// > The measurement of the Crazyflie at the "current" time step,
//   to avoid confusion
float current_xzy_rpy_measurement[6];

// > The measurement of the Crazyflie at the "previous" time step,
//   used for computing finite difference velocities
float previous_xzy_rpy_measurement[6];

// > The full 12 state estimate maintained by the finite
//   difference state estimator
float stateInterialEstimate_viaFiniteDifference[12];

280
281
282
283
284
285
// > The full 12 state estimate maintained by the point mass
//   kalman filter state estimator
float stateInterialEstimate_viaPointMassKalmanFilter[12];

// THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
// > For the (x,y,z) position
286
287
288
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);
289
// > For the (roll,pitch,yaw) angles
290
291
292
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);
Paul Beuchat's avatar
Paul Beuchat committed
293
294
295



296
// VARIABLES FOR THE NAMESPACES FOR THE PARAMETER SERVICES
Paul Beuchat's avatar
Paul Beuchat committed
297
298
299
300
301
302
// > For the paramter service of this agent
std::string namespace_to_own_agent_parameter_service;
// > For the parameter service of the coordinator
std::string namespace_to_coordinator_parameter_service;


303
304
305
// ROS PUBLISHER FOR SENDING OUT THE DEBUG MESSAGES
ros::Publisher debugPublisher;

Paul Beuchat's avatar
Paul Beuchat committed
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
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
395

// VARIABLES RELATING TO PERFORMING THE CONVERSION INTO BODY FRAME

// Boolean whether to execute the convert into body frame function
bool shouldPerformConvertIntoBodyFrame = false;


// VARIABLES RELATING TO THE PUBLISHING OF A DEBUG MESSAGE

// Boolean indiciating whether the "Debug Message" of this agent should be published or not
bool shouldPublishDebugMessage = false;

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


// VARIABLES RELATING TO PUBLISHING CURRENT POSITION AND FOLLOWING ANOTHER AGENT'S
// POSITION

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

// Boolean indicating whether the (x,y,z,yaw) of this agent should be published or not
// > The default behaviour is: do not publish,
// > This varaible is changed based on parameters loaded from the YAML file
bool shouldPublishCurrent_xyz_yaw = false;

// Boolean indicating whether the (x,y,z,yaw) setpoint of this agent should adapted in
// an attempt to follow the "my_current_xyz_yaw_topic" from another agent
// > The default behaviour is: do not follow,
// > This varaible is changed based on parameters loaded from the YAML file
bool shouldFollowAnotherAgent = false;

// The order in which agents should follow eachother
// > This parameter is a vector of integers that specifies  agent ID's
// > The order of the agent ID's is the ordering of the line formation
// > i.e., the first ID is the leader, the second ID should follow the first ID, and so on
std::vector<int> follow_in_a_line_agentIDs(100);

// Integer specifying the ID of the agent that will be followed by this agent
// > The default behaviour not to follow any agent, indicated by ID zero
// > This varaible is changed based on parameters loaded from the YAML file
int agentID_to_follow = 0;

// ROS Publisher for my current (x,y,z,yaw) position
ros::Publisher my_current_xyz_yaw_publisher;

// ROS Subscriber for my position
ros::Subscriber xyz_yaw_to_follow_subscriber;


// RELEVANT NOTES ABOUT THE VARIABLES DECLARE HERE:
// The "CrazyflieData" type used for the "request" variable is a
// 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





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

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

// CONTROLLER COMPUTATIONS
396
// > The function that is called to "start" all estimation and control computations
Paul Beuchat's avatar
Paul Beuchat committed
397
bool calculateControlOutput(Controller::Request &request, Controller::Response &response);
398
399

// > The various functions that implement an LQR controller
400
401
402
403
404
405
void calculateControlOutput_viaLQR(                     float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
void calculateControlOutput_viaLQRforMotors(            float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
void calculateControlOutput_viaLQRforActuators(         float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
void calculateControlOutput_viaLQRforRates(             float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
void calculateControlOutput_viaLQRforAngles(            float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
void calculateControlOutput_viaLQRforAnglesRatesNested( float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
406
void calculateControlOutput_viaAngleResponseTest(       float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
407
408
409
410

// ESTIMATOR COMPUTATIONS
void performEstimatorUpdate_forStateInterial(Controller::Request &request);
void performEstimatorUpdate_forStateInterial_viaFiniteDifference();
411
void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter();
412

413
414
415
416
417

// PUBLISHING OF THE DEBUG MESSAGE
void construct_and_publish_debug_message(Controller::Request &request, Controller::Response &response);


418
419
// TRANSFORMATION FROM INTERIAL ESTIMATE TO BODY FRAME ERROR
void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setpoint[4], float (&bodyFrameError)[12]);
Paul Beuchat's avatar
Paul Beuchat committed
420
421

// TRANSFORMATION OF THE (x,y) INERTIAL FRAME ERROR INTO AN (x,y) BODY FRAME ERROR
422
void convertIntoBodyFrame(float stateInertial[12], float (&stateBody)[12], float yaw_measured);
Paul Beuchat's avatar
Paul Beuchat committed
423
424
425
426
427
428
429
430

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

// SETPOINT CHANGE CALLBACK
void setpointCallback(const Setpoint& newSetpoint);
void xyz_yaw_to_follow_callback(const Setpoint& newSetpoint);

431
432
433
// CUSTOM COMMAND RECEIVED CALLBACK
void customCommandReceivedCallback(const CustomButton& commandReceived);

434
435
436
// PUBLISH THE CURRENT X,Y,Z, AND YAW
void publish_current_xyz_yaw(float x, float y, float z, float yaw);

Paul Beuchat's avatar
Paul Beuchat committed
437
438
// LOAD PARAMETERS
float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
439
440
441
442
443
void  getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
int   getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
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);
Paul Beuchat's avatar
Paul Beuchat committed
444
445
446
447
448

void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
void fetchYamlParameters(ros::NodeHandle& nodeHandle);
void processFetchedParameters();