-
Notifications
You must be signed in to change notification settings - Fork 386
[HardwareComponentInterface] Add get state and command interface handle methods #2831
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: master
Are you sure you want to change the base?
Changes from 4 commits
3472e37
f3d110c
06272cf
a1c3480
1310cbb
85d03d5
4ed7464
a7cfdaa
8e3fe4e
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -246,6 +246,82 @@ class Handle | |
| // END | ||
| } | ||
|
|
||
| /** | ||
| * @brief Get the value of the handle. | ||
| * @tparam T The type of the value to be retrieved. | ||
| * @param lock The lock to access the value. | ||
| * @param value The variable to store the retrieved value. | ||
| * @return true if the value is retrieved successfully, false otherwise. | ||
| * @note The method is thread-safe and non-blocking. | ||
| * @note Ideal for the data types that are large in size to avoid copy during return. | ||
| */ | ||
| template <typename T> | ||
| [[nodiscard]] bool get_value(std::shared_lock<std::shared_mutex> & lock, T & value) const | ||
| { | ||
| if (!lock.owns_lock()) | ||
| { | ||
| return false; | ||
| } | ||
| // BEGIN (Handle export change): for backward compatibility | ||
| // TODO(saikishor) get value_ if old functionality is removed | ||
| if constexpr (std::is_same_v<T, double>) | ||
| { | ||
| switch (data_type_) | ||
| { | ||
| case HandleDataType::DOUBLE: | ||
| THROW_ON_NULLPTR(value_ptr_); | ||
| value = *value_ptr_; | ||
| return true; | ||
| case HandleDataType::BOOL: | ||
| // TODO(christophfroehlich): replace with RCLCPP_WARN_ONCE once | ||
| // https://github.com/ros2/rclcpp/issues/2587 | ||
| // is fixed | ||
| if (!notified_) | ||
| { | ||
| RCLCPP_WARN( | ||
| rclcpp::get_logger(get_name()), | ||
| "Casting bool to double for interface: %s. Better use get_optional<bool>().", | ||
| get_name().c_str()); | ||
| notified_ = true; | ||
| } | ||
| value = static_cast<double>(std::get<bool>(value_)); | ||
| return true; | ||
| default: | ||
| throw std::runtime_error( | ||
| fmt::format( | ||
| FMT_COMPILE("Data type: '{}' cannot be casted to double for interface: {}"), | ||
| data_type_.to_string(), get_name())); | ||
| } | ||
| } | ||
| try | ||
| { | ||
| value = std::get<T>(value_); | ||
| return true; | ||
| } | ||
| catch (const std::bad_variant_access & err) | ||
| { | ||
| throw std::runtime_error( | ||
| fmt::format( | ||
| FMT_COMPILE("Invalid data type: '{}' access for interface: {} expected: '{}'"), | ||
| get_type_name<T>(), get_name(), data_type_.to_string())); | ||
| } | ||
| } | ||
|
|
||
| /** | ||
| * @brief Get the value of the handle. | ||
| * @tparam T The type of the value to be retrieved. | ||
| * @param value The variable to store the retrieved value. | ||
| * @return true if the value is retrieved successfully, false otherwise. | ||
| * @note The method is thread-safe and non-blocking. | ||
|
||
| * @note Ideal for the data types that are large in size to avoid copy during return. | ||
| */ | ||
| template <typename T> | ||
| [[nodiscard]] bool get_value(T & value) const | ||
| { | ||
| std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock); | ||
| return get_value(lock, value); | ||
| } | ||
|
|
||
| /** | ||
| * @brief Set the value of the handle. | ||
| * @tparam T The type of the value to be set. | ||
|
|
||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
The documentation states the method is 'non-blocking', but the method uses
std::shared_lockwhich can block if a writer holds the mutex. Consider clarifying this as 'non-blocking only if the lock is successfully acquired' or removing the non-blocking claim.There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Why do we expose this method in the interface? I would make it protected. The Handle should be a thread save entity in my point of view and locking/unlocking should be handled internally. I think exposing of
bool get_value(T & value) constshould be enough or am i missing something?And am i mistaken or is the function actually thradunsafe because if you create
mutex_2lock it with somestd::shared_lock<std::shared_mutex> lock2(handle_mutex_, std::try_to_lock);and pass it i would break thread safety or not?There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Why not, this is useful to avoid the copies and then you want to do it in a thread safe approach right?. Moreover, it has similar schema as
set_valuemethodIf you do that and if it doesn't own the lock, it would enter the condition
!lock.owns_lock()immediately and then returns