Skip to content

Commit

Permalink
Add import_joint_limiters method to also work for Gazebo and other …
Browse files Browse the repository at this point in the history
…simulators
  • Loading branch information
saikishor committed Jan 9, 2025
1 parent 55e7995 commit c292555
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 1 deletion.
2 changes: 2 additions & 0 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -289,6 +289,7 @@ void ControllerManager::init_controller_manager()
// Get parameters needed for RT "update" loop to work
if (is_resource_manager_initialized())
{
resource_manager_->import_joint_limiters(robot_description_);
init_services();
}
else
Expand Down Expand Up @@ -370,6 +371,7 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String &
get_logger(),
"Resource Manager has been successfully initialized. Starting Controller Manager "
"services...");
resource_manager_->import_joint_limiters(robot_description_);
init_services();
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,12 @@ class ResourceManager
virtual bool load_and_initialize_components(
const std::string & urdf, const unsigned int update_rate = 100);

/**
* @brief Import joint limiters from the URDF.
* @param urdf string containing the URDF.
*/
void import_joint_limiters(const std::string & urdf);

/**
* @brief if the resource manager load_and_initialize_components(...) function has been called
* this returns true. We want to permit to loading the urdf later on, but we currently don't want
Expand Down
7 changes: 6 additions & 1 deletion hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1160,7 +1160,6 @@ bool ResourceManager::load_and_initialize_components(
resource_storage_->cm_update_rate_ = update_rate;

auto hardware_info = hardware_interface::parse_control_resources_from_urdf(urdf);
resource_storage_->import_joint_limiters(hardware_info);
// Set the update rate for all hardware components
for (auto & hw : hardware_info)
{
Expand Down Expand Up @@ -1235,6 +1234,12 @@ bool ResourceManager::load_and_initialize_components(
return components_are_loaded_and_initialized_;
}

void ResourceManager::import_joint_limiters(const std::string & urdf)
{
const auto hardware_info = hardware_interface::parse_control_resources_from_urdf(urdf);
resource_storage_->import_joint_limiters(hardware_info);
}

bool ResourceManager::are_components_initialized() const
{
return components_are_loaded_and_initialized_;
Expand Down

0 comments on commit c292555

Please sign in to comment.