APM:Libraries
NSHShellStream.cpp
Go to the documentation of this file.
1 /*
2  implementation of NSH shell as a stream, for use in nsh over MAVLink
3 
4  See GCS_serial_control.cpp for usage
5  */
6 
7 #include <AP_HAL/AP_HAL.h>
8 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
9 #include <stdio.h>
10 #include <stdarg.h>
11 #include <unistd.h>
12 #include <stdlib.h>
13 #include <errno.h>
14 #include <apps/nsh.h>
15 #include <fcntl.h>
16 #include <sys/ioctl.h>
17 #include "Scheduler.h"
18 
19 extern const AP_HAL::HAL& hal;
20 
21 #include "Util.h"
22 using namespace VRBRAIN;
23 
25 {
26  NSHShellStream *nsh = (NSHShellStream *)arg;
27  close(0);
28  close(1);
29  close(2);
30  dup2(nsh->child.in, 0);
31  dup2(nsh->child.out, 1);
32  dup2(nsh->child.out, 2);
33 
34  nsh_consolemain(0, nullptr);
35 
36  nsh->shell_stdin = -1;
37  nsh->shell_stdout = -1;
38  nsh->child.in = -1;
39  nsh->child.out = -1;
40 }
41 
43 {
44  if (hal.util->available_memory() < 8192) {
45  if (!showed_memory_warning) {
46  showed_memory_warning = true;
47  hal.console->printf("Not enough memory for shell\n");
48  }
49  return;
50  }
51  if (hal.util->get_soft_armed()) {
52  if (!showed_armed_warning) {
53  showed_armed_warning = true;
54  hal.console->printf("Disarm to start nsh shell\n");
55  }
56  // don't allow shell start when armed
57  return;
58  }
59 
60  int p1[2], p2[2];
61 
62  if (pipe(p1) != 0) {
63  return;
64  }
65  if (pipe(p2) != 0) {
66  return;
67  }
68  shell_stdin = p1[0];
69  shell_stdout = p2[1];
70  child.in = p2[0];
71  child.out = p1[1];
72 
73  pthread_attr_t thread_attr;
74  struct sched_param param;
75 
76  pthread_attr_init(&thread_attr);
77  pthread_attr_setstacksize(&thread_attr, 2048);
78 
79  param.sched_priority = APM_SHELL_PRIORITY;
80  (void)pthread_attr_setschedparam(&thread_attr, &param);
81  pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
82 
83  pthread_create(&shell_thread_ctx, &thread_attr, (pthread_startroutine_t)&VRBRAIN::NSHShellStream::shell_thread, this);
84 }
85 
86 size_t NSHShellStream::write(uint8_t b)
87 {
88  if (shell_stdout == -1) {
89  start_shell();
90  }
91  if (shell_stdout != -1) {
93  }
94  return 0;
95 }
96 
97 size_t NSHShellStream::write(const uint8_t *buffer, size_t size)
98 {
99  size_t ret = 0;
100  while (size > 0) {
101  if (write(*buffer++) != 1) {
102  break;
103  }
104  ret++;
105  size--;
106  }
107  return ret;
108 }
109 
111 {
112  if (shell_stdin == -1) {
113  start_shell();
114  }
115  if (shell_stdin != -1) {
116  uint8_t b;
117  if (::read(shell_stdin, &b, 1) == 1) {
118  return b;
119  }
120  }
121  return -1;
122 }
123 
125 {
126  uint32_t ret = 0;
127  if (ioctl(shell_stdin, FIONREAD, (unsigned long)&ret) == OK) {
128  return ret;
129  }
130  return 0;
131 }
132 
134 {
135  uint32_t ret = 0;
136  if (ioctl(shell_stdout, FIONWRITE, (unsigned long)&ret) == OK) {
137  return ret;
138  }
139  return 0;
140 }
141 
142 #endif // CONFIG_HAL_BOARD
virtual uint32_t available_memory(void)
Definition: Util.h:121
int16_t read() override
bool get_soft_armed() const
Definition: Util.h:15
bool showed_armed_warning
Definition: Util.h:24
AP_HAL::UARTDriver * console
Definition: HAL.h:110
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
pthread_t shell_thread_ctx
Definition: Util.h:17
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
AP_HAL::Util * util
Definition: HAL.h:115
uint32_t txspace() override
uint32_t available() override
#define APM_SHELL_PRIORITY
Definition: Scheduler.h:22
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
bool showed_memory_warning
Definition: Util.h:23
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
struct VRBRAIN::NSHShellStream::@117 child
static void shell_thread(void *arg)