Skip to content

Commit be0bc1e

Browse files
joaoantoniocardosopatrickelectric
authored andcommitted
src: connection: Fix panic when DNS lookup fails
1 parent d828e6e commit be0bc1e

File tree

3 files changed

+27
-26
lines changed

3 files changed

+27
-26
lines changed

src/connection/mod.rs

+16
Original file line numberDiff line numberDiff line change
@@ -102,3 +102,19 @@ pub fn connect<M: Message>(address: &str) -> io::Result<Box<dyn MavConnection<M>
102102
protocol_err
103103
}
104104
}
105+
106+
/// Returns the socket address for the given address.
107+
pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
108+
address: T,
109+
) -> Result<std::net::SocketAddr, io::Error> {
110+
let addr = match address.to_socket_addrs()?.next() {
111+
Some(addr) => addr,
112+
None => {
113+
return Err(io::Error::new(
114+
io::ErrorKind::Other,
115+
"Host address lookup failed",
116+
));
117+
}
118+
};
119+
Ok(addr)
120+
}

src/connection/tcp.rs

+5-10
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,8 @@ use std::net::{TcpListener, TcpStream};
66
use std::sync::Mutex;
77
use std::time::Duration;
88

9+
use super::get_socket_addr;
10+
911
/// TCP MAVLink connection
1012
1113
pub fn select_protocol<M: Message>(
@@ -26,11 +28,8 @@ pub fn select_protocol<M: Message>(
2628
}
2729

2830
pub fn tcpout<T: ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
29-
let addr = address
30-
.to_socket_addrs()
31-
.unwrap()
32-
.next()
33-
.expect("Host address lookup failed.");
31+
let addr = get_socket_addr(address)?;
32+
3433
let socket = TcpStream::connect(addr)?;
3534
socket.set_read_timeout(Some(Duration::from_millis(100)))?;
3635

@@ -45,11 +44,7 @@ pub fn tcpout<T: ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
4544
}
4645

4746
pub fn tcpin<T: ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
48-
let addr = address
49-
.to_socket_addrs()
50-
.unwrap()
51-
.next()
52-
.expect("Invalid address");
47+
let addr = get_socket_addr(address)?;
5348
let listener = TcpListener::bind(addr)?;
5449

5550
//For now we only accept one incoming stream: this blocks until we get one

src/connection/udp.rs

+6-16
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,8 @@ use std::net::ToSocketAddrs;
66
use std::net::{SocketAddr, UdpSocket};
77
use std::sync::Mutex;
88

9+
use super::get_socket_addr;
10+
911
/// UDP MAVLink connection
1012
1113
pub fn select_protocol<M: Message>(
@@ -28,34 +30,22 @@ pub fn select_protocol<M: Message>(
2830
}
2931

3032
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")?;
3735
socket
3836
.set_broadcast(true)
3937
.expect("Couldn't bind to broadcast address.");
4038
UdpConnection::new(socket, false, Some(addr))
4139
}
4240

4341
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)?;
4943
let socket = UdpSocket::bind("0.0.0.0:0")?;
5044
UdpConnection::new(socket, false, Some(addr))
5145
}
5246

5347
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)?;
5949
let socket = UdpSocket::bind(addr)?;
6050
UdpConnection::new(socket, true, None)
6151
}

0 commit comments

Comments
 (0)