/
main.cpp
687 lines (547 loc) · 16.6 KB
/
main.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
/****************************************************************************
*
* Copyright (C) 2015 Mark Charlebois. 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.
*
****************************************************************************/
/**
* @file main.cpp
* Basic shell to execute builtin "apps"
*
* @author Mark Charlebois <charlebm@gmail.com>
* @author Roman Bapst <bapstroman@gmail.com>
*/
#include <iostream>
#include <fstream>
#include <string>
#include <sstream>
#include <vector>
#include <signal.h>
#include <unistd.h>
#include <stdio.h>
#include "apps.h"
#include "px4_middleware.h"
#include "px4_posix.h"
#include "px4_log.h"
#include "DriverFramework.hpp"
#include <termios.h>
#include <sys/stat.h>
#include <px4_tasks.h>
namespace px4
{
void init_once();
}
using namespace std;
#define CMD_BUFF_SIZE 100
#ifdef PATH_MAX
const unsigned path_max_len = PATH_MAX;
#else
const unsigned path_max_len = 1024;
#endif
static volatile bool _ExitFlag = false;
static struct termios orig_term;
extern "C" {
void _SigIntHandler(int sig_num);
void _SigIntHandler(int sig_num)
{
cout.flush();
cout << endl << "Exiting..." << endl;
cout.flush();
_ExitFlag = true;
}
void _SigFpeHandler(int sig_num);
void _SigFpeHandler(int sig_num)
{
cout.flush();
cout << endl << "floating point exception" << endl;
PX4_BACKTRACE();
cout.flush();
}
void _SigSegvHandler(int sig_num);
void _SigSegvHandler(int sig_num)
{
cout.flush();
cout << endl << "segmentation fault" << endl;
PX4_BACKTRACE();
cout.flush();
}
}
static inline bool fileExists(const string &name)
{
struct stat buffer;
return (stat(name.c_str(), &buffer) == 0);
}
static inline bool dirExists(const string &path)
{
struct stat info;
if (stat(path.c_str(), &info) != 0) {
return false;
} else if (info.st_mode & S_IFDIR) {
return true;
} else {
return false;
}
}
static inline void touch(const string &name)
{
fstream fs;
fs.open(name, ios::out);
fs.close();
}
static int mkpath(const char *path, mode_t mode);
static int do_mkdir(const char *path, mode_t mode)
{
struct stat st;
int status = 0;
if (stat(path, &st) != 0) {
/* Directory does not exist. EEXIST for race condition */
if (mkdir(path, mode) != 0 && errno != EEXIST) {
status = -1;
}
} else if (!S_ISDIR(st.st_mode)) {
errno = ENOTDIR;
status = -1;
}
return (status);
}
/**
** mkpath - ensure all directories in path exist
** Algorithm takes the pessimistic view and works top-down to ensure
** each directory in path exists, rather than optimistically creating
** the last element and working backwards.
*/
static int mkpath(const char *path, mode_t mode)
{
char *pp;
char *sp;
int status;
char *copypath = strdup(path);
status = 0;
pp = copypath;
while (status == 0 && (sp = strchr(pp, '/')) != nullptr) {
if (sp != pp) {
/* Neither root nor double slash in path */
*sp = '\0';
status = do_mkdir(copypath, mode);
*sp = '/';
}
pp = sp + 1;
}
if (status == 0) {
status = do_mkdir(path, mode);
}
free(copypath);
return (status);
}
static string pwd()
{
char temp[path_max_len];
return (getcwd(temp, path_max_len) ? string(temp) : string(""));
}
static void print_prompt()
{
cout.flush();
cout << "pxh> ";
cout.flush();
}
static void run_cmd(const vector<string> &appargs, bool exit_on_fail, bool silently_fail = false)
{
static apps_map_type apps;
static bool initialized = false;
if (!initialized) {
init_app_map(apps);
initialized = true;
}
// command is appargs[0]
string command = appargs[0];
if (apps.find(command) != apps.end()) {
const char *arg[appargs.size() + 2];
unsigned int i = 0;
while (i < appargs.size() && appargs[i] != "") {
arg[i] = (char *)appargs[i].c_str();
++i;
}
arg[i] = (char *)nullptr;
int retval = apps[command](i, (char **)arg);
if (retval) {
cout << "Command '" << command << "' failed, returned " << retval << endl;
if (exit_on_fail && retval) {
exit(retval);
}
}
} else if (command == "help") {
list_builtins(apps);
} else if (command.length() == 0 || command[0] == '#') {
// Do nothing
} else if (!silently_fail) {
cout << "Invalid command: " << command << "\ntype 'help' for a list of commands" << endl;
}
}
static void usage()
{
cout << "./px4 [-d] [data_directory] startup_config [-h]" << endl;
cout << " -d - Optional flag to run the app in daemon mode and does not listen for user input." <<
endl;
cout << " This is needed if px4 is intended to be run as a upstart job on linux" << endl;
cout << "<data_directory> - directory where ROMFS and posix-configs are located (if not given, CWD is used)" << endl;
cout << "<startup_config> - config file for starting/stopping px4 modules" << endl;
cout << " -h - help/usage information" << endl;
}
static void process_line(string &line, bool exit_on_fail)
{
vector<string> appargs(20);
stringstream(line) >> appargs[0] >> appargs[1] >> appargs[2] >> appargs[3] >> appargs[4] >> appargs[5] >> appargs[6] >>
appargs[7] >> appargs[8] >> appargs[9] >> appargs[10] >> appargs[11] >> appargs[12] >> appargs[13] >>
appargs[14] >> appargs[15] >> appargs[16] >> appargs[17] >> appargs[18] >> appargs[19];
run_cmd(appargs, exit_on_fail);
}
static void restore_term()
{
cout << "Restoring terminal\n";
tcsetattr(0, TCSANOW, &orig_term);
}
bool px4_exit_requested(void)
{
return _ExitFlag;
}
static void set_cpu_scaling()
{
#if defined(__PX4_POSIX_EAGLE) || defined(__PX4_POSIX_EXCELSIOR)
// On Snapdragon we miss updates in sdlog2 unless all 4 CPUs are run
// at the maximum frequency all the time.
// Interestingely, cpu0 and cpu3 set the scaling for all 4 CPUs on Snapdragon.
system("echo performance > /sys/devices/system/cpu/cpu0/cpufreq/scaling_governor");
system("echo performance > /sys/devices/system/cpu/cpu3/cpufreq/scaling_governor");
// Alternatively we could also raise the minimum frequency to save some power,
// unfortunately this still lead to some drops.
//system("echo 1190400 > /sys/devices/system/cpu/cpu0/cpufreq/scaling_min_freq");
#endif
}
#ifdef __PX4_SITL_MAIN_OVERRIDE
int SITL_MAIN(int argc, char **argv);
int SITL_MAIN(int argc, char **argv)
#else
int main(int argc, char **argv)
#endif
{
bool daemon_mode = false;
bool chroot_on = false;
tcgetattr(0, &orig_term);
atexit(restore_term);
// SIGINT
struct sigaction sig_int {};
sig_int.sa_handler = _SigIntHandler;
sig_int.sa_flags = 0;// not SA_RESTART!;
sigaction(SIGINT, &sig_int, nullptr);
// SIGFPE
struct sigaction sig_fpe {};
sig_fpe.sa_handler = _SigFpeHandler;
sig_fpe.sa_flags = 0;// not SA_RESTART!;
sigaction(SIGFPE, &sig_fpe, nullptr);
// SIGSEGV
struct sigaction sig_segv {};
sig_segv.sa_handler = _SigSegvHandler;
sig_segv.sa_flags = SA_RESTART | SA_SIGINFO;
sigaction(SIGSEGV, &sig_segv, nullptr);
set_cpu_scaling();
int index = 1;
string commands_file;
int positional_arg_count = 0;
string data_path;
string node_name;
// parse arguments
while (index < argc) {
//cout << "arg: " << index << " : " << argv[index] << endl;
if (argv[index][0] == '-') {
// the arg starts with -
if (strncmp(argv[index], "-d", 2) == 0) {
daemon_mode = true;
} else if (strncmp(argv[index], "-h", 2) == 0) {
usage();
return 0;
} else if (strncmp(argv[index], "-c", 2) == 0) {
chroot_on = true;
} else {
PX4_ERR("Unknown/unhandled parameter: %s", argv[index]);
return 1;
}
} else if (!strncmp(argv[index], "__", 2)) {
//cout << "ros argument" << endl;
// ros arguments
if (!strncmp(argv[index], "__name:=", 8)) {
string name_arg = argv[index];
node_name = name_arg.substr(8);
cout << "node name: " << node_name << endl;
}
} else {
//cout << "positional argument" << endl;
positional_arg_count += 1;
if (positional_arg_count == 1) {
data_path = argv[index];
} else if (positional_arg_count == 2) {
commands_file = argv[index];
}
}
++index;
}
if (positional_arg_count != 2 && positional_arg_count != 1) {
PX4_ERR("Error expected 1 or 2 position arguments, got %d", positional_arg_count);
usage();
return -1;
}
bool symlinks_needed = true;
if (positional_arg_count == 1) { //data path is optional
commands_file = data_path;
symlinks_needed = false;
} else {
cout << "data path: " << data_path << endl;
}
cout << "commands file: " << commands_file << endl;
if (commands_file.empty()) {
PX4_ERR("Error commands file not specified");
return -1;
}
if (!fileExists(commands_file)) {
PX4_ERR("Error opening commands file, does not exist: %s", commands_file.c_str());
return -1;
}
// create sym-links
if (symlinks_needed) {
vector<string> path_sym_links;
path_sym_links.push_back("ROMFS");
path_sym_links.push_back("posix-configs");
path_sym_links.push_back("test_data");
for (unsigned i = 0; i < path_sym_links.size(); i++) {
string path_sym_link = path_sym_links[i];
//cout << "path sym link: " << path_sym_link << endl;
string src_path = data_path + "/" + path_sym_link;
string dest_path = pwd() + "/" + path_sym_link;
PX4_DEBUG("Creating symlink %s -> %s", src_path.c_str(), dest_path.c_str());
if (dirExists(path_sym_link)) { continue; }
// create sym-links
int ret = symlink(src_path.c_str(), dest_path.c_str());
if (ret != 0) {
PX4_ERR("Error creating symlink %s -> %s",
src_path.c_str(), dest_path.c_str());
return ret;
} else {
PX4_DEBUG("Successfully created symlink %s -> %s",
src_path.c_str(), dest_path.c_str());
}
}
}
// setup rootfs
const string eeprom_path = "./rootfs/eeprom/";
const string microsd_path = "./rootfs/fs/microsd/";
if (!fileExists(eeprom_path + "parameters")) {
cout << "creating new parameters file" << endl;
mkpath(eeprom_path.c_str(), S_IRUSR | S_IWUSR | S_IXUSR);
touch(eeprom_path + "parameters");
}
if (!fileExists(microsd_path + "dataman")) {
cout << "creating new dataman file" << endl;
mkpath(microsd_path.c_str(), S_IRUSR | S_IWUSR | S_IXUSR);
touch(microsd_path + "dataman");
}
// initialize
DriverFramework::Framework::initialize();
px4::init_once();
px4::init(argc, argv, "px4");
// if commandfile is present, process the commands from the file
if (!commands_file.empty()) {
ifstream infile(commands_file.c_str());
if (infile.is_open()) {
for (string line; getline(infile, line, '\n');) {
if (px4_exit_requested()) {
break;
}
// TODO: this should be true but for that we have to check all startup files
process_line(line, false);
}
} else {
PX4_ERR("Error opening commands file: %s", commands_file.c_str());
}
}
if (chroot_on) {
// Lock this application in the current working dir
// this is not an attempt to secure the environment,
// rather, to replicate a deployed file system.
char pwd_path[path_max_len];
const char *folderpath = "/rootfs/";
if (nullptr == getcwd(pwd_path, sizeof(pwd_path))) {
PX4_ERR("Failed acquiring working dir, abort.");
exit(1);
}
if (nullptr == strcat(pwd_path, folderpath)) {
PX4_ERR("Failed completing path, abort.");
exit(1);
}
if (chroot(pwd_path)) {
PX4_ERR("Failed chrooting application, path: %s, error: %s.", pwd_path, strerror(errno));
exit(1);
}
if (chdir("/")) {
PX4_ERR("Failed changing to root dir, path: %s, error: %s.", pwd_path, strerror(errno));
exit(1);
}
}
if (!daemon_mode) {
string mystr;
string string_buffer[CMD_BUFF_SIZE];
int buf_ptr_write = 0;
int buf_ptr_read = 0;
uint8_t cursor_position =
0; // position of the cursor from right to left (0: all the way to the right, mystr.length: all the way to the left)
print_prompt();
// change input mode so that we can manage shell
struct termios term;
tcgetattr(0, &term);
term.c_lflag &= ~ICANON;
term.c_lflag &= ~ECHO;
tcsetattr(0, TCSANOW, &term);
setbuf(stdin, nullptr);
while (!_ExitFlag) {
int c = getchar();
string add_string; // string to add at current cursor position
bool update_prompt = true;
switch (c) {
case EOF:
_ExitFlag = true;
break;
case 127: // backslash
if (mystr.length() - cursor_position > 0) {
mystr.erase(mystr.length() - cursor_position - 1, 1);
}
break;
case '\n': // user hit enter
if (buf_ptr_write == CMD_BUFF_SIZE) {
buf_ptr_write = 0;
}
if (buf_ptr_write > 0) {
if (!mystr.empty() && mystr != string_buffer[buf_ptr_write - 1]) {
string_buffer[buf_ptr_write] = mystr;
buf_ptr_write++;
}
} else {
if (!mystr.empty() && mystr != string_buffer[CMD_BUFF_SIZE - 1]) {
string_buffer[buf_ptr_write] = mystr;
buf_ptr_write++;
}
}
cout << endl;
process_line(mystr, false);
// reset string and cursor position
mystr = "";
cursor_position = 0;
buf_ptr_read = buf_ptr_write;
print_prompt();
break;
case '\033': { // arrow keys
c = getchar(); // skip first one, does not have the info
c = getchar();
if (c == 'A') { // arrow up
buf_ptr_read--;
} else if (c == 'B') { // arrow down
if (buf_ptr_read < buf_ptr_write) {
buf_ptr_read++;
}
} else if (c == 'C') { // arrow right
if (cursor_position > 0) {
printf("\033[1C");
cursor_position--;
}
break;
} else if (c == 'D') { // arrow left
if (cursor_position < mystr.length()) {
printf("\033[1D");
cursor_position++;
}
break;
} else if (c == 'H') { // Home (go to the beginning of the command)
cursor_position = mystr.length();
break;
} else if (c == '1') { // Home (go to the beginning of the command, Editing key)
(void)getchar(); // swallow '~'
cursor_position = mystr.length();
break;
} else if (c == 'F') { // End (go to the end of the command)
cursor_position = 0;
break;
} else if (c == '4') { // End (go to the end of the command, Editing key)
(void)getchar(); // swallow '~'
cursor_position = 0;
break;
}
if (buf_ptr_read < 0) {
buf_ptr_read = 0;
}
string saved_cmd = string_buffer[buf_ptr_read];
mystr = saved_cmd;
cursor_position = 0; // move cursor to end of line
break;
}
default: // any other input
if (c > 3) {
add_string += (char)c;
} else {
update_prompt = false;
}
break;
}
if (update_prompt) {
// reprint prompt with mystr
mystr.insert(mystr.length() - cursor_position, add_string);
printf("%c[2K", 27);
cout << (char)13;
print_prompt();
cout << mystr;
// Move the cursor to its position
if (cursor_position > 0) {
printf("\033[%dD", cursor_position);
}
}
}
} else {
while (!_ExitFlag) {
usleep(100000);
}
}
// TODO: Always try to stop muorb for QURT because px4_task_is_running doesn't seem to work.
if (true) {
//if (px4_task_is_running("muorb")) {
// sending muorb stop is needed if it is running to exit cleanly
vector<string> muorb_stop_cmd = { "muorb", "stop" };
run_cmd(muorb_stop_cmd, !daemon_mode, true);
}
vector<string> shutdown_cmd = { "shutdown" };
run_cmd(shutdown_cmd, true);
DriverFramework::Framework::shutdown();
return OK;
}
/* vim: set noet fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */