Skip to content

Commit c292555

Browse files
committed
Add import_joint_limiters method to also work for Gazebo and other simulators
1 parent 55e7995 commit c292555

File tree

3 files changed

+14
-1
lines changed

3 files changed

+14
-1
lines changed

controller_manager/src/controller_manager.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -289,6 +289,7 @@ void ControllerManager::init_controller_manager()
289289
// Get parameters needed for RT "update" loop to work
290290
if (is_resource_manager_initialized())
291291
{
292+
resource_manager_->import_joint_limiters(robot_description_);
292293
init_services();
293294
}
294295
else
@@ -370,6 +371,7 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String &
370371
get_logger(),
371372
"Resource Manager has been successfully initialized. Starting Controller Manager "
372373
"services...");
374+
resource_manager_->import_joint_limiters(robot_description_);
373375
init_services();
374376
}
375377
}

hardware_interface/include/hardware_interface/resource_manager.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -89,6 +89,12 @@ class ResourceManager
8989
virtual bool load_and_initialize_components(
9090
const std::string & urdf, const unsigned int update_rate = 100);
9191

92+
/**
93+
* @brief Import joint limiters from the URDF.
94+
* @param urdf string containing the URDF.
95+
*/
96+
void import_joint_limiters(const std::string & urdf);
97+
9298
/**
9399
* @brief if the resource manager load_and_initialize_components(...) function has been called
94100
* this returns true. We want to permit to loading the urdf later on, but we currently don't want

hardware_interface/src/resource_manager.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1160,7 +1160,6 @@ bool ResourceManager::load_and_initialize_components(
11601160
resource_storage_->cm_update_rate_ = update_rate;
11611161

11621162
auto hardware_info = hardware_interface::parse_control_resources_from_urdf(urdf);
1163-
resource_storage_->import_joint_limiters(hardware_info);
11641163
// Set the update rate for all hardware components
11651164
for (auto & hw : hardware_info)
11661165
{
@@ -1235,6 +1234,12 @@ bool ResourceManager::load_and_initialize_components(
12351234
return components_are_loaded_and_initialized_;
12361235
}
12371236

1237+
void ResourceManager::import_joint_limiters(const std::string & urdf)
1238+
{
1239+
const auto hardware_info = hardware_interface::parse_control_resources_from_urdf(urdf);
1240+
resource_storage_->import_joint_limiters(hardware_info);
1241+
}
1242+
12381243
bool ResourceManager::are_components_initialized() const
12391244
{
12401245
return components_are_loaded_and_initialized_;

0 commit comments

Comments
 (0)