Skip to content

Commit e4b7fbc

Browse files
Fixup hardware-interface patch
1 parent 4d629ee commit e4b7fbc

File tree

1 file changed

+33
-7
lines changed

1 file changed

+33
-7
lines changed
Lines changed: 33 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
diff --git a/CMakeLists.txt b/CMakeLists.txt
2-
index 385ae96fb..e4883ff18 100644
2+
index b4e0f6cab..896175fad 100644
33
--- a/CMakeLists.txt
44
+++ b/CMakeLists.txt
55
@@ -1,11 +1,6 @@
@@ -11,14 +11,40 @@ index 385ae96fb..e4883ff18 100644
1111
- -Werror=missing-braces)
1212
-endif()
1313
-
14-
set(THIS_PACKAGE_INCLUDE_DEPENDS
15-
control_msgs
16-
lifecycle_msgs
17-
@@ -51,6 +46,7 @@ target_include_directories(mock_components PUBLIC
14+
# using this instead of visibility macros
15+
# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053
16+
set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)
17+
@@ -54,6 +49,7 @@ target_include_directories(mock_components PUBLIC
1818
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
1919
$<INSTALL_INTERFACE:include/hardware_interface>
2020
)
2121
+target_link_libraries(mock_components PUBLIC hardware_interface)
2222
ament_target_dependencies(mock_components PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})
23-
# Causes the visibility macros to use dllexport rather than dllimport,
24-
# which is appropriate when building the dll but not consuming it.
23+
24+
pluginlib_export_plugin_description_file(
25+
diff --git a/include/hardware_interface/async_components.hpp b/include/hardware_interface/async_components.hpp
26+
index 052c4ba92..85efed01f 100644
27+
--- a/include/hardware_interface/async_components.hpp
28+
+++ b/include/hardware_interface/async_components.hpp
29+
@@ -82,7 +82,11 @@ public:
30+
{
31+
auto const period = std::chrono::nanoseconds(1'000'000'000 / cm_update_rate_);
32+
TimePoint next_iteration_time =
33+
- TimePoint(std::chrono::nanoseconds(clock_interface_->get_clock()->now().nanoseconds()));
34+
+ TimePoint(std::chrono::system_clock::time_point(
35+
+ std::chrono::duration_cast<std::chrono::system_clock::duration>(
36+
+ std::chrono::nanoseconds(clock_interface_->get_clock()->now().nanoseconds())
37+
+ )
38+
+ ));
39+
40+
if (
41+
component->get_lifecycle_state().id() ==
42+
@@ -99,7 +103,7 @@ public:
43+
component->read(clock_interface_->get_clock()->now(), measured_period);
44+
first_iteration = false;
45+
}
46+
- next_iteration_time += period;
47+
+ next_iteration_time += std::chrono::duration_cast<decltype(next_iteration_time)::duration>(period);
48+
std::this_thread::sleep_until(next_iteration_time);
49+
}
50+
},

0 commit comments

Comments
 (0)