@@ -6,6 +6,8 @@ use std::net::ToSocketAddrs;
6
6
use std:: net:: { SocketAddr , UdpSocket } ;
7
7
use std:: sync:: Mutex ;
8
8
9
+ use super :: get_socket_addr;
10
+
9
11
/// UDP MAVLink connection
10
12
11
13
pub fn select_protocol < M : Message > (
@@ -28,34 +30,22 @@ pub fn select_protocol<M: Message>(
28
30
}
29
31
30
32
pub fn udpbcast < T : ToSocketAddrs > ( address : T ) -> io:: Result < UdpConnection > {
31
- let addr = address
32
- . to_socket_addrs ( )
33
- . unwrap ( )
34
- . next ( )
35
- . expect ( "Invalid address" ) ;
36
- let socket = UdpSocket :: bind ( "0.0.0.0:0" ) . unwrap ( ) ;
33
+ let addr = get_socket_addr ( address) ?;
34
+ let socket = UdpSocket :: bind ( "0.0.0.0:0" ) ?;
37
35
socket
38
36
. set_broadcast ( true )
39
37
. expect ( "Couldn't bind to broadcast address." ) ;
40
38
UdpConnection :: new ( socket, false , Some ( addr) )
41
39
}
42
40
43
41
pub fn udpout < T : ToSocketAddrs > ( address : T ) -> io:: Result < UdpConnection > {
44
- let addr = address
45
- . to_socket_addrs ( )
46
- . unwrap ( )
47
- . next ( )
48
- . expect ( "Invalid address" ) ;
42
+ let addr = get_socket_addr ( address) ?;
49
43
let socket = UdpSocket :: bind ( "0.0.0.0:0" ) ?;
50
44
UdpConnection :: new ( socket, false , Some ( addr) )
51
45
}
52
46
53
47
pub fn udpin < T : ToSocketAddrs > ( address : T ) -> io:: Result < UdpConnection > {
54
- let addr = address
55
- . to_socket_addrs ( )
56
- . unwrap ( )
57
- . next ( )
58
- . expect ( "Invalid address" ) ;
48
+ let addr = get_socket_addr ( address) ?;
59
49
let socket = UdpSocket :: bind ( addr) ?;
60
50
UdpConnection :: new ( socket, true , None )
61
51
}
0 commit comments