Browse Source

SITL: make it possible to connect two SITL instances together

this adds --client to set uartC as a tcp client rather than a TCP
server
master
Andrew Tridgell 10 years ago
parent
commit
8ec98a5ec9
  1. 6
      libraries/AP_HAL_SITL/SITL_State.h
  2. 9
      libraries/AP_HAL_SITL/SITL_cmdline.cpp
  3. 72
      libraries/AP_HAL_SITL/UARTDriver.cpp
  4. 4
      libraries/AP_HAL_SITL/UARTDriver.h

6
libraries/AP_HAL_SITL/SITL_State.h

@ -55,6 +55,9 @@ public: @@ -55,6 +55,9 @@ public:
uint16_t voltage_pin_value; // pin 13
uint16_t current_pin_value; // pin 12
// return TCP client address for uartC
const char *get_client_address(void) const { return _client_address; }
private:
void _parse_command_line(int argc, char * const argv[]);
void _set_param_default(const char *parm);
@ -187,6 +190,9 @@ private: @@ -187,6 +190,9 @@ private:
// internal SITL model
Aircraft *sitl_model;
// TCP address to connect uartC to
const char *_client_address;
};
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL

9
libraries/AP_HAL_SITL/SITL_cmdline.cpp

@ -75,6 +75,11 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) @@ -75,6 +75,11 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
_rcout_port = 5502;
_simin_port = 5501;
_fdm_address = "127.0.0.1";
_client_address = NULL;
enum long_options {
CMDLINE_CLIENT=0
};
const struct GetOptLong::option options[] = {
{"help", false, 0, 'h'},
@ -89,6 +94,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) @@ -89,6 +94,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
{"home", true, 0, 'O'},
{"model", true, 0, 'M'},
{"frame", true, 0, 'F'},
{"client", true, 0, CMDLINE_CLIENT},
{0, false, 0, 0}
};
@ -135,6 +141,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) @@ -135,6 +141,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
case 'F':
_fdm_address = gopt.optarg;
break;
case CMDLINE_CLIENT:
_client_address = gopt.optarg;
break;
default:
_usage();
exit(1);

72
libraries/AP_HAL_SITL/UARTDriver.cpp

@ -64,6 +64,14 @@ void SITLUARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) @@ -64,6 +64,14 @@ void SITLUARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
_fd = _sitlState->gps_pipe();
break;
case 2:
if (_sitlState->get_client_address() != NULL) {
_tcp_start_client(_sitlState->get_client_address());
} else {
_tcp_start_connection(false);
}
break;
case 4:
/* gps2 */
_connected = true;
@ -228,9 +236,9 @@ void SITLUARTDriver::_tcp_start_connection(bool wait_for_connection) @@ -228,9 +236,9 @@ void SITLUARTDriver::_tcp_start_connection(bool wait_for_connection)
fprintf(stderr, "bind port %u for %u\n",
(unsigned)ntohs(sockaddr.sin_port),
(unsigned)_portNumber),
(unsigned)_portNumber);
ret = bind(_listen_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
ret = bind(_listen_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
if (ret == -1) {
fprintf(stderr, "bind failed on port %u - %s\n",
(unsigned)ntohs(sockaddr.sin_port),
@ -263,6 +271,66 @@ void SITLUARTDriver::_tcp_start_connection(bool wait_for_connection) @@ -263,6 +271,66 @@ void SITLUARTDriver::_tcp_start_connection(bool wait_for_connection)
}
}
/*
start a TCP client connection for the serial port.
*/
void SITLUARTDriver::_tcp_start_client(const char *address)
{
int one=1;
struct sockaddr_in sockaddr;
int ret;
if (_connected) {
return;
}
if (_fd != -1) {
close(_fd);
}
char *addr2 = strdup(address);
char *p = strchr(addr2, ':');
if (p == NULL) {
fprintf(stderr, "need IP:port\n");
exit(1);
}
*p = 0;
uint16_t port = htons(atoi(p+1));
memset(&sockaddr,0,sizeof(sockaddr));
#ifdef HAVE_SOCK_SIN_LEN
sockaddr.sin_len = sizeof(sockaddr);
#endif
sockaddr.sin_port = port;
sockaddr.sin_family = AF_INET;
sockaddr.sin_addr.s_addr = inet_addr(addr2);
free(addr2);
_fd = socket(AF_INET, SOCK_STREAM, 0);
if (_fd == -1) {
fprintf(stderr, "socket failed - %s\n", strerror(errno));
exit(1);
}
/* we want to be able to re-use ports quickly */
setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
ret = connect(_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
if (ret == -1) {
fprintf(stderr, "connect failed on port %u - %s\n",
(unsigned)ntohs(sockaddr.sin_port),
strerror(errno));
exit(1);
}
setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
_connected = true;
}
/*
see if a new connection is coming in
*/

4
libraries/AP_HAL_SITL/UARTDriver.h

@ -65,7 +65,11 @@ private: @@ -65,7 +65,11 @@ private:
uint16_t _rxSpace;
uint16_t _txSpace;
// IPv4 address of target for uartC
const char *_tcp_client_addr;
void _tcp_start_connection(bool wait_for_connection);
void _tcp_start_client(const char *address);
void _check_connection(void);
static bool _select_check(int );
static void _set_nonblocking(int );

Loading…
Cancel
Save