2015-06-17 04:04:51 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
/*
|
|
|
|
implementation of NSH shell as a stream, for use in nsh over MAVLink
|
|
|
|
|
|
|
|
See GCS_serial_control.cpp for usage
|
|
|
|
*/
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2015-06-17 04:04:51 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
|
|
#include <stdio.h>
|
|
|
|
#include <stdarg.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
#include <stdlib.h>
|
|
|
|
#include <errno.h>
|
|
|
|
#include <apps/nsh.h>
|
|
|
|
#include <fcntl.h>
|
|
|
|
#include <sys/ioctl.h>
|
|
|
|
#include "Scheduler.h"
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
#include "Util.h"
|
|
|
|
using namespace PX4;
|
|
|
|
|
AP_HAL_PX4: fix passing callback to member function
This is the same approach as done for AP_HAL_Linux in e3d78b8 ("AP_HAL_Linux:
fix passing callback to member function"). It fixes the following warnings:
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp: In member function 'virtual void PX4::PX4Scheduler::init(void*)':
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:55:95: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_timer_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_timer_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:65:94: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_uart_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_uart_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:75:92: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_io_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_io_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:85:100: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_storage_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_storage_thread, this);
ardupilot/libraries/AP_HAL_PX4/NSHShellStream.cpp: In member function 'void PX4::NSHShellStream::start_shell()':
ardupilot/libraries/AP_HAL_PX4/NSHShellStream.cpp:83:99: warning: converting from 'void (PX4::NSHShellStream::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&shell_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::NSHShellStream::shell_thread, this);
^
2015-11-25 13:30:34 -04:00
|
|
|
void NSHShellStream::shell_thread(void *arg)
|
2015-06-17 04:04:51 -03:00
|
|
|
{
|
AP_HAL_PX4: fix passing callback to member function
This is the same approach as done for AP_HAL_Linux in e3d78b8 ("AP_HAL_Linux:
fix passing callback to member function"). It fixes the following warnings:
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp: In member function 'virtual void PX4::PX4Scheduler::init(void*)':
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:55:95: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_timer_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_timer_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:65:94: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_uart_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_uart_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:75:92: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_io_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_io_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:85:100: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_storage_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_storage_thread, this);
ardupilot/libraries/AP_HAL_PX4/NSHShellStream.cpp: In member function 'void PX4::NSHShellStream::start_shell()':
ardupilot/libraries/AP_HAL_PX4/NSHShellStream.cpp:83:99: warning: converting from 'void (PX4::NSHShellStream::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&shell_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::NSHShellStream::shell_thread, this);
^
2015-11-25 13:30:34 -04:00
|
|
|
NSHShellStream *nsh = (NSHShellStream *)arg;
|
2015-06-17 04:04:51 -03:00
|
|
|
close(0);
|
|
|
|
close(1);
|
|
|
|
close(2);
|
AP_HAL_PX4: fix passing callback to member function
This is the same approach as done for AP_HAL_Linux in e3d78b8 ("AP_HAL_Linux:
fix passing callback to member function"). It fixes the following warnings:
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp: In member function 'virtual void PX4::PX4Scheduler::init(void*)':
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:55:95: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_timer_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_timer_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:65:94: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_uart_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_uart_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:75:92: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_io_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_io_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:85:100: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_storage_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_storage_thread, this);
ardupilot/libraries/AP_HAL_PX4/NSHShellStream.cpp: In member function 'void PX4::NSHShellStream::start_shell()':
ardupilot/libraries/AP_HAL_PX4/NSHShellStream.cpp:83:99: warning: converting from 'void (PX4::NSHShellStream::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&shell_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::NSHShellStream::shell_thread, this);
^
2015-11-25 13:30:34 -04:00
|
|
|
dup2(nsh->child.in, 0);
|
|
|
|
dup2(nsh->child.out, 1);
|
|
|
|
dup2(nsh->child.out, 2);
|
2015-06-17 04:04:51 -03:00
|
|
|
|
|
|
|
nsh_consolemain(0, NULL);
|
|
|
|
|
AP_HAL_PX4: fix passing callback to member function
This is the same approach as done for AP_HAL_Linux in e3d78b8 ("AP_HAL_Linux:
fix passing callback to member function"). It fixes the following warnings:
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp: In member function 'virtual void PX4::PX4Scheduler::init(void*)':
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:55:95: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_timer_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_timer_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:65:94: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_uart_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_uart_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:75:92: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_io_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_io_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:85:100: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_storage_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_storage_thread, this);
ardupilot/libraries/AP_HAL_PX4/NSHShellStream.cpp: In member function 'void PX4::NSHShellStream::start_shell()':
ardupilot/libraries/AP_HAL_PX4/NSHShellStream.cpp:83:99: warning: converting from 'void (PX4::NSHShellStream::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&shell_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::NSHShellStream::shell_thread, this);
^
2015-11-25 13:30:34 -04:00
|
|
|
nsh->shell_stdin = -1;
|
|
|
|
nsh->shell_stdout = -1;
|
|
|
|
nsh->child.in = -1;
|
|
|
|
nsh->child.out = -1;
|
2015-06-17 04:04:51 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void NSHShellStream::start_shell(void)
|
|
|
|
{
|
|
|
|
if (hal.util->available_memory() < 8192) {
|
|
|
|
if (!showed_memory_warning) {
|
|
|
|
showed_memory_warning = true;
|
|
|
|
hal.console->printf("Not enough memory for shell\n");
|
|
|
|
}
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (hal.util->get_soft_armed()) {
|
|
|
|
if (!showed_armed_warning) {
|
|
|
|
showed_armed_warning = true;
|
|
|
|
hal.console->printf("Disarm to start nsh shell\n");
|
|
|
|
}
|
|
|
|
// don't allow shell start when armed
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
int p1[2], p2[2];
|
|
|
|
|
|
|
|
if (pipe(p1) != 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (pipe(p2) != 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
shell_stdin = p1[0];
|
|
|
|
shell_stdout = p2[1];
|
|
|
|
child.in = p2[0];
|
|
|
|
child.out = p1[1];
|
|
|
|
|
|
|
|
pthread_attr_t thread_attr;
|
|
|
|
struct sched_param param;
|
|
|
|
|
|
|
|
pthread_attr_init(&thread_attr);
|
|
|
|
pthread_attr_setstacksize(&thread_attr, 2048);
|
|
|
|
|
|
|
|
param.sched_priority = APM_SHELL_PRIORITY;
|
|
|
|
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
|
|
|
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
|
|
|
|
|
|
|
pthread_create(&shell_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::NSHShellStream::shell_thread, this);
|
|
|
|
}
|
|
|
|
|
|
|
|
size_t NSHShellStream::write(uint8_t b)
|
|
|
|
{
|
|
|
|
if (shell_stdout == -1) {
|
|
|
|
start_shell();
|
|
|
|
}
|
|
|
|
if (shell_stdout != -1) {
|
|
|
|
return ::write(shell_stdout, &b, 1);
|
|
|
|
}
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
size_t NSHShellStream::write(const uint8_t *buffer, size_t size)
|
|
|
|
{
|
|
|
|
size_t ret = 0;
|
|
|
|
while (size > 0) {
|
|
|
|
if (write(*buffer++) != 1) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
ret++;
|
|
|
|
size--;
|
|
|
|
}
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
|
|
|
int16_t NSHShellStream::read()
|
|
|
|
{
|
|
|
|
if (shell_stdin == -1) {
|
|
|
|
start_shell();
|
|
|
|
}
|
|
|
|
if (shell_stdin != -1) {
|
|
|
|
uint8_t b;
|
|
|
|
if (::read(shell_stdin, &b, 1) == 1) {
|
|
|
|
return b;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return -1;
|
|
|
|
}
|
|
|
|
|
2016-08-02 10:42:50 -03:00
|
|
|
uint32_t NSHShellStream::available()
|
2015-06-17 04:04:51 -03:00
|
|
|
{
|
2016-08-02 10:42:50 -03:00
|
|
|
uint32_t ret = 0;
|
2015-06-17 04:04:51 -03:00
|
|
|
if (ioctl(shell_stdin, FIONREAD, (unsigned long)&ret) == OK) {
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
2016-08-02 10:42:50 -03:00
|
|
|
uint32_t NSHShellStream::txspace()
|
2015-06-17 04:04:51 -03:00
|
|
|
{
|
2016-08-02 10:42:50 -03:00
|
|
|
uint32_t ret = 0;
|
2015-06-17 04:04:51 -03:00
|
|
|
if (ioctl(shell_stdout, FIONWRITE, (unsigned long)&ret) == OK) {
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
#endif // CONFIG_HAL_BOARD
|