Skip to content

Commit c079105

Browse files
mergify[bot]saikishorbmagyar
authored
Move enforce_command_limits parameter to GPL parameters (backport #2305) (#2316)
* Move `enforce_command_limits` parameter to GPL parameters (#2305) (cherry picked from commit 2c691e0) # Conflicts: # controller_manager/src/controller_manager_parameters.yaml * change default to maintain behaviour and fix conflict --------- Co-authored-by: Sai Kishor Kothakota <[email protected]> Co-authored-by: Bence Magyar <[email protected]>
1 parent 6ea0064 commit c079105

File tree

4 files changed

+11
-13
lines changed

4 files changed

+11
-13
lines changed

controller_manager/doc/userdoc.rst

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -79,11 +79,6 @@ robot_description [std_msgs::msg::String]
7979
Parameters
8080
-----------
8181

82-
enforce_command_limits (optional; bool; default: ``false`` for Jazzy and earlier distro and ``true`` for Rolling and newer distros)
83-
Enforces the joint limits to the joint command interfaces.
84-
If the command is outside the limits, the command is clamped to be within the limits depending on the type of configured joint limits in the URDF.
85-
If the command is within the limits, the command is passed through without any changes.
86-
8782
<controller_name>.type
8883
Name of a plugin exported using ``pluginlib`` for a controller.
8984
This is a class from which controller's instance with name "``controller_name``" is created.

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -673,7 +673,6 @@ class ControllerManager : public rclcpp::Node
673673
std::string robot_description_;
674674
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr robot_description_subscription_;
675675
rclcpp::TimerBase::SharedPtr robot_description_notification_timer_;
676-
bool enforce_command_limits_;
677676

678677
controller_manager::MovingAverageStatistics periodicity_stats_;
679678

controller_manager/src/controller_manager.cpp

Lines changed: 3 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -490,7 +490,7 @@ void ControllerManager::init_controller_manager()
490490
// Get parameters needed for RT "update" loop to work
491491
if (is_resource_manager_initialized())
492492
{
493-
if (enforce_command_limits_)
493+
if (params_->enforce_command_limits)
494494
{
495495
resource_manager_->import_joint_limiters(robot_description_);
496496
}
@@ -556,12 +556,8 @@ void ControllerManager::init_controller_manager()
556556
RCLCPP_INFO(get_logger(), "Shutting down the controller manager.");
557557
}));
558558

559-
// Declare the enforce_command_limits parameter such a way that it is enabled by default for
560-
// rolling and newer alone
561-
enforce_command_limits_ =
562-
this->get_parameter_or("enforce_command_limits", RCLCPP_VERSION_MAJOR >= 29 ? true : false);
563559
RCLCPP_INFO_EXPRESSION(
564-
get_logger(), enforce_command_limits_, "Enforcing command limits is enabled...");
560+
get_logger(), params_->enforce_command_limits, "Enforcing command limits is enabled...");
565561
}
566562

567563
void ControllerManager::initialize_parameters()
@@ -615,7 +611,7 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String &
615611

616612
void ControllerManager::init_resource_manager(const std::string & robot_description)
617613
{
618-
if (enforce_command_limits_)
614+
if (params_->enforce_command_limits)
619615
{
620616
resource_manager_->import_joint_limiters(robot_description_);
621617
}

controller_manager/src/controller_manager_parameters.yaml

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,13 @@ controller_manager:
66
description: "The frequency of controller manager's real-time update loop. This loop reads states from hardware, updates controllers and writes commands to hardware."
77
}
88

9+
enforce_command_limits: {
10+
type: bool,
11+
default_value: false,
12+
read_only: true,
13+
description: "If true, the controller manager will enforce command limits defined in the robot description. If false, no limits will be enforced. If true, when the command is outside the limits, the command is clamped to be within the limits depending on the type of configured joint limits defined in the robot description. If the command is within the limits, the command is passed through without any changes.",
14+
}
15+
916
hardware_components_initial_state:
1017
unconfigured: {
1118
type: string_array,
@@ -28,6 +35,7 @@ controller_manager:
2835
shutdown_on_initial_state_failure: {
2936
type: bool,
3037
default_value: true,
38+
read_only: true,
3139
description: "Specifies whether the controller manager should shut down if setting the desired initial state fails during startup.",
3240
}
3341

0 commit comments

Comments
 (0)