Skip to content

Commit

Permalink
Move to single rw_rate variable instead of read and write separate rates
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Dec 4, 2024
1 parent 98aeea8 commit ef64595
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 35 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -48,11 +48,8 @@ struct HardwareComponentInfo
/// Component is async
bool is_async;

//// read rate
unsigned int read_rate;

//// write rate
unsigned int write_rate;
//// read/write rate
unsigned int rw_rate;

/// Component current state.
rclcpp_lifecycle::State state;
Expand Down
18 changes: 7 additions & 11 deletions hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,11 +142,7 @@ class ResourceStorage
component_info.name = hardware_info.name;
component_info.type = hardware_info.type;
component_info.group = hardware_info.group;
component_info.read_rate =
(hardware_info.rw_rate == 0 || hardware_info.rw_rate > cm_update_rate_)
? cm_update_rate_
: hardware_info.rw_rate;
component_info.write_rate =
component_info.rw_rate =
(hardware_info.rw_rate == 0 || hardware_info.rw_rate > cm_update_rate_)
? cm_update_rate_
: hardware_info.rw_rate;
Expand Down Expand Up @@ -1856,16 +1852,16 @@ HardwareReadWriteStatus ResourceManager::read(
try
{
if (
resource_storage_->hardware_info_map_[component.get_name()].read_rate == 0 ||
resource_storage_->hardware_info_map_[component.get_name()].read_rate ==
resource_storage_->hardware_info_map_[component.get_name()].rw_rate == 0 ||
resource_storage_->hardware_info_map_[component.get_name()].rw_rate ==
resource_storage_->cm_update_rate_)
{
ret_val = component.read(time, period);
}
else
{
const double read_rate =
resource_storage_->hardware_info_map_[component.get_name()].read_rate;
resource_storage_->hardware_info_map_[component.get_name()].rw_rate;
const auto current_time = resource_storage_->get_clock()->now();
const rclcpp::Duration actual_period = current_time - component.get_last_read_time();
if (actual_period.seconds() * read_rate >= 0.99)
Expand Down Expand Up @@ -1942,16 +1938,16 @@ HardwareReadWriteStatus ResourceManager::write(
try
{
if (
resource_storage_->hardware_info_map_[component.get_name()].write_rate == 0 ||
resource_storage_->hardware_info_map_[component.get_name()].write_rate ==
resource_storage_->hardware_info_map_[component.get_name()].rw_rate == 0 ||
resource_storage_->hardware_info_map_[component.get_name()].rw_rate ==
resource_storage_->cm_update_rate_)
{
ret_val = component.write(time, period);
}
else
{
const double write_rate =
resource_storage_->hardware_info_map_[component.get_name()].write_rate;
resource_storage_->hardware_info_map_[component.get_name()].rw_rate;
const auto current_time = resource_storage_->get_clock()->now();
const rclcpp::Duration actual_period = current_time - component.get_last_write_time();
if (actual_period.seconds() * write_rate >= 0.99)
Expand Down
30 changes: 11 additions & 19 deletions hardware_interface_testing/test/test_resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -457,14 +457,10 @@ TEST_F(ResourceManagerTest, resource_status)
EXPECT_EQ(status_map[TEST_ACTUATOR_HARDWARE_NAME].type, TEST_ACTUATOR_HARDWARE_TYPE);
EXPECT_EQ(status_map[TEST_SENSOR_HARDWARE_NAME].type, TEST_SENSOR_HARDWARE_TYPE);
EXPECT_EQ(status_map[TEST_SYSTEM_HARDWARE_NAME].type, TEST_SYSTEM_HARDWARE_TYPE);
// read_rate
EXPECT_EQ(status_map[TEST_ACTUATOR_HARDWARE_NAME].read_rate, 50u);
EXPECT_EQ(status_map[TEST_SENSOR_HARDWARE_NAME].read_rate, 20u);
EXPECT_EQ(status_map[TEST_SYSTEM_HARDWARE_NAME].read_rate, 25u);
// write_rate
EXPECT_EQ(status_map[TEST_ACTUATOR_HARDWARE_NAME].write_rate, 50u);
EXPECT_EQ(status_map[TEST_SENSOR_HARDWARE_NAME].write_rate, 20u);
EXPECT_EQ(status_map[TEST_SYSTEM_HARDWARE_NAME].write_rate, 25u);
// read/write_rate
EXPECT_EQ(status_map[TEST_ACTUATOR_HARDWARE_NAME].rw_rate, 50u);
EXPECT_EQ(status_map[TEST_SENSOR_HARDWARE_NAME].rw_rate, 20u);
EXPECT_EQ(status_map[TEST_SYSTEM_HARDWARE_NAME].rw_rate, 25u);
// plugin_name
EXPECT_EQ(
status_map[TEST_ACTUATOR_HARDWARE_NAME].plugin_name, TEST_ACTUATOR_HARDWARE_PLUGIN_NAME);
Expand Down Expand Up @@ -1765,17 +1761,13 @@ class ResourceManagerTestReadWriteDifferentReadWriteRate : public ResourceManage
status_map[TEST_SENSOR_HARDWARE_NAME].state.id(),
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);

// read_rate
EXPECT_EQ(status_map[TEST_ACTUATOR_HARDWARE_NAME].read_rate, 50u);
EXPECT_EQ(status_map[TEST_SENSOR_HARDWARE_NAME].read_rate, 20u);
EXPECT_EQ(status_map[TEST_SYSTEM_HARDWARE_NAME].read_rate, 25u);
// write_rate
EXPECT_EQ(status_map[TEST_ACTUATOR_HARDWARE_NAME].write_rate, 50u);
EXPECT_EQ(status_map[TEST_SENSOR_HARDWARE_NAME].write_rate, 20u);
EXPECT_EQ(status_map[TEST_SYSTEM_HARDWARE_NAME].write_rate, 25u);

actuator_rw_rate_ = status_map[TEST_ACTUATOR_HARDWARE_NAME].read_rate;
system_rw_rate_ = status_map[TEST_SYSTEM_HARDWARE_NAME].read_rate;
// read/write_rate
EXPECT_EQ(status_map[TEST_ACTUATOR_HARDWARE_NAME].rw_rate, 50u);
EXPECT_EQ(status_map[TEST_SENSOR_HARDWARE_NAME].rw_rate, 20u);
EXPECT_EQ(status_map[TEST_SYSTEM_HARDWARE_NAME].rw_rate, 25u);

actuator_rw_rate_ = status_map[TEST_ACTUATOR_HARDWARE_NAME].rw_rate;
system_rw_rate_ = status_map[TEST_SYSTEM_HARDWARE_NAME].rw_rate;

claimed_itfs.push_back(
rm->claim_command_interface(TEST_ACTUATOR_HARDWARE_COMMAND_INTERFACES[0]));
Expand Down

0 comments on commit ef64595

Please sign in to comment.