mavlink: simplified UDP suport by adding new -u option

Use:

    mavlink start -u portnum

to set the UDP port.

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois
2015-06-05 09:55:35 -07:00
parent aded2d3c03
commit 59ad47003a
+15 -22
View File
@@ -176,7 +176,7 @@ Mavlink::Mavlink() :
_rate_rx(0.0f), _rate_rx(0.0f),
_socket_fd(-1), _socket_fd(-1),
_protocol(SERIAL), _protocol(SERIAL),
_udp_port(14556), _udp_port(14556),
_rstatus {}, _rstatus {},
_message_buffer {}, _message_buffer {},
_message_buffer_mutex {}, _message_buffer_mutex {},
@@ -1338,8 +1338,10 @@ Mavlink::task_main(int argc, char *argv[])
bool err_flag = false; bool err_flag = false;
int myoptind=1; int myoptind=1;
const char *myoptarg = NULL; const char *myoptarg = NULL;
char* eptr;
int temp_int_arg;
while ((ch = px4_getopt(argc, argv, "b:r:d:m:fpvwx", &myoptind, &myoptarg)) != EOF) { while ((ch = px4_getopt(argc, argv, "b:r:d:u:m:fpvwx", &myoptind, &myoptarg)) != EOF) {
switch (ch) { switch (ch) {
case 'b': case 'b':
_baudrate = strtoul(myoptarg, NULL, 10); _baudrate = strtoul(myoptarg, NULL, 10);
@@ -1364,26 +1366,17 @@ Mavlink::task_main(int argc, char *argv[])
case 'd': case 'd':
_device_name = myoptarg; _device_name = myoptarg;
if (strncmp(_device_name, "udp",3) == 0) { if (strncmp(_device_name, "udp",3) == 0) {
bool err = false;
set_protocol(UDP); set_protocol(UDP);
const char* p = strchr(_device_name,':'); }
if (p != nullptr ) { break;
p++;
if (strlen(p) > 0) { case 'u':
char* eptr; temp_int_arg = strtoul(myoptarg, &eptr, 10);
int port = strtol(p,&eptr,0); if ( *eptr == '\0' ) {
if (*eptr == 0) { _udp_port = temp_int_arg;
_udp_port = port; } else {
} warnx("invalid data udp_port '%s'", myoptarg);
else { err_flag = true;
err = true;
}
}
}
if (err) {
warnx("invalid device-name '%s'", myoptarg);
}
err_flag |= err;
} }
break; break;
@@ -1942,7 +1935,7 @@ Mavlink::stream_command(int argc, char *argv[])
static void usage() static void usage()
{ {
warnx("usage: mavlink {start|stop-all|stream} [-d udp[:<port-num>]] [-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 udp_port] [-b baudrate]\n\t[-r rate][-m mode] [-s stream] [-f] [-p] [-v] [-w] [-x]");
} }
int mavlink_main(int argc, char *argv[]) int mavlink_main(int argc, char *argv[])