Skip to content

Commit d34800c

Browse files
authored
Delete failing parameter undeclare in JointGroupPositionController (ros-controls#222)
* delete failing parameter unset from joint group position controller * explicitly set the interface_name parameter to HW_IF_POSITION * set interface_name param in velocity and effort controllers * fix line spacing and length * additional code style fix
1 parent a86a8c2 commit d34800c

File tree

3 files changed

+12
-6
lines changed

3 files changed

+12
-6
lines changed

effort_controllers/src/joint_group_effort_controller.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -40,8 +40,10 @@ JointGroupEffortController::init(
4040
}
4141

4242
try {
43-
// undeclare interface parameter used in the general forward_command_controller
44-
get_node()->undeclare_parameter("interface_name");
43+
// Explicitly set the interface parameter declared by the forward_command_controller
44+
// to match the value set in the JointGroupEffortController constructor.
45+
get_node()->set_parameter(
46+
rclcpp::Parameter("interface_name", hardware_interface::HW_IF_EFFORT));
4547
} catch (const std::exception & e) {
4648
fprintf(stderr, "Exception thrown during init stage with message: %s \n", e.what());
4749
return controller_interface::return_type::ERROR;

position_controllers/src/joint_group_position_controller.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -39,8 +39,10 @@ JointGroupPositionController::init(const std::string & controller_name)
3939
}
4040

4141
try {
42-
// undeclare interface parameter used in the general forward_command_controller
43-
get_node()->undeclare_parameter("interface_name");
42+
// Explicitly set the interface parameter declared by the forward_command_controller
43+
// to match the value set in the JointGroupPositionController constructor.
44+
get_node()->set_parameter(
45+
rclcpp::Parameter("interface_name", hardware_interface::HW_IF_POSITION));
4446
} catch (const std::exception & e) {
4547
fprintf(stderr, "Exception thrown during init stage with message: %s \n", e.what());
4648
return controller_interface::return_type::ERROR;

velocity_controllers/src/joint_group_velocity_controller.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -40,8 +40,10 @@ JointGroupVelocityController::init(
4040
}
4141

4242
try {
43-
// undeclare interface parameter used in the general forward_command_controller
44-
get_node()->undeclare_parameter("interface_name");
43+
// Explicitly set the interface parameter declared by the forward_command_controller
44+
// to match the value set in the JointGroupVelocityController constructor.
45+
get_node()->set_parameter(
46+
rclcpp::Parameter("interface_name", hardware_interface::HW_IF_VELOCITY));
4547
} catch (const std::exception & e) {
4648
fprintf(stderr, "Exception thrown during init stage with message: %s \n", e.what());
4749
return controller_interface::return_type::ERROR;

0 commit comments

Comments
 (0)