Skip to content

Commit 443d5af

Browse files
authored
Bring Over Changes from Core Repos (#2)
* Adding additional send function * Bring over change for std::future based join reception thread
1 parent cbeccd6 commit 443d5af

File tree

2 files changed

+18
-12
lines changed

2 files changed

+18
-12
lines changed

include/socketcan_adapter/socketcan_adapter.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -156,6 +156,11 @@ class SocketcanAdapter : public std::enable_shared_from_this<SocketcanAdapter>
156156
/// @return optional error string filled with an error message if any
157157
std::optional<socket_error_string_t> send(const std::shared_ptr<const CanFrame> frame);
158158

159+
/// @brief Transmit a can frame via socket
160+
/// @param frame Linux CAN frame to send
161+
/// @return optional error string filled with an error message if any
162+
std::optional<socket_error_string_t> send(const can_frame & frame);
163+
159164
/// @brief Set receive timeout
160165
/// @param reecive_timeout_s std::chrono::duration<float> sets receive timeout in seconds
161166
void set_receive_timeout(const std::chrono::duration<float> & recive_timeout_s);

src/socketcan_adapter.cpp

Lines changed: 13 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525

2626
#include <cerrno>
2727
#include <cstring>
28+
#include <future>
2829
#include <memory>
2930
#include <optional>
3031
#include <string>
@@ -226,6 +227,11 @@ std::optional<SocketcanAdapter::socket_error_string_t> SocketcanAdapter::send(
226227
: std::nullopt;
227228
}
228229

230+
std::optional<SocketcanAdapter::socket_error_string_t> SocketcanAdapter::send(const can_frame & frame)
231+
{
232+
return send(polymath::socketcan::CanFrame(frame));
233+
}
234+
229235
std::optional<SocketcanAdapter::socket_error_string_t> SocketcanAdapter::sendFilters()
230236
{
231237
socket_error_string_t error_output("");
@@ -326,20 +332,15 @@ bool SocketcanAdapter::joinReceptionThread(const std::chrono::duration<float> &
326332
{
327333
stop_thread_requested_ = true;
328334

329-
auto start_time = std::chrono::steady_clock::now();
330-
// Check thread running to tell when to join the thread
331-
while (thread_running_ && ((std::chrono::steady_clock::now() - start_time) < timeout_s)) {
332-
std::this_thread::sleep_for(std::chrono::milliseconds(100));
333-
}
334-
335-
// Attempt to force joining at this point
336-
337335
if (can_receive_thread_.joinable()) {
338-
can_receive_thread_.join();
339-
return true;
340-
} else {
341-
return false;
336+
// Use std::async to wait asynchronously for the thread to stop
337+
std::future<void> join_future = std::async(std::launch::async, [this] { can_receive_thread_.join(); });
338+
339+
// Wait for the thread to stop within the timeout period
340+
return join_future.wait_for(timeout_s) == std::future_status::ready;
342341
}
342+
343+
return false;
343344
}
344345

345346
std::string SocketcanAdapter::get_interface()

0 commit comments

Comments
 (0)