From 2b02759d5677da034c35705b9e24c4dfb3b4a497 Mon Sep 17 00:00:00 2001 From: Emerson Knapp Date: Wed, 6 May 2026 15:41:22 -0700 Subject: [PATCH 1/3] Update Rolling CI to Resolute --- .github/workflows/build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 17aa5af..c208aae 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -21,7 +21,7 @@ jobs: - ros: kilted ubuntu: noble - ros: rolling - ubuntu: noble + ubuntu: resolute name: ROS 2 ${{ matrix.ros }} container: image: ghcr.io/ros-tooling/setup-ros-docker/setup-ros-docker-ubuntu-${{ matrix.ubuntu }}:latest From 2c0453b3c4108c2e0f758c01affa674a9e3ed622 Mon Sep 17 00:00:00 2001 From: Emerson Knapp Date: Wed, 6 May 2026 16:16:46 -0700 Subject: [PATCH 2/3] Fix cmake deprecation danger, scope down boost dependency to system, which is all we use --- axiomatic_adapter/CMakeLists.txt | 2 +- axiomatic_adapter/package.xml | 2 +- socketcan_adapter/CMakeLists.txt | 2 +- socketcan_adapter_ros/CMakeLists.txt | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/axiomatic_adapter/CMakeLists.txt b/axiomatic_adapter/CMakeLists.txt index fe6b375..7f651e7 100644 --- a/axiomatic_adapter/CMakeLists.txt +++ b/axiomatic_adapter/CMakeLists.txt @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -cmake_minimum_required(VERSION 3.8) +cmake_minimum_required(VERSION 3.22) project(axiomatic_adapter) if(NOT CMAKE_CXX_STANDARD) diff --git a/axiomatic_adapter/package.xml b/axiomatic_adapter/package.xml index fb3278e..6b30b89 100644 --- a/axiomatic_adapter/package.xml +++ b/axiomatic_adapter/package.xml @@ -10,8 +10,8 @@ ament_cmake_ros - boost cli11 + libboost-system-dev socketcan_adapter catch2 diff --git a/socketcan_adapter/CMakeLists.txt b/socketcan_adapter/CMakeLists.txt index 674c2fd..c0dc200 100644 --- a/socketcan_adapter/CMakeLists.txt +++ b/socketcan_adapter/CMakeLists.txt @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -cmake_minimum_required(VERSION 3.8) +cmake_minimum_required(VERSION 3.22) project(socketcan_adapter) # Project-wide language standards diff --git a/socketcan_adapter_ros/CMakeLists.txt b/socketcan_adapter_ros/CMakeLists.txt index c5fdd8d..58661ee 100644 --- a/socketcan_adapter_ros/CMakeLists.txt +++ b/socketcan_adapter_ros/CMakeLists.txt @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -cmake_minimum_required(VERSION 3.8) +cmake_minimum_required(VERSION 3.22) project(socketcan_adapter_ros) # Project-wide language standards From 76b7e12a953e153657148e0cd56fdd930cbdeb07 Mon Sep 17 00:00:00 2001 From: Emerson Knapp Date: Wed, 6 May 2026 21:33:42 -0700 Subject: [PATCH 3/3] Switch over to std::error_code --- axiomatic_adapter/src/axiomatic_adapter.cpp | 38 ++++++++++----------- 1 file changed, 18 insertions(+), 20 deletions(-) diff --git a/axiomatic_adapter/src/axiomatic_adapter.cpp b/axiomatic_adapter/src/axiomatic_adapter.cpp index 8fb1491..1ba4beb 100644 --- a/axiomatic_adapter/src/axiomatic_adapter.cpp +++ b/axiomatic_adapter/src/axiomatic_adapter.cpp @@ -23,13 +23,13 @@ #include #include #include +#include #include #include #include #include #include -#include namespace polymath { @@ -69,12 +69,12 @@ class AxiomaticAdapter::AxiomaticAdapterImpl boost::asio::steady_timer timer(tcp_io_context_); timer.expires_after(TCP_IP_CONNECTION_TIMEOUT_MS); - TCPSocketConnectionState connection_state{false, boost::asio::error::would_block}; + TCPSocketConnectionState connection_state{false, std::make_error_code(std::errc::operation_would_block)}; std::mutex connection_state_mutex; // Asynchronously attempt to connect boost::asio::async_connect( - tcp_socket_, endpoints, [&](const boost::system::error_code & error, const boost::asio::ip::tcp::endpoint &) { + tcp_socket_, endpoints, [&](const std::error_code & error, const boost::asio::ip::tcp::endpoint &) { std::lock_guard guard(connection_state_mutex); connection_state.error_code = error; connection_state.connected = !error; @@ -83,11 +83,11 @@ class AxiomaticAdapter::AxiomaticAdapterImpl }); // Set up a timer to cancel the operation if it exceeds the timeout - timer.async_wait([&](const boost::system::error_code & error) { + timer.async_wait([&](const std::error_code & error) { if (!error) { std::lock_guard guard(connection_state_mutex); if (!connection_state.connected) { - connection_state.error_code = boost::asio::error::timed_out; + connection_state.error_code = std::make_error_code(std::errc::timed_out); tcp_socket_.cancel(); } } @@ -98,7 +98,7 @@ class AxiomaticAdapter::AxiomaticAdapterImpl tcp_io_context_.run(); // capture the error message and connection state - boost::system::error_code captured_error; + std::error_code captured_error; bool is_connected; { std::lock_guard guard(connection_state_mutex); @@ -124,16 +124,14 @@ class AxiomaticAdapter::AxiomaticAdapterImpl bool closeSocket() { if (socket_state_ != TCPSocketState::CLOSED) { - boost::system::error_code error_code; - tcp_socket_.close(error_code); - - if (error_code) { - std::cerr << "[ERROR] Failed to close TCP socket: " << error_code.message() << std::endl; + try { + tcp_socket_.close(); + } catch (const std::exception & e) { + std::cerr << "[ERROR] Failed to close TCP socket: " << e.what() << std::endl; return false; - } else { - socket_state_ = TCPSocketState::CLOSED; - return true; } + socket_state_ = TCPSocketState::CLOSED; + return true; } return true; } @@ -184,7 +182,7 @@ class AxiomaticAdapter::AxiomaticAdapterImpl { std::vector data(1024, 0); std::atomic data_received(false); - boost::system::error_code error_code; + std::error_code error_code; // Set up the timer for timeout boost::asio::steady_timer timer(tcp_io_context_); @@ -192,7 +190,7 @@ class AxiomaticAdapter::AxiomaticAdapterImpl // Start async receive operation tcp_socket_.async_receive( - boost::asio::buffer(data), [&](const boost::system::error_code & error, std::size_t bytes_transferred) { + boost::asio::buffer(data), [&](const std::error_code & error, std::size_t bytes_transferred) { error_code = error; if (!error) { data.resize(bytes_transferred); @@ -202,9 +200,9 @@ class AxiomaticAdapter::AxiomaticAdapterImpl }); // Set up the timer to handle timeout cancellation - timer.async_wait([&](const boost::system::error_code & error) { + timer.async_wait([&](const std::error_code & error) { if (!error && !data_received.load()) { - error_code = boost::asio::error::timed_out; + error_code = std::make_error_code(std::errc::timed_out); // Cancel the ongoing async receive operation on timeout (does not close socket) tcp_socket_.cancel(); } @@ -215,7 +213,7 @@ class AxiomaticAdapter::AxiomaticAdapterImpl tcp_io_context_.run(); // Check for timeout or other errors - if (error_code == boost::asio::error::timed_out) { + if (error_code == std::errc::timed_out) { return std::optional("Receive operation timed out"); } else if (error_code) { return std::optional( @@ -353,7 +351,7 @@ class AxiomaticAdapter::AxiomaticAdapterImpl struct TCPSocketConnectionState { bool connected{false}; - boost::system::error_code error_code{boost::asio::error::would_block}; + std::error_code error_code{std::make_error_code(std::errc::operation_would_block)}; }; boost::asio::io_context tcp_io_context_;