Skip to content

Commit ca62a0b

Browse files
committed
Parse the actual period to the read and write methods
1 parent 23fde82 commit ca62a0b

File tree

1 file changed

+10
-4
lines changed

1 file changed

+10
-4
lines changed

hardware_interface/src/resource_manager.cpp

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1801,9 +1801,12 @@ HardwareReadWriteStatus ResourceManager::read(
18011801
1.0 / resource_storage_->hardware_info_map_[component.get_name()].read_rate);
18021802
if (
18031803
component.get_last_read_time().seconds() == 0 ||
1804-
(time - component.get_last_read_time()).seconds() >= hw_read_period.seconds())
1804+
(time - component.get_last_read_time()) >= hw_read_period)
18051805
{
1806-
ret_val = component.read(time, hw_read_period);
1806+
const rclcpp::Duration actual_period = component.get_last_read_time().seconds() == 0
1807+
? hw_read_period
1808+
: time - component.get_last_read_time();
1809+
ret_val = component.read(time, actual_period);
18071810
}
18081811
}
18091812
const auto component_group = component.get_group_name();
@@ -1878,9 +1881,12 @@ HardwareReadWriteStatus ResourceManager::write(
18781881
1.0 / resource_storage_->hardware_info_map_[component.get_name()].write_rate);
18791882
if (
18801883
component.get_last_write_time().seconds() == 0 ||
1881-
(time - component.get_last_write_time()).seconds() >= hw_write_period.seconds())
1884+
(time - component.get_last_write_time()) >= hw_write_period)
18821885
{
1883-
ret_val = component.write(time, hw_write_period);
1886+
const rclcpp::Duration actual_period = component.get_last_write_time().seconds() == 0
1887+
? hw_write_period
1888+
: time - component.get_last_read_time();
1889+
ret_val = component.write(time, actual_period);
18841890
}
18851891
}
18861892
const auto component_group = component.get_group_name();

0 commit comments

Comments
 (0)