SITL: added -C option to desktop mode

this allows running APM to stdout, which is useful for test sketches
This commit is contained in:
Andrew Tridgell 2012-02-24 17:22:02 +11:00
parent f221bd13ab
commit 1d95137b71
3 changed files with 27 additions and 2 deletions

View File

@ -70,6 +70,7 @@ static struct tcp_state {
int listen_fd; // socket we are listening on
int fd; // data socket
int serial_port;
bool console;
} tcp_state[FS_MAX_PORTS];
@ -85,6 +86,17 @@ static void tcp_start_connection(unsigned int serial_port, bool wait_for_connect
struct sockaddr_in sockaddr;
int ret;
if (desktop_state.console_mode) {
// hack for console access
s->connected = true;
s->listen_fd = -1;
s->fd = 1;
s->serial_port = serial_port;
s->console = true;
set_nonblocking(0);
return;
}
s->serial_port = serial_port;
memset(&sockaddr,0,sizeof(sockaddr));
@ -291,6 +303,10 @@ int FastSerial::read(void)
return -1;
}
if (s->console) {
return ::read(0, &c, 1);
}
int n = recv(s->fd, &c, 1, MSG_DONTWAIT | MSG_NOSIGNAL);
if (n <= 0) {
// the socket has reached EOF
@ -326,7 +342,11 @@ void FastSerial::write(uint8_t c)
if (!desktop_state.slider) {
flags |= MSG_DONTWAIT;
}
send(s->fd, &c, 1, flags);
if (s->console) {
::write(s->fd, &c, 1);
} else {
send(s->fd, &c, 1, flags);
}
}
// Buffer management ///////////////////////////////////////////////////////////

View File

@ -10,6 +10,7 @@ struct desktop_info {
bool quadcopter; // use quadcopter outputs
unsigned framerate;
float initial_height;
bool console_mode;
};
extern struct desktop_info desktop_state;

View File

@ -29,6 +29,7 @@ static void usage(void)
printf("\t-w wipe eeprom and dataflash\n");
printf("\t-r RATE set SITL framerate\n");
printf("\t-H HEIGHT initial barometric height\n");
printf("\t-C use console instead of TCP ports\n");
}
int main(int argc, char * const argv[])
@ -40,7 +41,7 @@ int main(int argc, char * const argv[])
signal(SIGFPE, sig_fpe);
while ((opt = getopt(argc, argv, "swhr:H:")) != -1) {
while ((opt = getopt(argc, argv, "swhr:H:C")) != -1) {
switch (opt) {
case 's':
desktop_state.slider = true;
@ -55,6 +56,9 @@ int main(int argc, char * const argv[])
case 'H':
desktop_state.initial_height = atof(optarg);
break;
case 'C':
desktop_state.console_mode = true;
break;
default:
usage();
exit(1);