simulator: Add output so user knows that the simulator / system is waiting for data

This commit is contained in:
Lorenz Meier 2015-07-02 16:53:20 -07:00
parent 0499ddb1dd
commit 32bf4dc773
2 changed files with 4 additions and 2 deletions

View File

@ -128,6 +128,7 @@ int Simulator::start(int argc, char *argv[])
PX4_WARN("Simulator creation failed");
ret = 1;
}
return ret;
}

View File

@ -400,6 +400,7 @@ void Simulator::pollForMAVLinkMessages(bool publish)
// wait for first data from simulator and respond with first controls
// this is important for the UDP communication to work
int pret = -1;
PX4_WARN("Waiting for initial data on UDP.. Please connect the simulator first.");
while (pret <= 0) {
pret = ::poll(&fds[0], (sizeof(fds[0])/sizeof(fds[0])), 100);
}
@ -535,9 +536,9 @@ int openUart(const char *uart_name, int baud)
/* Try to set baud rate */
struct termios uart_config;
memset(&uart_config, 0, sizeof(uart_config));
memset(&uart_config, 0, sizeof(uart_config));
int termios_state;
int termios_state;
/* Back up the original uart configuration to restore it after exit */
if ((termios_state = tcgetattr(uart_fd, &uart_config)) < 0) {