Skip to content

Commit

Permalink
move the async function handler to the realtime_tools and integrate f…
Browse files Browse the repository at this point in the history
…rom it
  • Loading branch information
saikishor committed Jun 12, 2024
1 parent 56e3229 commit 4474281
Show file tree
Hide file tree
Showing 7 changed files with 8 additions and 551 deletions.
6 changes: 1 addition & 5 deletions controller_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ endif()
set(THIS_PACKAGE_INCLUDE_DEPENDS
hardware_interface
rclcpp_lifecycle
realtime_tools
)

find_package(ament_cmake REQUIRED)
Expand Down Expand Up @@ -74,11 +75,6 @@ if(BUILD_TESTING)
ament_target_dependencies(test_imu_sensor
sensor_msgs
)

ament_add_gmock(test_async_function_handler test/test_async_function_handler.cpp)
target_link_libraries(test_async_function_handler
controller_interface
)
endif()

install(
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@
#include <utility>
#include <vector>

#include "controller_interface/async_function_handler.hpp"
#include "controller_interface/visibility_control.h"
#include "realtime_tools/async_function_handler.hpp"

#include "hardware_interface/handle.hpp"
#include "hardware_interface/loaned_command_interface.hpp"
Expand Down Expand Up @@ -286,7 +286,7 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy

private:
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
std::unique_ptr<ros2_control::AsyncFunctionHandler<return_type>> async_handler_;
std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
};

using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
Expand Down
4 changes: 4 additions & 0 deletions controller_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,16 @@
<buildtool_depend>ament_cmake_gen_version_h</buildtool_depend>

<build_depend>hardware_interface</build_depend>
<build_depend>realtime_tools</build_depend>
<build_depend>rclcpp_lifecycle</build_depend>
<build_depend>sensor_msgs</build_depend>

<build_export_depend>hardware_interface</build_export_depend>
<build_export_depend>realtime_tools</build_export_depend>
<build_export_depend>rclcpp_lifecycle</build_export_depend>

<exec_depend>realtime_tools</exec_depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>sensor_msgs</test_depend>

Expand Down
2 changes: 1 addition & 1 deletion controller_interface/src/controller_interface_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ const rclcpp_lifecycle::State & ControllerInterfaceBase::configure()
}
if (is_async_)
{
async_handler_ = std::make_unique<ros2_control::AsyncFunctionHandler<return_type>>();
async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
async_handler_->init(
std::bind(&ControllerInterfaceBase::get_state, this),
std::bind(
Expand Down
Loading

0 comments on commit 4474281

Please sign in to comment.