Skip to content

Commit

Permalink
Fixed issues due to merge with master
Browse files Browse the repository at this point in the history
  • Loading branch information
Lennart Nachtigall committed Jan 23, 2024
1 parent 63c51a7 commit eaedafe
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 4 deletions.
3 changes: 3 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,9 @@ if(BUILD_TESTING)
ament_add_gmock(realtime_box_tests test/realtime_box_tests.cpp)
target_link_libraries(realtime_box_tests realtime_tools)

ament_add_gmock(realtime_box_best_effort_tests test/realtime_box_best_effort_tests.cpp)
target_link_libraries(realtime_box_best_effort_tests realtime_tools)

ament_add_gmock(realtime_buffer_tests test/realtime_buffer_tests.cpp)
target_link_libraries(realtime_buffer_tests realtime_tools)

Expand Down
6 changes: 3 additions & 3 deletions include/realtime_tools/realtime_box_best_effort.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,11 +41,11 @@ template <typename T>
constexpr auto is_ptr_or_smart_ptr = rcpputils::is_pointer<T>::value;

/*!
A Box that ensures thread safe access to the boxed contents.
A Box that ensures thread safe access to the boxed contents.
Access is best effort. If it can not lock it will return.
NOTE about pointers:
You can use pointers with this box but the access will be different.
You can use pointers with this box but the access will be different.
Only use the get/set methods that take function pointer for accessing the internal value.
*/
template <class T, typename mutex_type = std::mutex>
Expand Down Expand Up @@ -115,7 +115,7 @@ class RealtimeBoxBestEffort
return value_;
}
/**
* @brief access the content (r) with best effort
* @brief access the content (r) with best effort
* @return false if the mutex could not be locked
* @note only safe way to access pointer type content (r)
*/
Expand Down
2 changes: 1 addition & 1 deletion test/realtime_box_best_effort_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ TEST(RealtimeBoxBestEffort, assignment_operator)
DefaultConstructable data;
data.a = 1000;
RealtimeBoxBestEffort<DefaultConstructable> box;
//Assignement operator is always non RT!
//Assignment operator is always non RT!
box = data;

auto value = box.get();
Expand Down

0 comments on commit eaedafe

Please sign in to comment.