File tree Expand file tree Collapse file tree 3 files changed +14
-1
lines changed
include/hardware_interface Expand file tree Collapse file tree 3 files changed +14
-1
lines changed Original file line number Diff line number Diff line change @@ -289,6 +289,7 @@ void ControllerManager::init_controller_manager()
289
289
// Get parameters needed for RT "update" loop to work
290
290
if (is_resource_manager_initialized ())
291
291
{
292
+ resource_manager_->import_joint_limiters (robot_description_);
292
293
init_services ();
293
294
}
294
295
else
@@ -370,6 +371,7 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String &
370
371
get_logger (),
371
372
" Resource Manager has been successfully initialized. Starting Controller Manager "
372
373
" services..." );
374
+ resource_manager_->import_joint_limiters (robot_description_);
373
375
init_services ();
374
376
}
375
377
}
Original file line number Diff line number Diff line change @@ -89,6 +89,12 @@ class ResourceManager
89
89
virtual bool load_and_initialize_components (
90
90
const std::string & urdf, const unsigned int update_rate = 100 );
91
91
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
+
92
98
/* *
93
99
* @brief if the resource manager load_and_initialize_components(...) function has been called
94
100
* this returns true. We want to permit to loading the urdf later on, but we currently don't want
Original file line number Diff line number Diff line change @@ -1160,7 +1160,6 @@ bool ResourceManager::load_and_initialize_components(
1160
1160
resource_storage_->cm_update_rate_ = update_rate;
1161
1161
1162
1162
auto hardware_info = hardware_interface::parse_control_resources_from_urdf (urdf);
1163
- resource_storage_->import_joint_limiters (hardware_info);
1164
1163
// Set the update rate for all hardware components
1165
1164
for (auto & hw : hardware_info)
1166
1165
{
@@ -1235,6 +1234,12 @@ bool ResourceManager::load_and_initialize_components(
1235
1234
return components_are_loaded_and_initialized_;
1236
1235
}
1237
1236
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
+
1238
1243
bool ResourceManager::are_components_initialized () const
1239
1244
{
1240
1245
return components_are_loaded_and_initialized_;
You can’t perform that action at this time.
0 commit comments