/
simulator_mavlink.cpp
1249 lines (969 loc) · 34.4 KB
/
simulator_mavlink.cpp
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
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/****************************************************************************
*
* Copyright (c) 2015 Mark Charlebois. All rights reserved.
* Copyright (c) 2016 Anton Matosov. All rights reserved.
* Copyright (c) 2018 PX4 Development Team. 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, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <termios.h>
#include <px4_log.h>
#include <px4_time.h>
#include <px4_tasks.h>
#include "simulator.h"
#include <simulator_config.h>
#include "errno.h"
#include <lib/ecl/geo/geo.h>
#include <drivers/drv_pwm_output.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <netinet/tcp.h>
#include <pthread.h>
#include <conversion/rotation.h>
#include <mathlib/mathlib.h>
#include <limits>
#ifdef ENABLE_UART_RC_INPUT
#ifndef B460800
#define B460800 460800
#endif
#ifndef B921600
#define B921600 921600
#endif
static int openUart(const char *uart_name, int baud);
#endif
static int _fd;
static unsigned char _buf[2048];
static sockaddr_in _srcaddr;
static unsigned _addrlen = sizeof(_srcaddr);
static hrt_abstime batt_sim_start = 0;
const unsigned mode_flag_armed = 128;
const unsigned mode_flag_custom = 1;
using namespace simulator;
using namespace time_literals;
mavlink_hil_actuator_controls_t Simulator::actuator_controls_from_outputs(const actuator_outputs_s &actuators)
{
mavlink_hil_actuator_controls_t msg{};
msg.time_usec = hrt_absolute_time() + hrt_absolute_time_offset();
bool armed = (_vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED);
const float pwm_center = (PWM_DEFAULT_MAX + PWM_DEFAULT_MIN) / 2;
int _system_type = _param_mav_type.get();
/* scale outputs depending on system type */
if (_system_type == MAV_TYPE_QUADROTOR ||
_system_type == MAV_TYPE_HEXAROTOR ||
_system_type == MAV_TYPE_OCTOROTOR ||
_system_type == MAV_TYPE_VTOL_DUOROTOR ||
_system_type == MAV_TYPE_VTOL_QUADROTOR ||
_system_type == MAV_TYPE_VTOL_TILTROTOR ||
_system_type == MAV_TYPE_VTOL_RESERVED2) {
/* multirotors: set number of rotor outputs depending on type */
unsigned n;
switch (_system_type) {
case MAV_TYPE_VTOL_DUOROTOR:
n = 2;
break;
case MAV_TYPE_QUADROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
n = 4;
break;
case MAV_TYPE_VTOL_RESERVED2:
// this is the standard VTOL / quad plane with 5 propellers
n = 5;
break;
case MAV_TYPE_HEXAROTOR:
n = 6;
break;
default:
n = 8;
break;
}
for (unsigned i = 0; i < 16; i++) {
if (actuators.output[i] > PWM_DEFAULT_MIN / 2) {
if (i < n) {
/* scale PWM out PWM_DEFAULT_MIN..PWM_DEFAULT_MAX us to 0..1 for rotors */
msg.controls[i] = (actuators.output[i] - PWM_DEFAULT_MIN) / (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN);
} else {
/* scale PWM out PWM_DEFAULT_MIN..PWM_DEFAULT_MAX us to -1..1 for other channels */
msg.controls[i] = (actuators.output[i] - pwm_center) / ((PWM_DEFAULT_MAX - PWM_DEFAULT_MIN) / 2);
}
} else {
/* send 0 when disarmed and for disabled channels */
msg.controls[i] = 0.0f;
}
}
} else {
/* fixed wing: scale throttle to 0..1 and other channels to -1..1 */
for (unsigned i = 0; i < 16; i++) {
if (actuators.output[i] > PWM_DEFAULT_MIN / 2) {
if (i != 4) {
/* scale PWM out PWM_DEFAULT_MIN..PWM_DEFAULT_MAX us to -1..1 for normal channels */
msg.controls[i] = (actuators.output[i] - pwm_center) / ((PWM_DEFAULT_MAX - PWM_DEFAULT_MIN) / 2);
} else {
/* scale PWM out PWM_DEFAULT_MIN..PWM_DEFAULT_MAX us to 0..1 for throttle */
msg.controls[i] = (actuators.output[i] - PWM_DEFAULT_MIN) / (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN);
}
} else {
/* set 0 for disabled channels */
msg.controls[i] = 0.0f;
}
}
}
msg.mode = mode_flag_custom;
msg.mode |= (armed) ? mode_flag_armed : 0;
msg.flags = 0;
return msg;
}
void Simulator::send_controls()
{
// copy new actuator data if available
bool updated = false;
orb_check(_actuator_outputs_sub, &updated);
if (updated) {
actuator_outputs_s actuators{};
orb_copy(ORB_ID(actuator_outputs), _actuator_outputs_sub, &actuators);
if (actuators.timestamp > 0) {
const mavlink_hil_actuator_controls_t hil_act_control = actuator_controls_from_outputs(actuators);
mavlink_message_t message{};
mavlink_msg_hil_actuator_controls_encode(_param_mav_sys_id.get(), _param_mav_comp_id.get(), &message, &hil_act_control);
PX4_DEBUG("sending controls t=%ld (%ld)", actuators.timestamp, hil_act_control.time_usec);
send_mavlink_message(message);
}
}
}
static void fill_rc_input_msg(input_rc_s *rc, mavlink_rc_channels_t *rc_channels)
{
rc->timestamp = hrt_absolute_time();
rc->timestamp_last_signal = rc->timestamp;
rc->channel_count = rc_channels->chancount;
rc->rssi = rc_channels->rssi;
rc->values[0] = rc_channels->chan1_raw;
rc->values[1] = rc_channels->chan2_raw;
rc->values[2] = rc_channels->chan3_raw;
rc->values[3] = rc_channels->chan4_raw;
rc->values[4] = rc_channels->chan5_raw;
rc->values[5] = rc_channels->chan6_raw;
rc->values[6] = rc_channels->chan7_raw;
rc->values[7] = rc_channels->chan8_raw;
rc->values[8] = rc_channels->chan9_raw;
rc->values[9] = rc_channels->chan10_raw;
rc->values[10] = rc_channels->chan11_raw;
rc->values[11] = rc_channels->chan12_raw;
rc->values[12] = rc_channels->chan13_raw;
rc->values[13] = rc_channels->chan14_raw;
rc->values[14] = rc_channels->chan15_raw;
rc->values[15] = rc_channels->chan16_raw;
rc->values[16] = rc_channels->chan17_raw;
rc->values[17] = rc_channels->chan18_raw;
}
void Simulator::update_sensors(const mavlink_hil_sensor_t *imu)
{
// write sensor data to memory so that drivers can copy data from there
RawMPUData mpu = {};
mpu.accel_x = imu->xacc;
mpu.accel_y = imu->yacc;
mpu.accel_z = imu->zacc;
mpu.temp = imu->temperature;
mpu.gyro_x = imu->xgyro;
mpu.gyro_y = imu->ygyro;
mpu.gyro_z = imu->zgyro;
write_MPU_data(&mpu);
perf_begin(_perf_mpu);
RawAccelData accel = {};
accel.x = imu->xacc;
accel.y = imu->yacc;
accel.z = imu->zacc;
write_accel_data(&accel);
perf_begin(_perf_accel);
RawMagData mag = {};
mag.x = imu->xmag;
mag.y = imu->ymag;
mag.z = imu->zmag;
write_mag_data(&mag);
perf_begin(_perf_mag);
RawBaroData baro = {};
// Get air pressure and pressure altitude
// valid for troposphere (below 11km AMSL)
baro.pressure = imu->abs_pressure;
baro.temperature = imu->temperature;
write_baro_data(&baro);
RawAirspeedData airspeed = {};
airspeed.temperature = imu->temperature;
// FIXME: diff_pressure needs some noise to pass preflight checks, so we just take the
// noise from the gyro.
airspeed.diff_pressure = imu->diff_pressure + ((imu->ygyro > 0) ? 0.001f : 0.0f);
write_airspeed_data(&airspeed);
}
void Simulator::update_gps(const mavlink_hil_gps_t *gps_sim)
{
RawGPSData gps = {};
gps.timestamp = hrt_absolute_time();
gps.lat = gps_sim->lat;
gps.lon = gps_sim->lon;
gps.alt = gps_sim->alt;
gps.eph = gps_sim->eph;
gps.epv = gps_sim->epv;
gps.vel = gps_sim->vel;
gps.vn = gps_sim->vn;
gps.ve = gps_sim->ve;
gps.vd = gps_sim->vd;
gps.cog = gps_sim->cog;
gps.fix_type = gps_sim->fix_type;
gps.satellites_visible = gps_sim->satellites_visible;
write_gps_data((void *)&gps);
}
void Simulator::handle_message(const mavlink_message_t *msg)
{
switch (msg->msgid) {
case MAVLINK_MSG_ID_HIL_SENSOR:
handle_message_hil_sensor(msg);
break;
case MAVLINK_MSG_ID_HIL_OPTICAL_FLOW:
handle_message_optical_flow(msg);
break;
case MAVLINK_MSG_ID_ODOMETRY:
handle_message_odometry(msg);
break;
case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
handle_message_vision_position_estimate(msg);
break;
case MAVLINK_MSG_ID_DISTANCE_SENSOR:
handle_message_distance_sensor(msg);
break;
case MAVLINK_MSG_ID_HIL_GPS:
handle_message_hil_gps(msg);
break;
case MAVLINK_MSG_ID_RC_CHANNELS:
handle_message_rc_channels(msg);
break;
case MAVLINK_MSG_ID_LANDING_TARGET:
handle_message_landing_target(msg);
break;
case MAVLINK_MSG_ID_HIL_STATE_QUATERNION:
handle_message_hil_state_quaternion(msg);
break;
}
}
void Simulator::handle_message_distance_sensor(const mavlink_message_t *msg)
{
mavlink_distance_sensor_t dist;
mavlink_msg_distance_sensor_decode(msg, &dist);
publish_distance_topic(&dist);
}
void Simulator::handle_message_hil_gps(const mavlink_message_t *msg)
{
mavlink_hil_gps_t gps_sim;
mavlink_msg_hil_gps_decode(msg, &gps_sim);
if (_publish) {
//PX4_WARN("FIXME: Need to publish GPS topic. Not done yet.");
}
update_gps(&gps_sim);
}
void Simulator::handle_message_hil_sensor(const mavlink_message_t *msg)
{
mavlink_hil_sensor_t imu;
mavlink_msg_hil_sensor_decode(msg, &imu);
// set temperature to a decent value
imu.temperature = 32.0f;
struct timespec ts;
abstime_to_ts(&ts, imu.time_usec);
px4_clock_settime(CLOCK_MONOTONIC, &ts);
hrt_abstime now_us = hrt_absolute_time();
#if 0
// This is just for to debug missing HIL_SENSOR messages.
static hrt_abstime last_time = 0;
hrt_abstime diff = now_us - last_time;
float step = diff / 4000.0f;
if (step > 1.1f || step < 0.9f) {
PX4_INFO("HIL_SENSOR: imu time_usec: %lu, time_usec: %lu, diff: %lu, step: %.2f", imu.time_usec, now_us, diff, step);
}
last_time = now_us;
#endif
if (_publish) {
publish_sensor_topics(&imu);
}
update_sensors(&imu);
// battery simulation (limit update to 100Hz)
if (hrt_elapsed_time(&_battery_status.timestamp) >= 10_ms) {
const float discharge_interval_us = _param_sim_bat_drain.get() * 1000 * 1000;
bool armed = (_vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED);
if (!armed || batt_sim_start == 0 || batt_sim_start > now_us) {
batt_sim_start = now_us;
}
float ibatt = -1.0f; // no current sensor in simulation
const float minimum_percentage = 0.499f; // change this value if you want to simulate low battery reaction
/* Simulate the voltage of a linearly draining battery but stop at the minimum percentage */
float battery_percentage = 1.0f - (now_us - batt_sim_start) / discharge_interval_us;
battery_percentage = math::max(battery_percentage, minimum_percentage);
float vbatt = math::gradual(battery_percentage, 0.f, 1.f, _battery.empty_cell_voltage(), _battery.full_cell_voltage());
vbatt *= _battery.cell_count();
const float throttle = 0.0f; // simulate no throttle compensation to make the estimate predictable
_battery.updateBatteryStatus(now_us, vbatt, ibatt, true, true, 0, throttle, armed, &_battery_status);
// publish the battery voltage
int batt_multi;
orb_publish_auto(ORB_ID(battery_status), &_battery_pub, &_battery_status, &batt_multi, ORB_PRIO_HIGH);
}
}
void Simulator::handle_message_hil_state_quaternion(const mavlink_message_t *msg)
{
mavlink_hil_state_quaternion_t hil_state;
mavlink_msg_hil_state_quaternion_decode(msg, &hil_state);
uint64_t timestamp = hrt_absolute_time();
/* attitude */
struct vehicle_attitude_s hil_attitude = {};
{
hil_attitude.timestamp = timestamp;
matrix::Quatf q(hil_state.attitude_quaternion);
q.copyTo(hil_attitude.q);
hil_attitude.rollspeed = hil_state.rollspeed;
hil_attitude.pitchspeed = hil_state.pitchspeed;
hil_attitude.yawspeed = hil_state.yawspeed;
// always publish ground truth attitude message
int hilstate_multi;
orb_publish_auto(ORB_ID(vehicle_attitude_groundtruth), &_attitude_pub, &hil_attitude, &hilstate_multi, ORB_PRIO_HIGH);
}
/* global position */
struct vehicle_global_position_s hil_gpos = {};
{
hil_gpos.timestamp = timestamp;
hil_gpos.lat = hil_state.lat / 1E7;//1E7
hil_gpos.lon = hil_state.lon / 1E7;//1E7
hil_gpos.alt = hil_state.alt / 1E3;//1E3
hil_gpos.vel_n = hil_state.vx / 100.0f;
hil_gpos.vel_e = hil_state.vy / 100.0f;
hil_gpos.vel_d = hil_state.vz / 100.0f;
// always publish ground truth attitude message
int hil_gpos_multi;
orb_publish_auto(ORB_ID(vehicle_global_position_groundtruth), &_gpos_pub, &hil_gpos, &hil_gpos_multi, ORB_PRIO_HIGH);
}
/* local position */
struct vehicle_local_position_s hil_lpos = {};
{
hil_lpos.timestamp = timestamp;
double lat = hil_state.lat * 1e-7;
double lon = hil_state.lon * 1e-7;
if (!_hil_local_proj_inited) {
_hil_local_proj_inited = true;
map_projection_init(&_hil_local_proj_ref, lat, lon);
_hil_ref_timestamp = timestamp;
_hil_ref_lat = lat;
_hil_ref_lon = lon;
_hil_ref_alt = hil_state.alt / 1000.0f;
}
float x;
float y;
map_projection_project(&_hil_local_proj_ref, lat, lon, &x, &y);
hil_lpos.timestamp = timestamp;
hil_lpos.xy_valid = true;
hil_lpos.z_valid = true;
hil_lpos.v_xy_valid = true;
hil_lpos.v_z_valid = true;
hil_lpos.x = x;
hil_lpos.y = y;
hil_lpos.z = _hil_ref_alt - hil_state.alt / 1000.0f;
hil_lpos.vx = hil_state.vx / 100.0f;
hil_lpos.vy = hil_state.vy / 100.0f;
hil_lpos.vz = hil_state.vz / 100.0f;
matrix::Eulerf euler = matrix::Quatf(hil_attitude.q);
hil_lpos.yaw = euler.psi();
hil_lpos.xy_global = true;
hil_lpos.z_global = true;
hil_lpos.ref_lat = _hil_ref_lat;
hil_lpos.ref_lon = _hil_ref_lon;
hil_lpos.ref_alt = _hil_ref_alt;
hil_lpos.ref_timestamp = _hil_ref_timestamp;
hil_lpos.vxy_max = std::numeric_limits<float>::infinity();
hil_lpos.vz_max = std::numeric_limits<float>::infinity();
hil_lpos.hagl_min = std::numeric_limits<float>::infinity();
hil_lpos.hagl_max = std::numeric_limits<float>::infinity();
// always publish ground truth attitude message
int hil_lpos_multi;
orb_publish_auto(ORB_ID(vehicle_local_position_groundtruth), &_lpos_pub, &hil_lpos, &hil_lpos_multi, ORB_PRIO_HIGH);
}
}
void Simulator::handle_message_landing_target(const mavlink_message_t *msg)
{
mavlink_landing_target_t landing_target_mavlink;
mavlink_msg_landing_target_decode(msg, &landing_target_mavlink);
struct irlock_report_s report = {};
report.timestamp = hrt_absolute_time();
report.signature = landing_target_mavlink.target_num;
report.pos_x = landing_target_mavlink.angle_x;
report.pos_y = landing_target_mavlink.angle_y;
report.size_x = landing_target_mavlink.size_x;
report.size_y = landing_target_mavlink.size_y;
int irlock_multi;
orb_publish_auto(ORB_ID(irlock_report), &_irlock_report_pub, &report, &irlock_multi, ORB_PRIO_HIGH);
}
void Simulator::handle_message_odometry(const mavlink_message_t *msg)
{
publish_odometry_topic(msg);
}
void Simulator::handle_message_optical_flow(const mavlink_message_t *msg)
{
mavlink_hil_optical_flow_t flow;
mavlink_msg_hil_optical_flow_decode(msg, &flow);
publish_flow_topic(&flow);
}
void Simulator::handle_message_rc_channels(const mavlink_message_t *msg)
{
mavlink_rc_channels_t rc_channels;
mavlink_msg_rc_channels_decode(msg, &rc_channels);
fill_rc_input_msg(&_rc_input, &rc_channels);
// publish message
if (_publish) {
int rc_multi;
orb_publish_auto(ORB_ID(input_rc), &_rc_channels_pub, &_rc_input, &rc_multi, ORB_PRIO_HIGH);
}
}
void Simulator::handle_message_vision_position_estimate(const mavlink_message_t *msg)
{
publish_odometry_topic(msg);
}
void Simulator::send_mavlink_message(const mavlink_message_t &aMsg)
{
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
uint16_t bufLen = 0;
bufLen = mavlink_msg_to_send_buffer(buf, &aMsg);
ssize_t len;
if (_ip == InternetProtocol::UDP) {
len = ::sendto(_fd, buf, bufLen, 0, (struct sockaddr *)&_srcaddr, sizeof(_srcaddr));
} else {
len = ::send(_fd, buf, bufLen, 0);
}
if (len <= 0) {
PX4_WARN("Failed sending mavlink message: %s", strerror(errno));
}
}
void Simulator::poll_topics()
{
// copy new actuator data if available
bool updated = false;
orb_check(_vehicle_status_sub, &updated);
if (updated) {
orb_copy(ORB_ID(vehicle_status), _vehicle_status_sub, &_vehicle_status);
}
}
void *Simulator::sending_trampoline(void * /*unused*/)
{
_instance->send();
return nullptr;
}
void Simulator::send()
{
#ifdef __PX4_DARWIN
pthread_setname_np("sim_send");
#else
pthread_setname_np(pthread_self(), "sim_send");
#endif
// Before starting, we ought to send a heartbeat to initiate the SITL
// simulator to start sending sensor data which will set the time and
// get everything rolling.
// Without this, we get stuck at px4_poll which waits for a time update.
send_heartbeat();
px4_pollfd_struct_t fds[1] = {};
fds[0].fd = _actuator_outputs_sub;
fds[0].events = POLLIN;
while (true) {
// Wait for up to 100ms for data.
int pret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
if (pret == 0) {
// Timed out, try again.
continue;
}
if (pret < 0) {
PX4_ERR("poll error %s", strerror(errno));
continue;
}
if (fds[0].revents & POLLIN) {
// Got new data to read, update all topics.
parameters_update(false);
poll_topics();
send_controls();
}
}
}
void Simulator::request_hil_state_quaternion()
{
mavlink_command_long_t cmd_long = {};
mavlink_message_t message = {};
cmd_long.command = MAV_CMD_SET_MESSAGE_INTERVAL;
cmd_long.param1 = MAVLINK_MSG_ID_HIL_STATE_QUATERNION;
cmd_long.param2 = 5e3;
mavlink_msg_command_long_encode(_param_mav_sys_id.get(), _param_mav_comp_id.get(), &message, &cmd_long);
send_mavlink_message(message);
}
void Simulator::send_heartbeat()
{
mavlink_heartbeat_t hb = {};
mavlink_message_t message = {};
hb.autopilot = 12;
hb.base_mode |= (_vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) ? 128 : 0;
mavlink_msg_heartbeat_encode(_param_mav_sys_id.get(), _param_mav_comp_id.get(), &message, &hb);
send_mavlink_message(message);
}
void Simulator::initialize_sensor_data()
{
// Write sensor data to memory so that drivers can copy data from there.
RawMPUData mpu = {};
mpu.accel_z = CONSTANTS_ONE_G;
write_MPU_data(&mpu);
RawAccelData accel = {};
accel.z = CONSTANTS_ONE_G;
write_accel_data(&accel);
RawMagData mag = {};
mag.x = 0.4f;
mag.y = 0.0f;
mag.z = 0.6f;
write_mag_data((void *)&mag);
RawBaroData baro = {};
// calculate air pressure from altitude (valid for low altitude)
baro.pressure = 120000.0f;
baro.temperature = 25.0f;
write_baro_data(&baro);
RawAirspeedData airspeed {};
write_airspeed_data(&airspeed);
}
void Simulator::poll_for_MAVLink_messages()
{
#ifdef __PX4_DARWIN
pthread_setname_np("sim_rcv");
#else
pthread_setname_np(pthread_self(), "sim_rcv");
#endif
struct sockaddr_in _myaddr {};
_myaddr.sin_family = AF_INET;
_myaddr.sin_addr.s_addr = htonl(INADDR_ANY);
_myaddr.sin_port = htons(_port);
if (_ip == InternetProtocol::UDP) {
if ((_fd = socket(AF_INET, SOCK_DGRAM, 0)) < 0) {
PX4_ERR("Creating UDP socket failed: %s", strerror(errno));
return;
}
if (bind(_fd, (struct sockaddr *)&_myaddr, sizeof(_myaddr)) < 0) {
PX4_ERR("bind for UDP port %i failed (%i)", _port, errno);
return;
}
PX4_INFO("Waiting for simulator to connect on UDP port %u", _port);
while (true) {
// Once we receive something, we're most probably good and can carry on.
int len = ::recvfrom(_fd, _buf, sizeof(_buf), 0,
(struct sockaddr *)&_srcaddr, (socklen_t *)&_addrlen);
if (len > 0) {
break;
} else {
system_sleep(1);
}
}
PX4_INFO("Simulator connected on UDP port %u.", _port);
} else {
PX4_INFO("Waiting for simulator to connect on TCP port %u", _port);
while (true) {
if ((_fd = socket(AF_INET, SOCK_STREAM, 0)) < 0) {
PX4_ERR("Creating TCP socket failed: %s", strerror(errno));
return;
}
int yes = 1;
int ret = setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, (char *) &yes, sizeof(int));
if (ret != 0) {
PX4_ERR("setsockopt failed: %s", strerror(errno));
}
socklen_t myaddr_len = sizeof(_myaddr);
ret = connect(_fd, (struct sockaddr *)&_myaddr, myaddr_len);
if (ret == 0) {
break;
} else {
::close(_fd);
system_sleep(1);
}
}
PX4_INFO("Simulator connected on TCP port %u.", _port);
}
// Create a thread for sending data to the simulator.
pthread_t sender_thread;
pthread_attr_t sender_thread_attr;
pthread_attr_init(&sender_thread_attr);
pthread_attr_setstacksize(&sender_thread_attr, PX4_STACK_ADJUSTED(4000));
struct sched_param param;
(void)pthread_attr_getschedparam(&sender_thread_attr, ¶m);
// sender thread should run immediately after new outputs are available
// to send the lockstep update to the simulation
param.sched_priority = SCHED_PRIORITY_ACTUATOR_OUTPUTS + 1;
(void)pthread_attr_setschedparam(&sender_thread_attr, ¶m);
struct pollfd fds[2] = {};
unsigned fd_count = 1;
fds[0].fd = _fd;
fds[0].events = POLLIN;
#ifdef ENABLE_UART_RC_INPUT
// setup serial connection to autopilot (used to get manual controls)
int serial_fd = openUart(PIXHAWK_DEVICE, PIXHAWK_DEVICE_BAUD);
char serial_buf[1024];
if (serial_fd >= 0) {
fds[1].fd = serial_fd;
fds[1].events = POLLIN;
fd_count++;
PX4_INFO("Start using %s for radio control input.", PIXHAWK_DEVICE);
} else {
PX4_INFO("Not using %s for radio control input. Assuming joystick input via MAVLink.", PIXHAWK_DEVICE);
}
#endif
// Subscribe to topics.
// Only subscribe to the first actuator_outputs to fill a single HIL_ACTUATOR_CONTROLS.
_actuator_outputs_sub = orb_subscribe_multi(ORB_ID(actuator_outputs), 0);
_vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
// got data from simulator, now activate the sending thread
pthread_create(&sender_thread, &sender_thread_attr, Simulator::sending_trampoline, nullptr);
pthread_attr_destroy(&sender_thread_attr);
mavlink_status_t mavlink_status = {};
// Request HIL_STATE_QUATERNION for ground truth.
request_hil_state_quaternion();
_initialized = true;
while (true) {
// wait for new mavlink messages to arrive
int pret = ::poll(&fds[0], fd_count, 1000);
if (pret == 0) {
// Timed out.
continue;
}
if (pret < 0) {
PX4_ERR("poll error %d, %d", pret, errno);
continue;
}
if (fds[0].revents & POLLIN) {
int len = ::recvfrom(_fd, _buf, sizeof(_buf), 0, (struct sockaddr *)&_srcaddr, (socklen_t *)&_addrlen);
if (len > 0) {
mavlink_message_t msg;
for (int i = 0; i < len; i++) {
if (mavlink_parse_char(MAVLINK_COMM_0, _buf[i], &msg, &mavlink_status)) {
handle_message(&msg);
}
}
}
}
#ifdef ENABLE_UART_RC_INPUT
// got data from PIXHAWK
if (fd_count > 1 && fds[1].revents & POLLIN) {
len = ::read(serial_fd, serial_buf, sizeof(serial_buf));
if (len > 0) {
mavlink_message_t msg;
mavlink_status_t serial_status = {};
for (int i = 0; i < len; ++i) {
if (mavlink_parse_char(MAVLINK_COMM_1, serial_buf[i], &msg, &serial_status)) {
// have a message, handle it
bool prev_publish = _publish;
set_publish(true);
handle_message(&msg);
set_publish(prev_publish);
}
}
}
}
#endif
}
orb_unsubscribe(_actuator_outputs_sub);
orb_unsubscribe(_vehicle_status_sub);
}
#ifdef ENABLE_UART_RC_INPUT
int openUart(const char *uart_name, int baud)
{
/* process baud rate */
int speed;
switch (baud) {
case 0: speed = B0; break;
case 50: speed = B50; break;
case 75: speed = B75; break;
case 110: speed = B110; break;
case 134: speed = B134; break;
case 150: speed = B150; break;
case 200: speed = B200; break;
case 300: speed = B300; break;
case 600: speed = B600; break;
case 1200: speed = B1200; break;
case 1800: speed = B1800; break;
case 2400: speed = B2400; break;
case 4800: speed = B4800; break;
case 9600: speed = B9600; break;
case 19200: speed = B19200; break;
case 38400: speed = B38400; break;
case 57600: speed = B57600; break;
case 115200: speed = B115200; break;
case 230400: speed = B230400; break;
case 460800: speed = B460800; break;
case 921600: speed = B921600; break;
default:
PX4_ERR("Unsupported baudrate: %d", baud);
return -EINVAL;
}
/* open uart */
int uart_fd = ::open(uart_name, O_RDWR | O_NOCTTY);
if (uart_fd < 0) {
return uart_fd;
}
/* Try to set baud rate */
struct termios uart_config = {};
int termios_state;
/* Back up the original uart configuration to restore it after exit */
if ((termios_state = tcgetattr(uart_fd, &uart_config)) < 0) {
PX4_ERR("tcgetattr failed for %s: %s\n", uart_name, strerror(errno));
::close(uart_fd);
return -1;
}
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
PX4_ERR("cfsetispeed or cfsetospeed failed for %s: %s\n", uart_name, strerror(errno));
::close(uart_fd);
return -1;
}
// Make raw
cfmakeraw(&uart_config);
if ((termios_state = tcsetattr(uart_fd, TCSANOW, &uart_config)) < 0) {
PX4_ERR("tcsetattr failed for %s: %s\n", uart_name, strerror(errno));
::close(uart_fd);
return -1;
}
return uart_fd;
}
#endif
int Simulator::publish_sensor_topics(const mavlink_hil_sensor_t *imu)
{
uint64_t timestamp = hrt_absolute_time();
if ((imu->fields_updated & 0x1FFF) != 0x1FFF) {
PX4_DEBUG("All sensor fields in mavlink HIL_SENSOR packet not updated. Got %08x", imu->fields_updated);
}
/*
static int count=0;
static uint64_t last_timestamp=0;
count++;
if (!(count % 200)) {
PX4_WARN("TIME : %lu, dt: %lu",
(unsigned long) timestamp,(unsigned long) timestamp - (unsigned long) last_timestamp);
PX4_WARN("IMU : %f %f %f",imu->xgyro,imu->ygyro,imu->zgyro);
PX4_WARN("ACCEL: %f %f %f",imu->xacc,imu->yacc,imu->zacc);
PX4_WARN("MAG : %f %f %f",imu->xmag,imu->ymag,imu->zmag);
PX4_WARN("BARO : %f %f %f",imu->abs_pressure,imu->pressure_alt,imu->temperature);
}
last_timestamp = timestamp;
*/
/* gyro */
{
sensor_gyro_s gyro = {};
gyro.timestamp = timestamp;