forked from OpenIPC/msposd
-
Notifications
You must be signed in to change notification settings - Fork 1
/
msposd.c
1387 lines (1117 loc) · 38.6 KB
/
msposd.c
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
#include <getopt.h>
#include <stdio.h>
#include <stdlib.h>
#include <fcntl.h>
#include <errno.h>
#include <string.h>
#include <unistd.h>
#include <signal.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <sys/mman.h>
#include <arpa/inet.h>
#include <stdbool.h>
#include <termios.h>
#include <assert.h>
#include <time.h>
#include "version.h"
#include <event2/event.h>
#include <event2/util.h>
#include <event2/buffer.h>
#include <event2/bufferevent.h>
#include "mavlink/common/mavlink.h"
#include "osd/msp/msp.h"
//#include "osd/msp/msp.h" // why the fuck
//#include "osd/msp_displayport_mux.c"
#include "osd/net/network.h"
#include "osd.c" //Should be merged
//#include "msp/msp.cpp"
#define MAX_MTU 9000
#include "osd/util/settings.h"
bool vtxMenuActive = false;
bool armed = true; // assume armed until we are told otherwise from the fc
bool AbortNow=false;
bool verbose = false;
bool ParseMSP = true;
bool DrawOSD = false;
bool mspVTXenabled = false;
bool vtxMenuEnabled = false;
//libevent base main loop
extern struct event_base *base = NULL;
int serial_fd = 0;
int in_sock = 0;
int MSPUDPPort=0;
int MSP_PollRate=20;
int matrix_size=0;
int AHI_Enabled=1;
bool enable_simple_uart=false;
const char *default_master = "/dev/ttyAMA0";
const int default_baudrate = 115200;
const char *defualt_out_addr = "";
const char *default_in_addr = "127.0.0.1:0";
const int RC_CHANNELS = 65; //RC_CHANNELS ( #65 ) for regular MAVLINK RC Channels read (https://mavlink.io/en/messages/common.html#RC_CHANNELS)
const int RC_CHANNELS_RAW = 35; //RC_CHANNELS_RAW ( #35 ) for ExpressLRS,Crossfire and other RC procotols (https://mavlink.io/en/messages/common.html#RC_CHANNELS_RAW)
//if we gonna use MSP parsing
msp_state_t *rx_msp_state;
struct bufferevent *serial_bev;
struct sockaddr_in sin_out = {
.sin_family = AF_INET,
};
int out_sock=0;
long aggregate=1;
/*
When aggregating packets, we flush when a message that draws artifical horizon (AHI). This shows the minimum size of packets in the buffer in order to flush
If we need smooth response of the OSD, then set this to 1.
Value of 3 is a compromise, 3 sequential packets for AHI change will be aggregated, this will save bandwidth, but will reduse the frame rate of the OSD.
*/
int minAggPckts=3;
bool monitor_wfb=false;
static int temp = false;
static void print_usage()
{
printf("Usage: msposd [OPTIONS]\n"
"Where:\n"
" -m --master Serial port to receive MSP (%s by default)\n"
" -b --baudrate Serial port baudrate (%d by default)\n"
" -o --output UDP endpoint to forward aggregated MSP messages (%s)\n"
" -c --channels RC Channel to listen for commands (0 by default) and exec channels.sh. This command can be repeated. Channel values are 1-based.\n"
" -w --wait Delay after each command received(2000ms default)\n"
" -r --fps Max MSP Display refresh rate(5..50)\n"
" -p --persist How long a channel value must persist to generate a command - for multiposition switches (0ms default)\n"
" -t --temp Read SoC temperature\n"
" -d --wfb Monitors wfb.log file and reports errors via HUD messages\n"
" -s --osd Parse MSP and draw OSD over the video\n"
" -a --ahi Draw graphic AHI, mode [0-No, 2-Simple 1-Ladder, 3-LadderEx]\n"
" -x --matrix OSD matrix (0 - 53:20 , 1- 50:18 chars)\n"
" --mspvtx Enable mspvtx support\n"
" -v --verbose Show debug infot\n"
" --help Display this help\n",
default_master, default_baudrate, defualt_out_addr);
}
static speed_t speed_by_value(int baudrate)
{
switch (baudrate) {
case 9600:
return B9600;
case 19200:
return B19200;
case 38400:
return B38400;
case 57600:
return B57600;
case 115200:
return B115200;
case 230400:
return B230400;
case 460800:
return B460800;
case 500000:
return B500000;
case 921600:
return B921600;
case 1500000:
return B1500000;
default:
printf("Not implemented baudrate %d\n", baudrate);
exit(EXIT_FAILURE);
}
}
uint64_t get_current_time_ms() // in milliseconds
{
struct timespec ts;
int rc = clock_gettime(1 /*CLOCK_MONOTONIC*/, &ts);
//if (rc < 0)
// return get_current_time_ms_Old();
return ts.tv_sec * 1000LL + ts.tv_nsec / 1000000;
}
static bool parse_host_port(const char *s, struct in_addr *out_addr,
in_port_t *out_port)
{
char host_and_port[32] = { 0 };
strncpy(host_and_port, s, sizeof(host_and_port) - 1);
char *colon = strchr(host_and_port, ':');
if (NULL == colon) {
return -1;
}
*colon = '\0';
const char *host = host_and_port, *port_ptr = colon + 1;
const bool is_valid_addr = inet_aton(host, out_addr) != 0;
if (!is_valid_addr) {
printf("Cannot parse host `%s'.\n", host);
return false;
}
int port;
if (sscanf(port_ptr, "%d", &port) != 1) {
printf("Cannot parse port `%s'.\n", port_ptr);
return false;
}
*out_port = htons(port);
return true;
}
static void signal_cb(evutil_socket_t fd, short event, void *arg)
{
struct event_base *base = arg;
(void)event;
AbortNow=true;
printf("Exit Request: %s signal received\n", strsignal(fd));
event_base_loopbreak(base);
}
#define MAX_BUFFER_SIZE 50 //Limited by mavlink
static char MavLinkMsgFile[128]= "mavlink.msg";
#ifdef _x86
static char WfbLogFile[128]= "wfb.log";
#else
static char WfbLogFile[128]= "/tmp/wfb.log";
#endif
bool Check4MavlinkMsg(char* buffer) {
//const char *filename = MavLinkMsgFile;//"mavlink.msg";
FILE *file = fopen(MavLinkMsgFile, "rb");
if (file == NULL)// No file, no problem
return false;
size_t bytesRead = fread(buffer, 1, MAX_BUFFER_SIZE, file);
fclose(file);
if (bytesRead > 0) {
if (verbose)
printf("Mavlink msg from file:%s\n", buffer);
if (remove(MavLinkMsgFile) != 0)
printf("Error deleting file");
return true;
} else
printf("Mavlink empty file ?!\n");
return false;
}
static uint8_t system_id=1;
static unsigned long long LastWfbSent=0;
/// @brief wfb_tx output should be redirected to wfb.log. Parse it and extracted dropped packets!
/// @return Number of dropped packets for the last period
int SendWfbLogToGround(){
if (!monitor_wfb)
return false;
if ( abs(get_current_time_ms()-LastWfbSent) < 1000)//Once a second max
return 0;
LastWfbSent = abs(get_current_time_ms());
char msg_buf[200];
FILE *file = fopen(WfbLogFile, "r");
if (file == NULL) {
if (verbose)
printf("No file %s\n",WfbLogFile);
return 0;
}
char buff[200];
int total_dropped_packets = 0;
/*
UDP rxq overflow: 2 packets dropped
UDP rxq overflow: 45 packets dropped
*/
//if (verbose)
// printf("Parsing file: %s\n",WfbLogFile);
int maxlinestoparse=0;
// Read lines from the file and parse for dropped packets
while (fgets(buff, sizeof(buff), file) != NULL) {
if ((maxlinestoparse++) >30){//If the file is very long, no need to struggle
total_dropped_packets=9999;
break;
}
if (strstr(buff, "packets dropped") != NULL) { // Check if the line contains "packets dropped"
char *token = strtok(buff, " ");//split by space, Parse the line to extract the number of dropped packets
while (token != NULL) {
if (isdigit(token[0])) {
int dropped_packets = atoi(token);
total_dropped_packets += dropped_packets;
break;
}
token = strtok(NULL, " ");
}
}
}
fclose(file);
if (maxlinestoparse==0 && total_dropped_packets==0)//file was empty
return 0;
//remove(WfbLogFile) // This will break console output in the file!
file = fopen(WfbLogFile, "w");// Open the file in write mode, truncating it to zero size
if (file != NULL)
fclose(file);
if (false /*out_sock>0*/){//if we have outbound socket for mavlink, but now if available it is used for MSP
sprintf(msg_buf,"%d video pckts dropped!\n", total_dropped_packets);
printf("%s",msg_buf);
mavlink_message_t message;
mavlink_msg_statustext_pack_chan(
system_id,
MAV_COMP_ID_SYSTEM_CONTROL,
MAVLINK_COMM_1,
&message,
4, // 4 - Warning, 5 - Error
msg_buf,
0,0);
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
const int len = mavlink_msg_to_send_buffer(buffer, &message);
sendto(out_sock, buffer, len, 0, (struct sockaddr *)&sin_out, sizeof(sin_out));
}
return total_dropped_packets;
}
static bool SendInfoToGround(){
char msg_buf[MAX_BUFFER_SIZE];
if (!Check4MavlinkMsg(&msg_buf[0]))
return false;
//Huston, we have a message for you.
mavlink_message_t message;
mavlink_msg_statustext_pack_chan(
system_id,
MAV_COMP_ID_SYSTEM_CONTROL,
MAVLINK_COMM_1,
&message,
4, // 4 - Warning, 5 - Error
msg_buf,
0,0);
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
const int len = mavlink_msg_to_send_buffer(buffer, &message);
sendto(out_sock, buffer, len, 0, (struct sockaddr *)&sin_out, sizeof(sin_out));
return true;
}
uint64_t get_current_time_ms_Old() {
time_t current_time = time(NULL);
return (uint64_t)(current_time * 1000);
}
int last_wifi_temp;
static long last_wifi_temp_taken=0;
int Get8812EU2Temp(){
if ((get_time_ms() - last_wifi_temp_taken ) < 1000)//Set some caching to keep CPU load low
return last_wifi_temp;
last_wifi_temp_taken= get_time_ms();
FILE *stat = popen("cat /proc/net/rtl88x2eu/wlan0/thermal_state", "r");
if (stat == NULL) {
fprintf(stderr, "Failed to run command\n");
return 1;
}
char buffer[128];
int temperature=0;
char c[25];
// Read the first line of output
if (fgets(buffer, sizeof(buffer), stat) != NULL) {
if (sscanf(buffer, "rf_path: %*d, thermal_value: %*d, offset: %*d, temperature: %d", &temperature) == 1) {
printf("WiFi Temperature from the first line: %d\n", temperature);
} else {
fprintf(stderr, "Failed to parse wifi temperature\n");
}
}
// Close the pipe
pclose(stat);
last_wifi_temp=temperature;
return temperature;
}
int last_board_temp;
static long last_board_temp_taken=0;
/// @brief
/// @return -100 if no sigmastar found
int GetTempSigmaStar(){
if ( (get_time_ms() - last_board_temp_taken ) < 1000)//Set some caching to keep CPU load low
return last_board_temp;
last_board_temp_taken= get_time_ms();
//https://wx.comake.online/doc/doc/SigmaStarDocs-SSD220-SIGMASTAR-202305231834/platform/BSP/Ikayaki/frequency_en.html
FILE *file = fopen("/sys/devices/virtual/mstar/msys/TEMP_R", "r"); //Temperature 62
if (file == NULL) {
if (verbose)
printf("No temp data at %s\n",WfbLogFile);
return -100;
}
last_board_temp=-100;
char buff[200];
// Read lines from the file and parse for dropped packets
if (fgets(buff, sizeof(buff), file) != NULL) {
char *temperature_str = strstr(buff, "Temperature"); // Find "Temperature"
if (temperature_str != NULL)
last_board_temp = atoi(temperature_str + 12); // Extract temperature value
}
fclose(file);
if (verbose && last_board_temp<-90)
printf("No temp data in file %s\n",WfbLogFile);
//printf("SigmaStar temp: %d\n",last_board_temp);
return last_board_temp;
}
static uint64_t LastTempSent;
static int SendTempToGround(unsigned char* mavbuf){
if ( abs(get_current_time_ms()-LastTempSent) < 1000)//Once a second
return 0;
LastTempSent = abs(get_current_time_ms());
if(temp==2)//read the temperature only once per second
last_board_temp=GetTempSigmaStar();
char msg_buf[MAX_BUFFER_SIZE];
mavlink_message_t message;
mavlink_msg_raw_imu_pack_chan(
system_id,
MAV_COMP_ID_SYSTEM_CONTROL,
MAVLINK_COMM_1,
&message,0,0,0,0,0,0,0,0,0,0,0,
last_board_temp*100
);
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
const int len = mavlink_msg_to_send_buffer(mavbuf, &message);
//printf("temp %f sent with %d bytes",last_board_temp*100,len);
return len;
}
bool version_shown=false;
static void ShowVersionOnce(mavlink_message_t* msg, uint8_t header){
if (version_shown)
return;
version_shown=true;
/*
The major version can be determined from the packet start marker byte:
MAVLink 1: 0xFE
MAVLink 2: 0xFD
*/
if (header==0xFE)
printf("Detected MAVLink ver: 1.0 (%d)\n",msg->magic);
if (header==0xFD)
printf("Detected MAVLink version: 2.0 (%d)\n",msg->magic);
printf("System_id = %d \n",system_id);
}
bool fc_shown=false;
void handle_heartbeat(const mavlink_message_t* message)
{
if (fc_shown)
return;
fc_shown=true;
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(message, &heartbeat);
printf("Flight Controller Type :");
switch (heartbeat.autopilot) {
case MAV_AUTOPILOT_GENERIC:
printf("Generic/INAV");
break;
case MAV_AUTOPILOT_ARDUPILOTMEGA:
printf("ArduPilot");
break;
case MAV_AUTOPILOT_PX4:
printf("PX4");
break;
default:
printf("other");
break;
}
printf("\n");
}
void handle_statustext(const mavlink_message_t* message)
{
mavlink_statustext_t statustext;
mavlink_msg_statustext_decode(message, &statustext);
printf("FC message:%s", statustext.text);
}
unsigned long long get_current_time_ms_simple() {
clock_t current_clock_ticks = clock();
return (unsigned long long)(current_clock_ticks * 1000 / CLOCKS_PER_SEC);
}
uint16_t channels[18];
// Channel monitoring:
// Maximum number of channels to monitor.
#define kChannelCount 16
// Whether the channel monitoring was enabled.
bool rc_channel_mon_enabled = false;
// A boolean array that defines which channels are monitored.
// Setting a value to "true" will make this program run /usr/bin/channels.sh
// if the channel value changes.
static bool rc_channel_mon[kChannelCount] = {0};
//Time to wait between bash script starts.
long wait_after_bash=2000;
//how long a RC value should stay at one level to issue a command
int ChannelPersistPeriodMS=2000;
static uint64_t LastStart[kChannelCount] = {0};//
static unsigned long LastValue[kChannelCount] = {0};
uint16_t NewValue[kChannelCount] = {0};
static uint64_t NewValueStart[kChannelCount] = {0};
unsigned int ChannelCmds[kChannelCount] = {0};
static uint64_t mavpckts_ttl=0;
void ProcessChannel(int rc_channel_no){
//rc_channel_no, zero based
uint16_t val=0;
if (rc_channel_no<0 || rc_channel_no>15 /* || (mavpckts_ttl<100*/ ) //wait in the beginning for the values to settle
return;
if (!armed)
handle_stickcommands(channels);
if ( abs(get_current_time_ms()-LastStart[rc_channel_no]) < wait_after_bash)
return;
val=channels[rc_channel_no];
if (abs(val-NewValue[rc_channel_no])>32 && ChannelPersistPeriodMS>0){
//We have a new value, let us wait for it to persist
NewValue[rc_channel_no]=val;
NewValueStart[rc_channel_no]=get_current_time_ms();
return;
}else
if (abs(get_current_time_ms()-NewValueStart[rc_channel_no])<ChannelPersistPeriodMS)
return;//New value should remain "stable" for a second before being approved
else{}//New value persisted for more THAN ChannelPersistPeriodMS
if (abs(val-LastValue[rc_channel_no])<32)//the change is too small
return;
NewValue[rc_channel_no]=val;
LastValue[rc_channel_no]=val;
char buff[60];
// For compatibility purposes, channels.sh is called with 1-based channel argument.
sprintf(buff, "/usr/bin/channels.sh %d %d &", rc_channel_no + 1, val);
printf("Starting(%d): %s \n",ChannelCmds[rc_channel_no],buff);
LastStart[rc_channel_no]=get_current_time_ms();
if (ChannelCmds[rc_channel_no]>0){
//intentionally skip the first command, since when starting it will always receive some channel value and execute the script
system(buff);
}
printf("Started(%d): %s \n",ChannelCmds[rc_channel_no],buff);
ChannelCmds[rc_channel_no]++;
}
void ProcessChannels(){
for (int i=0; i < kChannelCount; ++i) {
if (rc_channel_mon[i])
ProcessChannel(i);
}
}
void showchannels(int count){
if (verbose){
printf("Channels :");
for (int i =0; i <count;i++)
printf("| %02d", channels[i]);
printf("\r\n");
}
}
void handle_msg_id_rc_channels_raw(const mavlink_message_t* message){
mavlink_rc_channels_raw_t rc_channels;
mavlink_msg_rc_channels_raw_decode(message, &rc_channels);
memcpy(&channels[0], &rc_channels.chan1_raw, 8 * sizeof(uint16_t));
showchannels(8);
ProcessChannels();
}
void handle_msg_id_rc_channels_override(const mavlink_message_t* message){
mavlink_rc_channels_override_t rc_channels;
mavlink_msg_rc_channels_override_decode(message, &rc_channels);
memcpy(&channels[0], &rc_channels.chan1_raw, 18 * sizeof(uint16_t));
showchannels(18);
ProcessChannels();
}
void handle_msg_id_rc_channels(const mavlink_message_t* message){
mavlink_rc_channels_t rc_channels;
mavlink_msg_rc_channels_decode(message, &rc_channels);
memcpy(&channels[0], &rc_channels.chan1_raw, 18 * sizeof(uint16_t));
showchannels(18);
ProcessChannels();
}
unsigned char mavbuf[2048];
unsigned int mavbuff_offset=0;
unsigned int mavpckts_count=0;
static void process_mavlink(uint8_t* buffer, int count, void *arg){
mavlink_message_t message;
mavlink_status_t status;
for (int i = 0; i < count; ++i) {
if (mavbuff_offset>2000){
printf("Mavlink buffer overflowed! Packed lost!\n");
mavbuff_offset=0;
}
mavbuf[mavbuff_offset]=buffer[i];
mavbuff_offset++;
if (mavlink_parse_char(MAVLINK_COMM_0, buffer[i], &message, &status) == 1) {
mavpckts_ttl++;
system_id=message.sysid;
ShowVersionOnce(&message, (uint8_t) buffer[0]);
if (verbose)
printf("Mavlink msg %d no: %d\n",message.msgid, message.seq);
switch (message.msgid) {
case MAVLINK_MSG_ID_RC_CHANNELS_RAW://35 Used by INAV
handle_msg_id_rc_channels_raw(&message);
break;
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE://70
handle_msg_id_rc_channels_override(&message);
break;
case MAVLINK_MSG_ID_RC_CHANNELS://65 used by ArduPilot
handle_msg_id_rc_channels(&message);
break;
case MAVLINK_MSG_ID_HEARTBEAT://Msg info from the FC
handle_heartbeat(&message);
break;
case MAVLINK_MSG_ID_STATUSTEXT://Msg info from the FC
//handle_statustext(&message);
break;
}
mavpckts_count++;
bool mustflush=false;
if (aggregate>0){//We will send whole packets only
if (
((aggregate>=1 && aggregate<50 ) && mavpckts_count>=aggregate ) || //if packets more than treshold
((aggregate>50 && aggregate<2000 ) && mavbuff_offset>=aggregate ) || //if buffer more than treshold
((mavpckts_count>=minAggPckts) && message.msgid==MAVLINK_MSG_ID_ATTITUDE ) //MAVLINK_MSG_ID_ATTITUDE will always cause the buffer flushed
){
//flush and send all data
if (sendto(out_sock, mavbuf, mavbuff_offset, 0, (struct sockaddr *)&sin_out, sizeof(sin_out)) == -1) {
perror("sendto()");
event_base_loopbreak(arg);
}
if (verbose)
printf("%d Pckts / %d bytes sent\n",mavpckts_count,mavbuff_offset);
mavbuff_offset=0;
mavpckts_count=0;
SendInfoToGround();
SendWfbLogToGround();
if (last_board_temp>-100){
mavbuff_offset=SendTempToGround(mavbuf);
}
if (mavbuff_offset>0){
mavpckts_count++;
}
}
}
}//if mavlink_parse_char
}
}
static long ttl_packets=0;
static long ttl_bytes=0;
static long stat_bytes=0;
static long stat_pckts=0;
static long last_stat=0;
//handles both UART and Serial read
static void serial_read_cb(struct bufferevent *bev, void *arg)
{
if (AbortNow)//Abort request by user pending...
return;
int fd = bufferevent_getfd(bev); // Get the file descriptor associated with the event
if (fd == serial_fd)
{}//printf("Reading from serial port...\n");
else if (fd == in_sock)
{}//printf("Reading from UDP socket...\n");
struct evbuffer *input = bufferevent_get_input(bev);
int packet_len, in_len;
struct event_base *base = arg;
while ((in_len = evbuffer_get_length(input))) {
unsigned char *data = evbuffer_pullup(input, in_len);
if (data == NULL) {
return;
}
packet_len = in_len;
if (get_time_ms() - last_stat>1000) {//no faster than 1 per second
last_stat=(get_time_ms());
if (stat_screen_refresh_count==0)
stat_screen_refresh_count++;
if (verbose){
if (DrawOSD)
printf("UART Events:%u MessagesTTL:%u AttitMSGs:%u(%dms) Bytes/S:%u FPS:%u of %u (skipped:%d), AvgFrameLoad ms:%d | %d | %d | \r\n",stat_pckts,stat_msp_msgs,stat_msp_msg_attitude, (stat_attitudeDelay / (stat_msp_msg_attitude+1) ),
stat_bytes, stat_screen_refresh_count, stat_MSP_draw_complete_count, stat_skipped_frames, stat_draw_overlay_1/stat_screen_refresh_count,stat_draw_overlay_2/stat_screen_refresh_count,stat_draw_overlay_3/stat_screen_refresh_count);
else
printf("UART Events:%u MessagesTTL:%u AttitMSGs:%u(%dms) Bytes/S Recvd:%u Sent:%u, Screen FPS:%u MSP_FPS:%u MSP_UDP_Pckts:%u, AvgFrameLoad ms:%d | %d | \r\n",stat_pckts,stat_msp_msgs,stat_msp_msg_attitude, (stat_attitudeDelay / (stat_msp_msg_attitude+1) ),
stat_bytes, stat_MSPBytesSent, stat_screen_refresh_count, stat_MSP_draw_complete_count,stat_UDP_MSPframes, stat_draw_overlay_1/stat_screen_refresh_count,stat_draw_overlay_3/stat_screen_refresh_count);
showchannels(18);
}
stat_screen_refresh_count=0;
stat_pckts=0;
stat_bytes=0;
stat_msp_msgs=0;
stat_msp_msg_attitude=0;
stat_draw_overlay_1=0;
stat_draw_overlay_2=0;
stat_draw_overlay_3=0;
stat_skipped_frames=0;
stat_MSPBytesSent=0;
stat_MSP_draw_complete_count=0;
stat_UDP_MSPframes=0;
}
stat_pckts++;
stat_bytes+=packet_len;
ttl_packets++;
ttl_bytes+=packet_len;
if (ParseMSP){
//Test to do RAW MSP forward here
//sendto(out_sock, data, packet_len, 0, (struct sockaddr *)&sin_out, sizeof(sin_out));
for(int i=0;i<packet_len;i++)
msp_process_data(rx_msp_state, data[i]);
//continue;
}else{
if (!version_shown && ttl_packets%10==3)//If garbage only, give some feedback do diagnose
printf("Packets:%d Bytes:%d\n",ttl_packets,ttl_bytes);
if (aggregate==0){
if (sendto(out_sock, data, packet_len, 0,
(struct sockaddr *)&sin_out,
sizeof(sin_out)) == -1) {
perror("sendto()");
//event_base_loopbreak(base);
return false;
}
}
//Let's try to parse the stream
if (aggregate>0 || rc_channel_mon_enabled)//if no RC channel control needed, only forward the data
process_mavlink(data,packet_len, arg);//Let's try to parse the stream
}
evbuffer_drain(input, packet_len);
}
}
// Signal handler function
void sendtestmsg(int signum) {
printf("Sending test mavlink msg.\n");
char buff[200];
sprintf(buff, "echo Hello_From_OpenIPC > %s", MavLinkMsgFile);
system(buff);
SendInfoToGround();
}
static void serial_event_cb(struct bufferevent *bev, short events, void *arg)
{
(void)bev;
struct event_base *base = arg;
if (events & (BEV_EVENT_EOF | BEV_EVENT_ERROR | BEV_EVENT_TIMEOUT)) {
printf("Serial connection closed\n");
event_base_loopbreak(base);
}
}
// Callback function to handle keyboard input
#ifdef __KEYBOARD_INPUT__
void stdin_read_callback(int fd, short event, void *arg) {
char buffer[256];
ssize_t n = read(fd, buffer, sizeof(buffer) - 1);
if (n > 0 && ! armed) {
buffer[n] = '\0'; // Null-terminate the input
printf("You typed: %s\n", buffer);
if (buffer[0] == 'm') {
printf("Disableing msposd\n");
vtxMenuEnabled = init_state_manager();
if (vtxMenuEnabled)
vtxMenuActive = true;
}
if (buffer[0] == 'q') {
printf("Enableing msposd\n");
vtxMenuActive = false;
}
if (buffer[0] == 'w') {
uint16_t channels[18];
channels[0] = 1500;
channels[1] = 2000;
channels[2] = 1500;
channels[3] = 1500;
handle_stickcommands(channels); // Move up
} else if (buffer[0] == 's') {
uint16_t channels[18];
channels[0] = 1500;
channels[1] = 1000;
channels[2] = 1500;
channels[3] = 1500;
handle_stickcommands(channels);// Move down
} else if (buffer[0] == 'a') {
uint16_t channels[18];
channels[0] = 1000;
channels[1] = 1500;
channels[2] = 1500;
channels[3] = 1500;
handle_stickcommands(channels);// Move left
} else if (buffer[0] == 'd') {
uint16_t channels[18];
channels[0] = 2000;
channels[1] = 1500;
channels[2] = 1500;
channels[3] = 1500;
handle_stickcommands(channels);// Move right
} else if (buffer[0] == 'e') {
//unused
}
}
}
#endif
static void* setup_temp_mem(off_t base, size_t size)
{
int mem_fd;
mem_fd = open("/dev/mem", O_RDWR | O_SYNC);
if (mem_fd < 0) {
fprintf(stderr, "can't open /dev/mem\n");
return NULL;
}
char *mapped_area =
mmap(NULL, size, PROT_READ | PROT_WRITE, MAP_SHARED, mem_fd, base);
if (mapped_area == MAP_FAILED) {
fprintf(stderr, "read_mem_reg mmap error: %s (%d)\n",
strerror(errno), errno);
return NULL;
}
uint32_t MISC_CTRL45 = 0;
// Set the T-Sensor cyclic capture mode by configuring MISC_CTRL45 bit[30]
MISC_CTRL45 |= 1 << 30;
// Set the capture period by configuring MISC_CTRL45 bit[27:20]
// The formula for calculating the cyclic capture periodis as follows:
// T = N x 2 (ms)
// N is the value of MISC_CTRL45 bit[27:20]
MISC_CTRL45 |= 50 << 20;
// Enable the T-Sensor by configuring MISC_CTRL45 bit[31] and start to collect the temperature
MISC_CTRL45 |= 1 << 31;
*(volatile uint32_t *)(mapped_area + 0xB4) = MISC_CTRL45;
return mapped_area;
}
static void temp_read(evutil_socket_t sock, short event, void *arg)
{
(void)sock;
(void)event;
char *mapped_area = arg;
uint32_t val = *(volatile uint32_t *)(mapped_area + 0xBC);
float tempo = val & ((1 << 16) - 1);
//tempo = ((tempo - 117) / 798.0f) * 165.0f - 40.0f;
tempo = ((tempo - 117) / 798) * 165 - 40;
if (last_board_temp == -100)//only once
printf("Temp read %f C\n", tempo);
last_board_temp=tempo;
}
int VariantCounter=0;
static bool ReadSerialSimple(int showstat){
if (showstat) {//no faster than 1 per second
last_stat=(get_time_ms());
if (stat_screen_refresh_count==0)
stat_screen_refresh_count++;
if (verbose){
if (DrawOSD)
printf("UART Events:%u MessagesTTL:%u AttitMSGs:%u(%dms) Bytes/S:%u FPS:%u of %u (skipped:%d), AvgFrameLoad ms:%d | %d | %d | \r\n",stat_pckts,stat_msp_msgs,stat_msp_msg_attitude, (stat_attitudeDelay / (stat_msp_msg_attitude+1) ),
stat_bytes, stat_screen_refresh_count, stat_MSP_draw_complete_count, stat_skipped_frames, stat_draw_overlay_1/stat_screen_refresh_count,stat_draw_overlay_2/stat_screen_refresh_count,stat_draw_overlay_3/stat_screen_refresh_count);
else
printf("UART Events:%u MessagesTTL:%u AttitMSGs:%u(%dms) Bytes/S Recvd:%u Sent:%u, Screen FPS:%u MSP_FPS:%u MSP_UDP_Pckts:%u, AvgFrameLoad ms:%d | %d | \r\n",stat_pckts,stat_msp_msgs,stat_msp_msg_attitude, (stat_attitudeDelay / (stat_msp_msg_attitude+1) ),
stat_bytes, stat_MSPBytesSent, stat_screen_refresh_count, stat_MSP_draw_complete_count,stat_UDP_MSPframes, stat_draw_overlay_1/stat_screen_refresh_count,stat_draw_overlay_3/stat_screen_refresh_count);
showchannels(18);
}
stat_screen_refresh_count=0;
stat_pckts=0;
stat_bytes=0;
stat_msp_msgs=0;
stat_msp_msg_attitude=0;
stat_draw_overlay_1=0;
stat_draw_overlay_2=0;
stat_draw_overlay_3=0;
stat_skipped_frames=0;
stat_MSPBytesSent=0;
stat_MSP_draw_complete_count=0;
stat_UDP_MSPframes=0;
}
uint8_t data[1024];
// Read from the serial port once per interval
int packet_len = read(serial_fd, data, sizeof(data));
if (packet_len < 0)
return;
stat_pckts++;
stat_bytes+=packet_len;
ttl_packets++;
ttl_bytes+=packet_len;
if (ParseMSP){
for(int i=0;i<packet_len;i++)
msp_process_data(rx_msp_state, data[i]);
//continue;
}
}
static void send_variant_request2(int serial_fd) {
uint8_t buffer[6];
int res=0;
if (enable_simple_uart ){
int rate_divider=MSP_PollRate / (1000 / MinTimeBetweenScreenRefresh);
if (rate_divider<1 || rate_divider>MSP_PollRate)
rate_divider=1;
if (( VariantCounter%rate_divider == 0 ))
ReadSerialSimple(VariantCounter == 0);
}
if (rc_channel_mon_enabled && VariantCounter%5==1){//once every 5 cycles, 4 times per second
construct_msp_command(buffer, MSP_RC, NULL, 0, MSP_OUTBOUND);
res = write(serial_fd, &buffer, sizeof(buffer));
}else if (AHI_Enabled){
if (AHI_Enabled==3 && VariantCounter%13==1){
construct_msp_command(buffer, MSP_COMP_GPS, NULL, 0, MSP_OUTBOUND);