Skip to content

Commit

Permalink
remove get_state function and focus on the trigger_predicate_ which d…
Browse files Browse the repository at this point in the history
…oes the same
  • Loading branch information
saikishor committed Jun 13, 2024
1 parent ecf4610 commit 9695ad6
Show file tree
Hide file tree
Showing 5 changed files with 23 additions and 32 deletions.
10 changes: 4 additions & 6 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
rclcpp_action
Threads
rcpputils
lifecycle_msgs
rclcpp_lifecycle
)

find_package(ament_cmake REQUIRED)
Expand Down Expand Up @@ -43,6 +41,8 @@ ament_target_dependencies(thread_priority PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}
# Unit Tests
if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(lifecycle_msgs REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(test_msgs REQUIRED)

ament_add_gmock(realtime_box_tests test/realtime_box_tests.cpp)
Expand Down Expand Up @@ -76,10 +76,8 @@ if(BUILD_TESTING)
ament_target_dependencies(realtime_server_goal_handle_tests test_msgs)

ament_add_gmock(test_async_function_handler test/test_async_function_handler.cpp)
target_link_libraries(test_async_function_handler
realtime_tools
thread_priority
)
target_link_libraries(test_async_function_handler realtime_tools thread_priority)
ament_target_dependencies(test_async_function_handler lifecycle_msgs rclcpp_lifecycle)
endif()

# Install
Expand Down
38 changes: 15 additions & 23 deletions include/realtime_tools/async_function_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,19 +29,17 @@
#include <utility>
#include <vector>

#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/duration.hpp"
#include "rclcpp/logging.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/thread_priority.hpp"

namespace realtime_tools
{
/**
* @brief Class to handle asynchronous function calls.
* AsyncFunctionHandler is a class that allows the user to have a ascynchronous call to the parsed
* method, when the lifecycyle state is in the ACTIVE state
* AsyncFunctionHandler is a class that allows the user to have a asynchronous call to the parsed
* method and be able to set some thread specific parameters
*/
template <typename T>
class AsyncFunctionHandler
Expand All @@ -51,23 +49,17 @@ class AsyncFunctionHandler

~AsyncFunctionHandler() { stop_async_update(); }

/// Initialize the AsyncFunctionHandler with the get_state_function and async_function
/// Initialize the AsyncFunctionHandler with the async_function and thread_priority
/**
* @param get_state_function Function that returns the current lifecycle state
* @param async_function Function that will be called asynchronously
* If the AsyncFunctionHandler is already initialized and is running, it will throw a runtime
* error.
* If the parsed functions are not valid, it will throw a runtime error.
*/
void init(
std::function<const rclcpp_lifecycle::State &()> get_state_function,
std::function<T(const rclcpp::Time &, const rclcpp::Duration &)> async_function,
int thread_priority = 50)
{
if (get_state_function == nullptr) {
throw std::runtime_error(
"AsyncFunctionHandler: parsed function to get the lifecycle state is not valid!");
}
if (async_function == nullptr) {
throw std::runtime_error(
"AsyncFunctionHandler: parsed function to call asynchronously is not valid!");
Expand All @@ -77,28 +69,31 @@ class AsyncFunctionHandler
"AsyncFunctionHandler: Cannot reinitialize while the thread is "
"running. Please stop the async update first!");
}
get_state_function_ = get_state_function;
async_function_ = async_function;
thread_priority_ = thread_priority;
}

/// Initialize the AsyncFunctionHandler with the get_state_function, async_function and
/// trigger_predicate
/// Initialize the AsyncFunctionHandler with the async_function and trigger_predicate
/**
* @param get_state_function Function that returns the current lifecycle state
* @param async_function Function that will be called asynchronously
* @param trigger_predicate Predicate function that will be called to check if the async update
* method should be triggered
* method should be triggered.
*
* \note The parsed trigger_predicate should be free from any concurrency issues. It is expected
* to be both thread-safe and reentrant.
*
* If the AsyncFunctionHandler is already initialized and is running, it will throw a runtime
* error.
* If the parsed functions are not valid, it will throw a runtime error.
*/
void init(
std::function<const rclcpp_lifecycle::State &()> get_state_function,
std::function<T(const rclcpp::Time &, const rclcpp::Duration &)> async_function,
std::function<bool()> trigger_predicate, int thread_priority = 50)
{
init(get_state_function, async_function, thread_priority);
if (trigger_predicate == nullptr) {
throw std::runtime_error("AsyncFunctionHandler: parsed trigger predicate is not valid!");
}
init(async_function, thread_priority);
trigger_predicate_ = trigger_predicate;
}

Expand Down Expand Up @@ -160,7 +155,7 @@ class AsyncFunctionHandler
/**
* @return True if the AsyncFunctionHandler is initialized, false otherwise
*/
bool is_initialized() const { return get_state_function_ && async_function_; }
bool is_initialized() const { return async_function_ && trigger_predicate_; }

/// Join the async update thread
/**
Expand Down Expand Up @@ -228,9 +223,7 @@ class AsyncFunctionHandler
"[https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html] "
"for details.");
}
// \note There might be an concurrency issue with the get_state() call here. This mightn't
// be critical here as the state of the controller is not expected to change during the
// update cycle

while (!async_update_stop_.load(std::memory_order_relaxed)) {
{
std::unique_lock<std::mutex> lock(async_mtx_);
Expand All @@ -251,7 +244,6 @@ class AsyncFunctionHandler
rclcpp::Time current_update_time_;
rclcpp::Duration current_update_period_{0, 0};

std::function<const rclcpp_lifecycle::State &()> get_state_function_;
std::function<T(const rclcpp::Time &, const rclcpp::Duration &)> async_function_;
std::function<bool()> trigger_predicate_ = []() { return true; };

Expand Down
4 changes: 2 additions & 2 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,11 @@
<buildtool_export_depend>ament_cmake</buildtool_export_depend>

<depend>rclcpp</depend>
<depend>lifecycle_msgs</depend>
<depend>rclcpp_lifecycle</depend>
<depend>rclcpp_action</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>lifecycle_msgs</test_depend>
<test_depend>rclcpp_lifecycle</test_depend>
<test_depend>test_msgs</test_depend>

<export>
Expand Down
1 change: 0 additions & 1 deletion test/test_async_function_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@ TestAsyncFunctionHandler::TestAsyncFunctionHandler()
void TestAsyncFunctionHandler::initialize()
{
handler_.init(
std::bind(&TestAsyncFunctionHandler::get_state, this),
std::bind(
&TestAsyncFunctionHandler::update, this, std::placeholders::_1, std::placeholders::_2),
[this]() { return state_.id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE; });
Expand Down
2 changes: 2 additions & 0 deletions test/test_async_function_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include <utility>

#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/async_function_handler.hpp"

namespace realtime_tools
Expand Down

0 comments on commit 9695ad6

Please sign in to comment.