Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Propagate read/write rate to the HardwareInfo properly #1928

Open
wants to merge 8 commits into
base: master
Choose a base branch
from
13 changes: 8 additions & 5 deletions hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,10 +142,7 @@ class ResourceStorage
component_info.name = hardware_info.name;
component_info.type = hardware_info.type;
component_info.group = hardware_info.group;
component_info.rw_rate =
(hardware_info.rw_rate == 0 || hardware_info.rw_rate > cm_update_rate_)
? cm_update_rate_
: hardware_info.rw_rate;
component_info.rw_rate = hardware_info.rw_rate;
component_info.plugin_name = hardware_info.hardware_plugin_name;
component_info.is_async = hardware_info.is_async;

Expand Down Expand Up @@ -1127,7 +1124,13 @@ bool ResourceManager::load_and_initialize_components(

resource_storage_->cm_update_rate_ = update_rate;

const auto hardware_info = hardware_interface::parse_control_resources_from_urdf(urdf);
auto hardware_info = hardware_interface::parse_control_resources_from_urdf(urdf);
// Set the update rate for all hardware components
for (auto & hw_rate : hardware_info)
{
hw_rate.rw_rate =
(hw_rate.rw_rate == 0 || hw_rate.rw_rate > update_rate) ? update_rate : hw_rate.rw_rate;
}
saikishor marked this conversation as resolved.
Show resolved Hide resolved

const std::string system_type = "system";
const std::string sensor_type = "sensor";
Expand Down
Loading