-
Notifications
You must be signed in to change notification settings - Fork 364
Add ControllerInterfaceParams
to initialize the Controllers
#2390
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
Open
saikishor
wants to merge
10
commits into
ros-controls:master
Choose a base branch
from
pal-robotics-forks:use/controller_interface_params
base: master
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
Open
Changes from all commits
Commits
Show all changes
10 commits
Select commit
Hold shift + click to select a range
72e82a3
Add controller initialization through ControllerInterfaceParams
saikishor 255df27
Use the update_rate from the controller interface params
saikishor ac5c555
Expose joint limits to the controller
saikishor ba6fa93
propagate the joint limits to the controller
saikishor 6d440dd
Add tests
saikishor 7101a73
Merge branch 'master' into use/controller_interface_params
saikishor 3c02f0a
Merge branch 'master' into use/controller_interface_params
saikishor dac4ba9
Merge branch 'master' into use/controller_interface_params
saikishor 89ceef1
Merge branch 'master' into use/controller_interface_params
bmagyar b7aca1a
Merge branch 'master' into use/controller_interface_params
bmagyar File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
60 changes: 60 additions & 0 deletions
60
controller_interface/include/controller_interface/controller_interface_params.hpp
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,60 @@ | ||
// Copyright 2025 ros2_control Development Team | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#ifndef CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_PARAMS_HPP_ | ||
#define CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_PARAMS_HPP_ | ||
|
||
#include <string> | ||
#include <unordered_map> | ||
|
||
#include "joint_limits/joint_limits.hpp" | ||
#include "rclcpp/node_options.hpp" | ||
|
||
/** | ||
* @brief Parameters for the Controller Interface | ||
* This struct holds the parameters required to initialize a controller interface. | ||
* | ||
* @var controller_name Name of the controller. | ||
* @var robot_description The URDF or SDF description of the robot. | ||
* @var cm_update_rate The update rate of the controller manager in Hz. | ||
* @var node_namespace The namespace for the controller node. | ||
* @var node_options Options for the controller node. | ||
* @var joint_limits A map of joint names to their limits. | ||
* @var soft_joint_limits A map of joint names to their soft limits. | ||
* | ||
* This struct is used to pass parameters to the controller interface during initialization. | ||
* It allows for easy configuration of the controller's behavior and interaction with the robot's | ||
* joints. | ||
*/ | ||
namespace controller_interface | ||
{ | ||
|
||
struct ControllerInterfaceParams | ||
{ | ||
ControllerInterfaceParams() = default; | ||
|
||
std::string controller_name = ""; | ||
std::string robot_description = ""; | ||
unsigned int update_rate = 0; | ||
|
||
std::string node_namespace = ""; | ||
rclcpp::NodeOptions node_options = rclcpp::NodeOptions(); | ||
|
||
std::unordered_map<std::string, joint_limits::JointLimits> hard_joint_limits = {}; | ||
std::unordered_map<std::string, joint_limits::SoftJointLimits> soft_joint_limits = {}; | ||
}; | ||
|
||
} // namespace controller_interface | ||
|
||
#endif // CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_PARAMS_HPP_ |
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -104,9 +104,21 @@ TEST(TestableControllerInterface, setting_update_rate_in_configure) | |
node_options_arguments.push_back("-p"); | ||
node_options_arguments.push_back("update_rate:=2812"); | ||
node_options = node_options.arguments(node_options_arguments); | ||
ASSERT_EQ( | ||
controller.init(TEST_CONTROLLER_NAME, "", 5000.0, "", node_options), | ||
controller_interface::return_type::OK); | ||
controller_interface::ControllerInterfaceParams params; | ||
params.controller_name = TEST_CONTROLLER_NAME; | ||
params.robot_description = ""; | ||
params.update_rate = 5000; // set a different update rate than the one in the node options | ||
params.node_namespace = ""; | ||
params.node_options = node_options; | ||
joint_limits::JointLimits joint_limits; | ||
joint_limits.has_velocity_limits = true; | ||
joint_limits.max_velocity = 1.0; | ||
params.hard_joint_limits["joint1"] = joint_limits; | ||
joint_limits::SoftJointLimits soft_joint_limits; | ||
soft_joint_limits.min_position = -1.0; | ||
soft_joint_limits.max_position = 1.0; | ||
params.soft_joint_limits["joint1"] = soft_joint_limits; | ||
Comment on lines
+113
to
+120
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. would you mind adding a new constructor to joint limits that allow a one-line initialization please? ;) There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Sure, I can |
||
ASSERT_EQ(controller.init(params), controller_interface::return_type::OK); | ||
|
||
// initialize executor to be able to get parameter update | ||
auto executor = | ||
|
@@ -122,6 +134,21 @@ TEST(TestableControllerInterface, setting_update_rate_in_configure) | |
|
||
// update_rate is set to controller_manager's rate | ||
ASSERT_EQ(controller.get_update_rate(), 5000u); | ||
const auto hard_limits = controller.get_hard_joint_limits(); | ||
const auto soft_limits = controller.get_soft_joint_limits(); | ||
ASSERT_THAT(hard_limits, testing::SizeIs(1)); | ||
ASSERT_TRUE(hard_limits.find("joint1") != hard_limits.end()); | ||
ASSERT_THAT(hard_limits.at("joint1").max_velocity, joint_limits.max_velocity); | ||
ASSERT_TRUE(hard_limits.at("joint1").has_velocity_limits); | ||
ASSERT_FALSE(hard_limits.at("joint1").has_position_limits); | ||
ASSERT_FALSE(hard_limits.at("joint1").has_acceleration_limits); | ||
ASSERT_FALSE(hard_limits.at("joint1").has_deceleration_limits); | ||
ASSERT_FALSE(hard_limits.at("joint1").has_jerk_limits); | ||
ASSERT_FALSE(hard_limits.at("joint1").has_effort_limits); | ||
ASSERT_THAT(soft_limits, testing::SizeIs(1)); | ||
ASSERT_TRUE(soft_limits.find("joint1") != soft_limits.end()); | ||
ASSERT_THAT(soft_limits.at("joint1").min_position, soft_joint_limits.min_position); | ||
ASSERT_THAT(soft_limits.at("joint1").max_position, soft_joint_limits.max_position); | ||
|
||
// Even after configure is 0 | ||
controller.configure(); | ||
|
@@ -156,6 +183,23 @@ TEST(TestableControllerInterface, setting_update_rate_in_configure) | |
controller.configure(); | ||
ASSERT_EQ(controller.get_update_rate(), 623u); | ||
|
||
// Should stay same after multiple cleanups as it is set during initialization | ||
const auto hard_limits_final = controller.get_hard_joint_limits(); | ||
const auto soft_limits_final = controller.get_soft_joint_limits(); | ||
ASSERT_THAT(hard_limits_final, testing::SizeIs(1)); | ||
ASSERT_TRUE(hard_limits_final.find("joint1") != hard_limits_final.end()); | ||
ASSERT_THAT(hard_limits_final.at("joint1").max_velocity, joint_limits.max_velocity); | ||
ASSERT_TRUE(hard_limits_final.at("joint1").has_velocity_limits); | ||
ASSERT_FALSE(hard_limits_final.at("joint1").has_position_limits); | ||
ASSERT_FALSE(hard_limits_final.at("joint1").has_acceleration_limits); | ||
ASSERT_FALSE(hard_limits_final.at("joint1").has_deceleration_limits); | ||
ASSERT_FALSE(hard_limits_final.at("joint1").has_jerk_limits); | ||
ASSERT_FALSE(hard_limits_final.at("joint1").has_effort_limits); | ||
ASSERT_THAT(soft_limits_final, testing::SizeIs(1)); | ||
ASSERT_TRUE(soft_limits_final.find("joint1") != soft_limits_final.end()); | ||
ASSERT_THAT(soft_limits_final.at("joint1").min_position, soft_joint_limits.min_position); | ||
ASSERT_THAT(soft_limits_final.at("joint1").max_position, soft_joint_limits.max_position); | ||
|
||
executor->cancel(); | ||
controller.get_node()->shutdown(); | ||
rclcpp::shutdown(); | ||
|
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
we could mark this function as deprecated already