|
|
@ -1701,7 +1701,6 @@ Mavlink::task_main(int argc, char *argv[]) |
|
|
|
case 'o': |
|
|
|
case 'o': |
|
|
|
temp_int_arg = strtoul(myoptarg, &eptr, 10); |
|
|
|
temp_int_arg = strtoul(myoptarg, &eptr, 10); |
|
|
|
if ( *eptr == '\0' ) { |
|
|
|
if ( *eptr == '\0' ) { |
|
|
|
warnx("set remote port %d", temp_int_arg); |
|
|
|
|
|
|
|
_remote_port = temp_int_arg; |
|
|
|
_remote_port = temp_int_arg; |
|
|
|
set_protocol(UDP); |
|
|
|
set_protocol(UDP); |
|
|
|
} else { |
|
|
|
} else { |
|
|
@ -1822,8 +1821,8 @@ Mavlink::task_main(int argc, char *argv[]) |
|
|
|
return ERROR; |
|
|
|
return ERROR; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
PX4_INFO("mode: %s, data rate: %d B/s on udp port %hu", |
|
|
|
PX4_INFO("mode: %s, data rate: %d B/s on udp port %hu remote port %hu", |
|
|
|
mavlink_mode_str(_mode), _datarate, _network_port); |
|
|
|
mavlink_mode_str(_mode), _datarate, _network_port, _remote_port); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
/* initialize send mutex */ |
|
|
|
/* initialize send mutex */ |
|
|
|