|
|
|
@ -185,6 +185,7 @@ Mavlink::Mavlink() :
@@ -185,6 +185,7 @@ Mavlink::Mavlink() :
|
|
|
|
|
_socket_fd(-1), |
|
|
|
|
_protocol(SERIAL), |
|
|
|
|
_network_port(14556), |
|
|
|
|
_remote_port(DEFAULT_REMOTE_PORT_UDP), |
|
|
|
|
_rstatus {}, |
|
|
|
|
_message_buffer {}, |
|
|
|
|
_message_buffer_mutex {}, |
|
|
|
@ -1056,7 +1057,7 @@ Mavlink::init_udp()
@@ -1056,7 +1057,7 @@ Mavlink::init_udp()
|
|
|
|
|
if (_mode != MAVLINK_MODE_ONBOARD) { |
|
|
|
|
_src_addr.sin_family = AF_INET; |
|
|
|
|
inet_aton("127.0.0.1", &_src_addr.sin_addr); |
|
|
|
|
_src_addr.sin_port = htons(DEFAULT_REMOTE_PORT_UDP); |
|
|
|
|
_src_addr.sin_port = htons(_remote_port); |
|
|
|
|
set_client_source_initialized(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -1064,7 +1065,7 @@ Mavlink::init_udp()
@@ -1064,7 +1065,7 @@ Mavlink::init_udp()
|
|
|
|
|
memset((char *)&_bcast_addr, 0, sizeof(_bcast_addr)); |
|
|
|
|
_bcast_addr.sin_family = AF_INET; |
|
|
|
|
inet_aton("255.255.255.255", &_bcast_addr.sin_addr); |
|
|
|
|
_bcast_addr.sin_port = htons(DEFAULT_REMOTE_PORT_UDP); |
|
|
|
|
_bcast_addr.sin_port = htons(_remote_port); |
|
|
|
|
|
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
@ -1521,7 +1522,7 @@ Mavlink::task_main(int argc, char *argv[])
@@ -1521,7 +1522,7 @@ Mavlink::task_main(int argc, char *argv[])
|
|
|
|
|
char* eptr; |
|
|
|
|
int temp_int_arg; |
|
|
|
|
|
|
|
|
|
while ((ch = px4_getopt(argc, argv, "b:r:d:u:m:fpvwx", &myoptind, &myoptarg)) != EOF) { |
|
|
|
|
while ((ch = px4_getopt(argc, argv, "b:r:d:u:o:m:fpvwx", &myoptind, &myoptarg)) != EOF) { |
|
|
|
|
switch (ch) { |
|
|
|
|
case 'b': |
|
|
|
|
_baudrate = strtoul(myoptarg, NULL, 10); |
|
|
|
@ -1559,6 +1560,18 @@ Mavlink::task_main(int argc, char *argv[])
@@ -1559,6 +1560,18 @@ Mavlink::task_main(int argc, char *argv[])
|
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case 'o': |
|
|
|
|
temp_int_arg = strtoul(myoptarg, &eptr, 10); |
|
|
|
|
if ( *eptr == '\0' ) { |
|
|
|
|
warnx("set remote port %d", temp_int_arg); |
|
|
|
|
_remote_port = temp_int_arg; |
|
|
|
|
set_protocol(UDP); |
|
|
|
|
} else { |
|
|
|
|
warnx("invalid remote udp_port '%s'", myoptarg); |
|
|
|
|
err_flag = true; |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
// case 'e':
|
|
|
|
|
// mavlink_link_termination_allowed = true;
|
|
|
|
|
// break;
|
|
|
|
@ -2320,7 +2333,7 @@ Mavlink::stream_command(int argc, char *argv[])
@@ -2320,7 +2333,7 @@ Mavlink::stream_command(int argc, char *argv[])
|
|
|
|
|
|
|
|
|
|
static void usage() |
|
|
|
|
{ |
|
|
|
|
warnx("usage: mavlink {start|stop-all|stream} [-d device] [-u udp_port] [-b baudrate]\n\t[-r rate][-m mode] [-s stream] [-f] [-p] [-v] [-w] [-x]"); |
|
|
|
|
warnx("usage: mavlink {start|stop-all|stream} [-d device] [-u network_port] [-o remote_port] [-b baudrate]\n\t[-r rate][-m mode] [-s stream] [-f] [-p] [-v] [-w] [-x]"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
int mavlink_main(int argc, char *argv[]) |
|
|
|
|