-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathrotorcraft.gen
734 lines (609 loc) · 26.7 KB
/
rotorcraft.gen
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
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
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
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
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
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
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
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
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
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
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
/*/
* Copyright (c) 2015-2023 LAAS/CNRS
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are
* met:
*
* 1. Redistributions of source code must retain the above copyright
* notice and this list of conditions.
* 2. Redistributions in binary form must reproduce the above copyright
* notice and this list of conditions in the documentation and/or
* other materials provided with the distribution.
*
* Anthony Mallet on Fri Feb 13 2015
*/
#pragma require "openrobots2-idl >= 2.0"
#include "or/pose/pose_estimator.gen"
#include "or/robot/rotorcraft.gen"
component rotorcraft {
version "3.4.1";
email "[email protected]";
lang "c";
require "genom3 >= 2.99.30";
codels-require "eigen3";
doc "Control multi-rotor UAVs using the telekyb3 protocol.";
provides or_rotorcraft;
uses or_pose_estimator;
exception e_sys { short code; string<128> what; };
exception e_baddev { string<256> dev; };
exception e_rotor_failure { unsigned short id; };
exception e_rotor_not_disabled { unsigned short id; };
exception e_rotor_stopped { unsigned short id; };
exception e_started, e_connection, e_range, e_input;
exception e_rate { string<8> what; };
exception e_bad_battery_percentage;
native conn_s;
native log_s;
port out or_pose_estimator::state imu {
doc "Provides current gyroscopes and accelerometer measurements.";
doc "";
doc "According to the nature of data, the port is filled with the imu";
doc "data timestamp `ts`, `intrinsic` true, no position (`pos` and";
doc "`pos_cov` are absent) and linear velocities `vx`, `vy`, `vz` set to";
doc "`NaN`. All other elements are always present.";
};
port out or_pose_estimator::state mag {
doc "Provides current magnetometer measurements.";
};
/* --- internal state ---------------------------------------------------- */
ids {
/* serial connection */
conn_s conn;
/* data timestamps and transmission rate */
struct sensor_time_s {
struct ts_s {
octet seq;
double last; /* last reception timestamp */
double ts, offset; /* clock estimator */
double rerr, rgain, rmed; /* rate estimator */
} imu, mag, motor[or_rotorcraft::max_rotors], battery;
struct rate_s {
double imu, mag, motor, battery;
} rate, measured_rate;
} sensor_time;
struct publish_time_s {
or::time::ts imu, mag, battery;
or::time::ts mstate[or_rotorcraft::max_rotors];
or::time::ts mwd[or_rotorcraft::max_rotors];
} publish_time, log_time;
/* battery data */
struct battery_s {
or::time::ts ts;
double min, max;
double level; //volts
octet status; // Get the status of the battery
} battery;
boolean simulate_battery;
/* imu calibration & filtering */
struct calibration_param_s {
double motion_tolerance;
} calib_param;
struct imu_calibration_s {
double gscale[9], gbias[3], gstddev[3];
double ascale[9], abias[3], astddev[3];
double mscale[9], mbias[3], mstddev[3];
double temp;
} imu_calibration;
boolean imu_calibration_updated;
struct imu_filter_s {
double galpha[3], aalpha[3], malpha[3]; /* filter coefficients */
double g[3], a[3], m[3]; /* raw data */
double gf[3], af[3], mf[3]; /* filtered data */
} imu_filter;
double imu_temp;
/* rotors data */
struct rotor_data_s {
or_rotorcraft::rotor_state state;
or::time::ts ts;
double wd;
octet clkrate;
boolean autoconf;
} rotor_data[or_rotorcraft::max_rotors];
/* servo parameters */
struct servo_s {
double timeout;
double ramp;
} servo;
/* logging */
log_s log;
};
attribute get_sensor_rate(out sensor_time.rate = {
.imu =: "Accelerometer and gyroscopes measurement frequency",
.mag =: "Magnetometer measurement frequency",
.motor =: "Various motor data measurement frequency",
.battery =: "Battery level measurement frequency"
},
out sensor_time.measured_rate = {
.imu =: "Accelerometer and gyroscopes effective frequency",
.mag =: "Magnetometer measurement frequency",
.motor =: "Various motor data effective frequency",
.battery =: "Battery level effective frequency"
}) {
doc "Get hardware sensor data publishing rate, see <<set_sensor_rate>>.";
};
function set_sensor_rate(in ids::sensor_time_s::rate_s rate = {
.imu = 1000.: "Accelerometer and gyroscopes measurement frequency",
.mag = 100.: "Magnetometer measurement frequency",
.motor = 50: "Various motor data measurement frequency",
.battery = 1: "Battery level measurement frequency"
}) {
doc "Set hardware sensor data publishing rate, in _Hz_";
doc "";
doc "`imu` and `mag` control the update frequency of port <<imu>> and";
doc "<<mag>> respectively, while `motor` and `battery` indirectly control";
doc "the port <<rotor_measure>>.";
doc "";
doc "CAUTION: The hardware may not be able to achieve the desired";
doc "frequency, especially for `motor` data when many motors are";
doc "controlled. In this case, no error will be reported, but the ports";
doc "update rate may be lower than expected and the <<servo>> service";
doc "will smoothly stop the motors.";
validate mk_set_sensor_rate(in rate, in conn, inout imu_filter,
inout sensor_time);
codel rc_log_sensor_rate(ids in sensor_time.rate, inout log);
};
attribute get_battery(out battery = {
.min =: "Minimum acceptable battery voltage",
.max =: "Full battery voltage",
.level =: "Current battery voltage"
}) {
doc "Get current battery voltage and limits.";
};
attribute set_battery_limits(
in battery.min = 14.0 : "Minimum acceptable battery voltage",
in battery.max = 16.7 : "Full battery voltage") {
doc "Set battery minimum and full voltage";
doc "";
doc "This controls the computed `energy left` percentage in the "
"port <<rotor_measure>>.";
validate mk_set_battery_limits(in min, in max);
throw e_range;
};
attribute get_calibration_param(out calib_param = {
.motion_tolerance =: "Tolerance factor of the standstill detector"
}) {
doc "Get IMU calibration parameters. See <<set_calibration_param>>.";
};
attribute set_calibration_param(in calib_param = {
.motion_tolerance = 10: "Tolerance factor of the standstill detector"
}) {
doc "Set IMU calibration parameters.";
doc "";
doc "The `motion_tolerance` is a multiplicative factor the controls the";
doc "sensitivity of the standstill detector used by <<calibrate_imu>>.";
doc "`motion_tolerance` must be greater than 1.0. The closer it is to 1.0,";
doc "the more the detector will be sensitive to slight motion, making the";
doc "calibration procedure practically cumbersome but hopefully more";
doc "precise. A good tradeoff is 10.0, which is the default.";
};
attribute get_imu_calibration(out imu_calibration = {
.gscale =: "Gyroscopes 3×3 scaling matrix (row major)",
.gbias =: "Gyroscopes bias vector",
.gstddev =: "Gyroscopes measurement noise",
.ascale =: "Accelerometers 3×3 scaling matrix (row major)",
.abias =: "Accelerometers bias vector",
.astddev =: "Accelerometers measurement noise",
.temp =: "Average IMU temperature (°C)"
}) {
doc "Get current gyroscopes and accelerometer calibration data.";
};
function set_imu_calibration(in ids::imu_calibration_s imu_calibration = {
.gscale =: "Gyroscopes 3×3 scaling matrix (row major)",
.gbias =: "Gyroscopes bias vector",
.gstddev =: "Gyroscopes measurement noise",
.ascale =: "Accelerometers 3×3 scaling matrix (row major)",
.abias =: "Accelerometers bias vector",
.astddev =: "Accelerometers measurement noise",
.temp = 21.: "Average IMU temperature (°C)"
}) {
doc "Set current gyroscopes, accelerometer and magnetometer calibration";
doc "data.";
doc "";
doc "Calling this service is mandatory after each component start, in";
doc "order to obtain precise IMU measurements.";
doc "";
doc "Input parameters are typically those returned by a call to";
doc "<<get_imu_calibration>> after a successful <<calibrate_imu>>";
doc "(which see).";
codel rc_set_imu_calibration(local in imu_calibration,
ids out imu_calibration::out,
out imu_calibration_updated);
codel rc_log_imu_calibration(ids in imu_calibration, inout log);
};
function get_imu_filter(
out double gfc[3] =: "Gyroscope X,Y,Z cut-off frequencies",
out double afc[3] =: "Accelerometer X,Y,Z cut-off frequencies",
out double mfc[3] =: "Magnetometer X,Y,Z cut-off frequencies") {
codel rc_get_imu_filter(in imu_filter, in sensor_time.rate,
out gfc, out afc, out mfc);
};
function set_imu_filter(
in double gfc[3] =: "Gyroscope X,Y,Z cut-off frequencies",
in double afc[3] =: "Accelerometer X,Y,Z cut-off frequencies",
in double mfc[3] =: "Magnetometer X,Y,Z cut-off frequencies") {
codel rc_set_imu_filter(in gfc, in afc, in mfc, in sensor_time.rate,
out imu_filter);
codel rc_log_imu_filter(in gfc, in afc, in mfc, inout log);
};
attribute get_imu_temp(out imu_temp =: "IMU temperature (°C)") {
doc "Get current IMU temperature.";
};
attribute set_timeout(in servo.timeout = 30:"Startup timeout (s)") {
doc "Set motor startup timeout";
};
attribute set_ramp(in servo.ramp);
/* --- tasks ------------------------------------------------------------- */
const unsigned short control_period_ms = 1;
task main {
period control_period_ms ms;
codel<start> mk_main_init(out ::ids, in imu, in mag)
yield main;
codel<main> mk_main_perm(in conn, in battery,
in imu_calibration,
in rotor_data,
inout sensor_time, inout publish_time,
inout imu_calibration_updated,
out rotor_measure, out imu, out mag)
yield log;
codel<log> rc_main_log(in battery, in imu_temp, in rotor_data,
in sensor_time.measured_rate, in rotor_measure,
in imu, in mag, in imu_filter, inout log_time,
inout log)
yield pause::main;
codel<stop> mk_main_stop(inout log)
yield ether;
};
task comm {
codel<start> mk_comm_start()
yield poll;
async codel<poll> mk_comm_poll(in conn)
yield nodata, recv;
codel<nodata> mk_comm_nodata(inout conn,
inout imu_filter, inout sensor_time,
out imu, out mag, out rotor_data,
out battery, out imu_temp)
yield poll;
codel<recv> mk_comm_recv(inout conn, in imu_calibration, inout imu_filter,
inout sensor_time,
out imu, out mag, out rotor_data, inout battery, in simulate_battery,
out imu_temp)
yield poll, recv;
codel<stop> mk_comm_stop(inout conn)
yield ether;
throw e_sys;
};
/* --- hw connection ----------------------------------------------------- */
activity connect(
in string<64> serial = "/dev/ttyUSB0" :"Serial device",
in unsigned long baud = 0 :"Baud rate (0 = don't change)") {
doc "Connect to the hardware.";
doc "";
doc "`serial` is the device special file to open, at `baud` speed. If one";
doc "or more connections are already open, they are all closed first.";
doc "";
doc "See <<pconnect>> to deal with multiple hardware connections.";
task comm;
codel<start> mk_connect_start(in serial, in baud, inout conn,
inout sensor_time)
yield ether;
throw e_sys, e_baddev;
interrupt servo;
};
activity pconnect(
in string<64> serial = "/dev/ttyUSB0" :"Serial device",
in unsigned long baud = 0 :"Baud rate (0 = don't change)",
in boolean imu = TRUE :"Use IMU",
in boolean mag = TRUE :"Use magnetometer",
in boolean motor = TRUE :"Use motors",
in unsigned short offset = 0 :"Motor id offset") {
doc "Connect to multiple hardware devices.";
doc "";
doc "This works like <<connect>>, except that existing connections are not";
doc "closed, so that multiple devices can be connected simultaneously.";
doc "";
doc "`serial` is the device special file to open, at `baud` speed. If a";
doc "connection with the same `serial` is already open, it is closed and";
doc "replaced by a new one with updated parameters.";
doc "";
doc "`imu`, `mag` and `motor` flags indicates whether the corresponding";
doc "part should be used (`TRUE`) or ignored (`FALSE`).";
doc "";
doc "`offset` is a small integer added to the motor ids reported by the";
doc "hardware, so that the <<rotor_measure>> or <<rotor_input>> arrays";
doc "present an aggregated view of the different devices. For instance,";
doc "to connect two devices that both have 4 motors numbered from 1 to 4,";
doc "set the first offset to 0 and the second to 4, so that";
doc "<<rotor_measure>> (resp. <<rotor_input>>) will present (resp. use)";
doc "motor ids from 1 to 8 with the first half directed to the first";
doc "device and the second half to the second device.";
task comm;
codel<start> mk_pconnect_start(in serial, in baud,
local in imu, local in mag,
in motor, in offset,
inout conn, inout sensor_time)
yield ether;
throw e_sys, e_baddev;
interrupt servo;
};
activity disconnect() {
doc "Disconnect from the hardware";
task comm;
codel<start> mk_disconnect_start(inout conn)
yield ether;
};
activity monitor() {
doc "Monitor connection status";
task comm;
codel<start, sleep> mk_monitor_check(in conn) yield pause::sleep, ether;
};
function disable_motor(in unsigned short motor) {
doc "Disable checking a motor status when it is disconnected";
codel mk_disable_motor(in motor, in conn, out rotor_data);
};
function enable_motor(in unsigned short motor) {
doc "Disable checking a motor status when it is disconnected";
codel mk_enable_motor(in motor, in conn, out rotor_data);
};
function set_pid(in unsigned short motor = 1 :"Motor id",
in double Kp = 0.:"Proportional gain",
in double Ki = 0.:"Integral gain",
in double Kd = 0.:"Derivative gain",
in double f = 0. :"Derivative filtering pole") {
doc "Update the hardware PID controller parameters, on hardware";
doc "that implements this.";
codel mk_set_pid(in conn, in motor, in Kp, in Ki, in Kd, in f);
throw e_baddev;
};
/* --- calibration ------------------------------------------------------- */
activity calibrate_imu(
in double tstill = 2 :"Duration in seconds of standstill positions",
in unsigned short nposes = 10 :"Number of different standstill positions",
in string<64> path = "": "Log file name (or empty string for no log)") {
doc "Calibrate accelerometers, gyroscopes and magnetometer.";
doc "";
doc "This service computes the `3×3` scaling matrices and `3D` bias vector";
doc "for gyroscopes, accelerometers and magnetometers so that all data is";
doc "returned in a consistent, orthogonal frame of reference. This is done";
doc "by implementing the paper '`A robust and easy to implement method for";
doc "IMU calibration without external equipments, ICRA 2014`'. It requires";
doc "no external sensor and a minimum of 10 static poses spanning the";
doc "whole SO(3) space, with moderate motion in between. The standard";
doc "deviation of the sensor noise is also estimated.";
doc "";
doc "The `tstill` parameter controls the time after which a standstill";
doc "position is detected (2 seconds is fine), while `nposes` sets the";
doc "required number of such standstill positions (minimum 10). The ";
doc "duration of motion between two standstill positions must not exceed";
doc "thirty times the `tstill` parameter (60 seconds by default).";
doc "";
doc "While running the calibration, a progress indication will be reported";
doc "to the standard output of the component. You should first set the";
doc "platform in the first standstill orientation, then start the service.";
doc "The service will report `stay still` until it has acquired the";
doc "first pose, then report `acquired pose 1`. You can then move to the";
doc "next standstill orientation, leave it until you read the same";
doc "messages again, and so on for all the `nposes` orientations.";
doc "";
doc "For the calibration to be precise, all the orientations";
doc "have to be as different as possible one from each other. Also, when";
doc "moving from one orientation to another, try to perform a motion such";
doc "that the angular velocities on all 3 axis are not zero.";
doc "";
doc "If you don't read `stay still` after moving to a new";
doc "pose, this means that the platform may be vibrating or slightly";
doc "moving, and the standstill detection cannot work. After some time,";
doc "the service will eventually abort and also report it on the standard";
doc "output.";
doc "";
doc "Once all orientations have been acquired, the results are set for the";
doc "current running instance, and available with <<get_imu_calibration>>.";
doc "Make sure to save the results somewhere before stopping the";
doc "component, so that you can load them with";
doc "<<set_imu_calibration>> when you later restart.";
doc "";
doc "If a log file name has been specified in `path`, the file is filled";
doc "with all samples acquired during calibration, corrected with the";
doc "newly estimated calibration parameters. In addition, a boolean";
doc "indicates for each sample if it is considered as part of a standstill";
doc "position or not, so that the quality of the calibration can be";
doc "visually assessed.";
doc "";
doc "CAUTION: This procedure does not set any particular vertical axis";
doc "and the IMU will typically end up calibrated but not aligned with the";
doc "gravity. Use <<set_zero>> (after calibration) to align the IMU.";
task main;
codel<start> mk_calibrate_imu_start(in calib_param, in tstill, in nposes)
yield collect;
codel<collect> mk_calibrate_imu_collect(in path,
in imu_temp, in imu, in mag)
yield pause::collect, main;
codel<main> mk_calibrate_imu_main(in path, in sensor_time.rate,
out imu_calibration,
out imu_calibration_updated)
yield ether;
throw e_sys, e_connection;
interrupt calibrate_imu, calibrate_mag, set_zero;
};
activity calibrate_mag(
in double tstill = 2 :"Duration in seconds of standstill positions",
in string<64> path = "": "Log file name (or empty string for no log)") {
doc "Calibrate magnetometer.";
doc "";
doc "This service computes the `3×3` scaling matrices and `3D` bias vector";
doc "for the magnetometers. This is a stripped down version of ";
doc "<<calibrate_imu>>, which see.";
doc "";
doc "Two standstill positions are required, with a motion not exceeding";
doc "thirty times the `tsill` parameter (2 by default, so 60s of motion).";
doc "The motion should cover the full SO(3) space for best results.";
doc "";
task main;
codel<start> mk_calibrate_mag_start(in calib_param, in tstill)
yield collect;
codel<collect> mk_calibrate_imu_collect(in path,
in imu_temp, in imu, in mag)
yield pause::collect, main;
codel<main> mk_calibrate_mag_main(in path, out imu_calibration,
out imu_calibration_updated)
yield ether;
throw e_sys, e_connection;
interrupt calibrate_imu, calibrate_mag, set_zero;
};
activity set_zero(in double duration = 10.: "Averaging time (s)") {
doc "Align IMU frame with the gravity vector and reset gyroscopes bias.";
doc "";
doc "This service updates the `3×3` scaling matrices and `3D` bias vector";
doc "for both gyroscopes and accelerometers so that the current";
doc "accelerometer measurements are only on the Z axis and the gyroscopes";
doc "return a 0 angular velocity on each axis.";
doc "";
doc "While running this service, the platform should be perfectly";
doc "standstill and in a horizontal configuration (i.e. it's roll and";
doc "pitch angles are considered zero).";
doc "";
doc "After completion, the current calibration results are updated and";
doc "can be retrieved with <<get_imu_calibration>>.";
doc "";
doc "This service should be called quite often, as the gyroscopes bias";
doc "are much dependent on the temperature, so it is important to";
doc "estimate them well.";
task main;
local struct accum {
double data[3];
unsigned long count;
or::time::ts last;
} accum[3];
codel<start> mk_avgsensors_start(out accum)
yield collect;
codel<collect> mk_avgsensors_collect(in imu, in mag, inout accum,
inout duration)
yield pause::collect, main;
codel<main> mk_set_zero(inout accum,
out imu_calibration, out imu_calibration_updated)
yield ether;
throw e_sys;
interrupt calibrate_imu, set_zero, set_zero_velocity;
};
activity set_zero_velocity(in double duration = 10.: "Averaging time (s)") {
doc "Reset gyroscopes bias.";
doc "";
doc "This service updates the `3D` bias vector for gyroscopes so that the";
doc "the gyroscopes return a 0 angular velocity on each axis.";
doc "";
doc "While running this service, the platform should be perfectly";
doc "standstill. This is a subset of what <<set_zero>> does.";
doc "";
doc "After completion, the current calibration results are updated and";
doc "can be retrieved with <<get_imu_calibration>>.";
task main;
local accum accum[3];
codel<start> mk_avgsensors_start(out accum)
yield collect;
codel<collect> mk_avgsensors_collect(in imu, in mag, inout accum,
inout duration)
yield pause::collect, main;
codel<main> mk_set_zero_velocity(inout accum,
out imu_calibration,
out imu_calibration_updated)
yield ether;
throw e_sys;
interrupt calibrate_imu, set_zero, set_zero_velocity;
};
/* --- flight ------------------------------------------------------------ */
activity start() {
doc "Spin propellers at the lowest velocity";
task main;
local unsigned short state;
local unsigned long timeout;
codel<start> mk_start_start(in conn, in servo, out timeout, out state,
in rotor_data)
yield pause::start, monitor;
codel<monitor> mk_start_monitor(in conn, in sensor_time,
inout timeout, inout state,
in rotor_data)
yield pause::monitor, ether;
codel<stop> mk_start_stop(in conn, in rotor_data)
yield pause::stop, ether;
interrupt start;
throw e_connection, e_started, e_sys, e_rotor_failure, e_rotor_stopped,
e_rate, e_rotor_not_disabled;
};
activity servo() {
doc "Control the propellers according to the given velocities";
task main;
local double scale;
codel<start> mk_servo_start(out scale)
yield main;
codel<main> mk_servo_main(in conn, in sensor_time, inout rotor_data,
in rotor_input, in servo, inout scale)
yield pause::main, stop;
codel<stop> mk_servo_stop(in conn)
yield ether;
interrupt servo;
throw e_connection, e_rotor_failure, e_rotor_stopped, e_rate, e_input;
};
function set_velocity(
in or_rotorcraft::rotor_control desired =: "Propeller velocities") {
doc "Set the given propeller velocity, once";
validate mk_validate_input(in rotor_data, inout desired);
codel mk_set_velocity(in conn, inout rotor_data, in desired);
interrupt servo;
throw e_connection, e_rotor_failure;
};
function set_throttle(
in or_rotorcraft::rotor_control desired =: "Propeller throttles") {
doc "Set the given propeller voltage";
validate mk_validate_input(in rotor_data, inout desired);
codel mk_set_throttle(in conn, inout rotor_data, in desired);
interrupt servo;
throw e_connection, e_rotor_failure;
};
activity stop() {
doc "Stop all propellers";
task main;
codel<start> mk_stop(in conn, in rotor_data)
yield pause::start, ether;
interrupt servo, start;
};
/* --- logging ----------------------------------------------------------- */
activity log(in string<64> path = "/tmp/rotorcraft.log": "Log file name",
in unsigned long decimation = 1: "Reduced logging frequency") {
doc "Log IMU and commanded wrench";
task main;
validate rc_log_open(in path, in decimation, inout log);
codel<start> rc_log_header(in imu_calibration,
in imu_filter, in sensor_time.rate, inout log)
yield ether;
throw e_sys;
};
function log_stop() {
doc "Stop logging";
codel mk_log_stop(out log);
};
function log_info(out unsigned long miss = :"Missed log entries",
out unsigned long total = :"Total log entries") {
doc "Show missed log entries";
codel mk_log_info(in log, out miss, out total);
};
activity get_sensor_average(
in double duration = 10.: "Averaging time (s)",
out or::t3d::avel gyr, out or::t3d::acc acc, out or::t3d::pos mag) {
doc "Compute gyroscopes, accelerometers and magnetomers average.";
task main;
local accum accum[3];
codel<start> mk_avgsensors_start(out accum)
yield collect;
codel<collect> mk_avgsensors_collect(in imu, port in mag, inout accum,
inout duration)
yield pause::collect, main;
codel<main> mk_get_sensor_average(inout accum,
out gyr, out acc, local out mag)
yield ether;
throw e_sys;
};
attribute should_simulate_battery(in simulate_battery = FALSE : "Simulate battery (TRUE/FALSE). Default is FALSE.") {
doc "Simulate battery";
};
};