diff --git a/app/telemetry/connection/tcp_connection.cpp b/app/telemetry/connection/tcp_connection.cpp index 3773eba14..0857aeca4 100644 --- a/app/telemetry/connection/tcp_connection.cpp +++ b/app/telemetry/connection/tcp_connection.cpp @@ -2,7 +2,7 @@ #include "tutil/qopenhdmavlinkhelper.hpp" #ifdef __windows__ -#define _WIN32_WINNT 0x0600 //TODO dirty +#define _WIN32_WINNT 0x0600 // TODO dirty #include #include // For InetPton #include @@ -13,263 +13,178 @@ #endif #include #include - #include - #include "mavlinkchannel.h" -static int tcp_socket_try_connect(const std::string remote_ip, const int remote_port,const int timeout_seconds){ - //qDebug()<<"tcp_socket_try_connect:"<(&remote_addr), sizeof(struct sockaddr_in)); - if(connect_result==0){ - qDebug()<<"Got connection immeiately"; + if (inet_pton(AF_INET, remote_ip.c_str(), &remote_addr.sin_addr) <= 0) { + qDebug() << "Error: Invalid IP address format -" << remote_ip.c_str(); + close(sockfd); + return -1; + } + + int connect_result = connect(sockfd, reinterpret_cast(&remote_addr), sizeof(struct sockaddr_in)); + if (connect_result == 0) { + qDebug() << "Connection established immediately."; return sockfd; } - if ((connect_result== -1) && (errno != EINPROGRESS)) { - qDebug()<<"Didnt get EINPROGRESS"<<(int)connect_result; + + if (connect_result == -1 && errno != EINPROGRESS) { + qDebug() << "Error: Connect failed and not EINPROGRESS -" << strerror(errno); close(sockfd); return -1; } - // Wait for up to X seconds to connect + + qDebug() << "Connection in progress, waiting for completion."; + fd_set fdset; struct timeval tv; FD_ZERO(&fdset); FD_SET(sockfd, &fdset); tv.tv_sec = timeout_seconds; tv.tv_usec = 0; - const int rc= select(sockfd + 1, NULL, &fdset, NULL, &tv); - if(rc!=1){ - qDebug()<<"Timed out or other crap"; + + int rc = select(sockfd + 1, NULL, &fdset, NULL, &tv); + if (rc != 1) { + qDebug() << "Error: Timeout or other issue in select() -" << strerror(errno); close(sockfd); return -1; } - // Check if there are any errors + int so_error; - // data to read socklen_t len = sizeof(so_error); - #ifdef __linux__ getsockopt(sockfd, SOL_SOCKET, SO_ERROR, &so_error, &len); if (so_error != 0) { - qDebug()<<"Any socket error:"<(data), data_len, flags, reinterpret_cast(&dest_addr), - sizeof(dest_addr)); + sizeof(dest_addr) + ); if (send_len != data_len) { + qDebug() << "Error: Failed to send message. Sent bytes:" << send_len + << "Expected:" << data_len << "-" << strerror(errno); return false; } - return true; -} - -TCPConnection::TCPConnection(MAV_MSG_CB cb, std::string remote_ip, int remote_port, int mavlink_channel): - m_cb(cb), - m_remote_ip(remote_ip), - m_remote_port(remote_port), - m_mav_channel(mavlink_channel) -{ -} - -TCPConnection::~TCPConnection() -{ - if(is_looping()){ - stop_looping(); - } -} - -void TCPConnection::set_remote(std::string remote_ip, int remote_port) -{ - assert(m_receive_thread==nullptr); - m_remote_ip=remote_ip; - m_remote_port=remote_port; -} - -bool TCPConnection::is_looping() -{ - return m_receive_thread!=nullptr; -} - -void TCPConnection::start_looping() -{ - assert(m_receive_thread==nullptr); - m_keep_receiving=true; - m_receive_thread=std::make_unique(&TCPConnection::loop_connect_receive,this); + qDebug() << "Message sent successfully. Bytes:" << send_len; + return true; } -void TCPConnection::stop_looping_if() -{ - if(is_looping())stop_looping(); -} +void TCPConnection::stop_looping() { + assert(m_receive_thread != nullptr); + qDebug() << "Stopping TCPConnection loop."; -void TCPConnection::stop_looping() -{ - assert(m_receive_thread!=nullptr); - qDebug()<<"TCPConnection2::stop_receiving begin"; - m_keep_receiving=false; + m_keep_receiving = false; #ifdef __windows__ - shutdown(m_socket_fd, SD_BOTH); - - closesocket(m_socket_fd); - - WSACleanup(); -#else \ - // This should interrupt a recv/recvfrom call. - shutdown(m_socket_fd, SHUT_RDWR); - // But on Mac, closing is also needed to stop blocking recv/recvfrom. - close(m_socket_fd); -#endif - m_receive_thread->join(); - m_receive_thread=nullptr; - qDebug()<<"TCPConnection2::stop_receiving end"; -} - - - - - -void TCPConnection::send_message(const mavlink_message_t &msg) -{ - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - const int buffer_len = mavlink_msg_to_send_buffer(buffer, &msg); - if(!m_keep_receiving){ - return; // Otherwise sendto blocks + if (shutdown(m_socket_fd, SD_BOTH) == SOCKET_ERROR) { + qDebug() << "Error: Failed to shutdown socket -" << WSAGetLastError(); } - if(m_socket_fd<0){ - //qDebug()<<"Cannot send message"; - return; + if (closesocket(m_socket_fd) == SOCKET_ERROR) { + qDebug() << "Error: Failed to close socket -" << WSAGetLastError(); } - if(!linux_send_message(m_socket_fd,m_remote_ip,m_remote_port,buffer,buffer_len)){ - //qDebug()<<"Cannot send message"; + WSACleanup(); +#else + if (shutdown(m_socket_fd, SHUT_RDWR) < 0) { + qDebug() << "Error: Failed to shutdown socket -" << strerror(errno); } -} - -bool TCPConnection::threadsafe_is_alive() -{ - const int32_t now_ms=QOpenHDMavlinkHelper::getTimeMilliseconds();; - const auto elapsed=now_ms-m_last_data_ms; - return elapsed <= 3*1000; -} + if (close(m_socket_fd) < 0) { + qDebug() << "Error: Failed to close socket -" << strerror(errno); + } +#endif + m_socket_fd = -1; -void TCPConnection::process_data(const uint8_t *data, int data_len) -{ - m_last_data_ms=QOpenHDMavlinkHelper::getTimeMilliseconds(); - mavlink_message_t msg; - for (int i = 0; i < data_len; i++) { - uint8_t res = mavlink_parse_char(m_mav_channel,data[i], &msg, &m_recv_status); - if (res) { - process_mavlink_message(msg); - } + if (m_receive_thread->joinable()) { + m_receive_thread->join(); + qDebug() << "Receive thread stopped."; } -} -void TCPConnection::process_mavlink_message(mavlink_message_t message) -{ - m_cb(message); + m_receive_thread = nullptr; + qDebug() << "TCPConnection loop stopped."; } +void TCPConnection::receive_until_stopped() { + qDebug() << "Receiving data until stopped."; + auto buffer = std::make_unique>(1500); // Enough for MTU 1500 bytes -void TCPConnection::receive_until_stopped() -{ - // Enough for MTU 1500 bytes. - auto buffer=std::make_unique>(); - buffer->resize(1500); - //struct timeval tv; - //tv.tv_sec = 3; - //tv.tv_usec = 0; - //setsockopt(m_socket_fd, SOL_SOCKET, SO_RCVTIMEO, (const char*)&tv, sizeof tv); while (m_keep_receiving) { - const auto elapsed_last_message=QOpenHDMavlinkHelper::getTimeMilliseconds()-m_last_data_ms; - if(elapsed_last_message>3*1000){ - qDebug()<<"No message for more than 3 seconds, disconnecting"; + const auto elapsed = QOpenHDMavlinkHelper::getTimeMilliseconds() - m_last_data_ms; + if (elapsed > 3000) { + qDebug() << "No message received for 3 seconds. Disconnecting."; return; } + const auto recv_len = recvfrom( m_socket_fd, - (char*)buffer->data(), + reinterpret_cast(buffer->data()), buffer->size(), 0, nullptr, - nullptr); + nullptr + ); if (recv_len == 0) { - // This can happen when shutdown is called on the socket, - // therefore we check _should_exit again. - //qDebug()<<"Got recv_len==0"; - //return; + qDebug() << "Received length 0. Possibly socket closed."; continue; } if (recv_len < 0) { - // This happens on desctruction when close(_socket_fd) is called, - // therefore be quiet. - // LogErr() << "recvfrom error: " << GET_ERROR(errno); - // Something went wrong, we should try to re-connect in next iteration. - //qDebug()<<"Got recv_len<0 :"<data(),recv_len); - } -} -void TCPConnection::loop_connect_receive() -{ -#ifdef __linux__ - qDebug()<<"TCPConnection2::loop_connect_receive begin"; - while(m_keep_receiving){ - m_socket_fd=tcp_socket_try_connect(m_remote_ip,m_remote_port,3); - if(m_socket_fd>0){ - m_last_data_ms=QOpenHDMavlinkHelper::getTimeMilliseconds(); - receive_until_stopped(); - qDebug()<<"Broke out of receive loop"; - close(m_socket_fd); - m_socket_fd=-1; - }else{ - int count=0; - while(m_keep_receiving && count<3){ - std::this_thread::sleep_for(std::chrono::seconds(1)); - count++; - } - } + qDebug() << "Received data. Bytes:" << recv_len; + process_data(buffer->data(), recv_len); } - qDebug()<<"TCPConnection2::loop_connect_receive end"; -#endif } diff --git a/app/telemetry/connection/udp_connection.cpp b/app/telemetry/connection/udp_connection.cpp index ac363f990..8d22f4d00 100644 --- a/app/telemetry/connection/udp_connection.cpp +++ b/app/telemetry/connection/udp_connection.cpp @@ -2,7 +2,7 @@ #include "tutil/qopenhdmavlinkhelper.hpp" #ifdef __windows__ -#define _WIN32_WINNT 0x0600 //TODO dirty +#define _WIN32_WINNT 0x0600 // TODO dirty #include #include // For InetPton #else @@ -21,242 +21,190 @@ #define GET_ERROR(_x) strerror(_x) #endif -#ifdef __windows__ -#endif - - -UDPConnection::UDPConnection(const std::string local_ip,const int local_port,MAV_MSG_CB cb) - :m_local_ip(local_ip),m_local_port(local_port),m_cb(cb) +UDPConnection::UDPConnection(const std::string local_ip, const int local_port, MAV_MSG_CB cb) + : m_local_ip(local_ip), m_local_port(local_port), m_cb(cb) { - + qDebug() << "UDPConnection initialized with local IP:" << local_ip.c_str() + << "Port:" << local_port; } UDPConnection::~UDPConnection() { + qDebug() << "Destroying UDPConnection..."; stop_looping_if(); } - void UDPConnection::start_looping() { - assert(m_receive_thread==nullptr); - m_keep_receiving=true; - m_receive_thread=std::make_unique(&UDPConnection::loop_receive,this); + qDebug() << "Starting UDP receiving loop..."; + assert(m_receive_thread == nullptr); + m_keep_receiving = true; + m_receive_thread = std::make_unique(&UDPConnection::loop_receive, this); + qDebug() << "UDP receiving loop started."; } void UDPConnection::stop_looping() { - assert(m_receive_thread!=nullptr); - qDebug()<<"UDP stop - begin"; - m_keep_receiving=false; -#ifdef __windows__ - shutdown(m_socket_fd, SD_BOTH); + assert(m_receive_thread != nullptr); + qDebug() << "Stopping UDP receiving loop..."; - closesocket(m_socket_fd); + m_keep_receiving = false; +#ifdef __windows__ + if (shutdown(m_socket_fd, SD_BOTH) == SOCKET_ERROR) { + qDebug() << "Error: Failed to shutdown socket -" << WSAGetLastError(); + } + if (closesocket(m_socket_fd) == SOCKET_ERROR) { + qDebug() << "Error: Failed to close socket -" << WSAGetLastError(); + } WSACleanup(); #else - // This should interrupt a recv/recvfrom call. - shutdown(m_socket_fd, SHUT_RDWR); - - // But on Mac, closing is also needed to stop blocking recv/recvfrom. - close(m_socket_fd); + if (shutdown(m_socket_fd, SHUT_RDWR) < 0) { + qDebug() << "Error: Failed to shutdown socket -" << strerror(errno); + } + if (close(m_socket_fd) < 0) { + qDebug() << "Error: Failed to close socket -" << strerror(errno); + } #endif - if(m_receive_thread){ + + if (m_receive_thread && m_receive_thread->joinable()) { m_receive_thread->join(); + qDebug() << "UDP receive thread stopped."; } - m_receive_thread=nullptr; - qDebug()<<"UDP stop - end"; + m_receive_thread = nullptr; + qDebug() << "UDP receiving loop stopped."; } void UDPConnection::send_message(const mavlink_message_t &msg) { - auto opt_remote=get_current_remote(); - if(opt_remote.has_value()){ - const Remote& remote=opt_remote.value(); - struct sockaddr_in dest_addr {}; - dest_addr.sin_family = AF_INET; - inet_pton(AF_INET, remote.ip.c_str(), &dest_addr.sin_addr.s_addr); - dest_addr.sin_port = htons(remote.port); - - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t buffer_len = mavlink_msg_to_send_buffer(buffer, &msg); - - const auto send_len = sendto( - m_socket_fd, - reinterpret_cast(buffer), - buffer_len, - 0, - reinterpret_cast(&dest_addr), - sizeof(dest_addr)); - - if (send_len != buffer_len) { - qDebug()<<"Cannot send data to "<(buffer), + buffer_len, + 0, + reinterpret_cast(&dest_addr), + sizeof(dest_addr)); + + if (send_len != buffer_len) { + qDebug() << "Error: Failed to send data to" << remote.to_string().c_str() << "-" + << strerror(errno); + } else { + qDebug() << "Message sent successfully to" << remote.to_string().c_str() + << "Bytes sent:" << send_len; } } -void UDPConnection::process_mavlink_message(mavlink_message_t message) -{ - m_cb(message); -} - void UDPConnection::loop_receive() { - while(m_keep_receiving){ - qDebug()<<"UDP start receiving on "<(&addr), sizeof(addr)) != 0) { - qDebug()<<"Cannot bind port "<>(); - buffer->resize(1500); + const bool success = setup_socket(); + if (success) { + qDebug() << "Socket setup successful. Listening for data..."; + auto buffer = std::make_unique>(1500); // Enough for MTU 1500 bytes while (m_keep_receiving) { - struct sockaddr_in src_addr = {}; + struct sockaddr_in src_addr{}; socklen_t src_addr_len = sizeof(src_addr); + const auto recv_len = recvfrom( m_socket_fd, - (char*)buffer->data(), + reinterpret_cast(buffer->data()), buffer->size(), 0, reinterpret_cast(&src_addr), &src_addr_len); - //qDebug()<<"Gt data"; if (recv_len == 0) { - // This can happen when shutdown is called on the socket, - // therefore we check _should_exit again. + qDebug() << "Received zero-length packet. Ignoring."; continue; } if (recv_len < 0) { - // This happens on destruction when close(_socket_fd) is called, - // therefore be quiet. - // LogErr() << "recvfrom error: " << GET_ERROR(errno); + qDebug() << "Error: Data reception failed -" << strerror(errno); continue; } - const std::string remote_ip=inet_ntoa(src_addr.sin_addr); - const int remote_port=ntohs(src_addr.sin_port); - set_remote(remote_ip,remote_port); - m_last_data_ms=QOpenHDMavlinkHelper::getTimeMilliseconds(); - process_data(buffer->data(),recv_len); - } - } - // TODO close socket - // set the remote back to unknown - clear_remote(); -} -std::optional UDPConnection::get_current_remote() -{ - std::lock_guard lock(m_remote_nutex); - if(m_curr_remote.has_value()){ - return m_curr_remote.value(); - } - return std::nullopt; -} + std::string remote_ip = inet_ntoa(src_addr.sin_addr); + int remote_port = ntohs(src_addr.sin_port); + qDebug() << "Received data from IP:" << remote_ip.c_str() + << "Port:" << remote_port + << "Bytes:" << recv_len; -void UDPConnection::set_remote(const std::string ip, int port) -{ - std::lock_guard lock(m_remote_nutex); - if(m_curr_remote.has_value()){ - auto& remote=m_curr_remote.value(); - if(remote.ip!=ip || remote.port != port){ - auto new_remote=Remote{ip,port}; - qDebug()<<"Remote changed from "<data(), recv_len); } - }else{ - auto new_remote=Remote{ip,port}; - qDebug()<<"Got remote "< lock(m_remote_nutex); - m_curr_remote=std::nullopt; -} + clear_remote(); + qDebug() << "Connection closed and remote cleared."; +} \ No newline at end of file