Skip to content

Commit

Permalink
src: connection: Fix panic when DNS lookup fails
Browse files Browse the repository at this point in the history
  • Loading branch information
joaoantoniocardoso committed Jan 10, 2024
1 parent 44dba87 commit 04f12e5
Show file tree
Hide file tree
Showing 3 changed files with 25 additions and 45 deletions.
16 changes: 16 additions & 0 deletions src/connection/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -102,3 +102,19 @@ pub fn connect<M: Message>(address: &str) -> io::Result<Box<dyn MavConnection<M>
protocol_err
}
}

/// Returns the socket address for the given address.
pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
address: T,
) -> Result<std::net::SocketAddr, io::Error> {
let addr = match address.to_socket_addrs()?.next() {
Some(addr) => addr,
None => {
return Err(io::Error::new(
io::ErrorKind::Other,
"Host address lookup failed",
));
}
};
Ok(addr)
}
22 changes: 4 additions & 18 deletions src/connection/tcp.rs
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@ use std::net::{TcpListener, TcpStream};
use std::sync::Mutex;
use std::time::Duration;

use super::get_socket_addr;

/// TCP MAVLink connection

pub fn select_protocol<M: Message>(
Expand All @@ -26,15 +28,7 @@ pub fn select_protocol<M: Message>(
}

pub fn tcpout<T: ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
let addr = match address.to_socket_addrs()?.next() {
Some(addr) => addr,
None => {
return Err(io::Error::new(
io::ErrorKind::Other,
"Host address lookup failed",
));
}
};
let addr = get_socket_addr(address)?;

let socket = TcpStream::connect(addr)?;
socket.set_read_timeout(Some(Duration::from_millis(100)))?;
Expand All @@ -50,15 +44,7 @@ pub fn tcpout<T: ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
}

pub fn tcpin<T: ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
let addr = match address.to_socket_addrs()?.next() {
Some(addr) => addr,
None => {
return Err(io::Error::new(
io::ErrorKind::Other,
"Host address lookup failed",
));
}
};
let addr = get_socket_addr(address)?;
let listener = TcpListener::bind(addr)?;

//For now we only accept one incoming stream: this blocks until we get one
Expand Down
32 changes: 5 additions & 27 deletions src/connection/udp.rs
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@ use std::net::ToSocketAddrs;
use std::net::{SocketAddr, UdpSocket};
use std::sync::Mutex;

use super::get_socket_addr;

/// UDP MAVLink connection

pub fn select_protocol<M: Message>(
Expand All @@ -28,15 +30,7 @@ pub fn select_protocol<M: Message>(
}

pub fn udpbcast<T: ToSocketAddrs>(address: T) -> io::Result<UdpConnection> {
let addr = match address.to_socket_addrs()?.next() {
Some(addr) => addr,
None => {
return Err(io::Error::new(
io::ErrorKind::Other,
"Host address lookup failed",
));
}
};
let addr = get_socket_addr(address)?;
let socket = UdpSocket::bind("0.0.0.0:0").unwrap();
socket
.set_broadcast(true)
Expand All @@ -45,29 +39,13 @@ pub fn udpbcast<T: ToSocketAddrs>(address: T) -> io::Result<UdpConnection> {
}

pub fn udpout<T: ToSocketAddrs>(address: T) -> io::Result<UdpConnection> {
let addr = match address.to_socket_addrs()?.next() {
Some(addr) => addr,
None => {
return Err(io::Error::new(
io::ErrorKind::Other,
"Host address lookup failed",
));
}
};
let addr = get_socket_addr(address)?;
let socket = UdpSocket::bind("0.0.0.0:0")?;
UdpConnection::new(socket, false, Some(addr))
}

pub fn udpin<T: ToSocketAddrs>(address: T) -> io::Result<UdpConnection> {
let addr = match address.to_socket_addrs()?.next() {
Some(addr) => addr,
None => {
return Err(io::Error::new(
io::ErrorKind::Other,
"Host address lookup failed",
));
}
};
let addr = get_socket_addr(address)?;
let socket = UdpSocket::bind(addr)?;
UdpConnection::new(socket, true, None)
}
Expand Down

0 comments on commit 04f12e5

Please sign in to comment.