Skip to content

Commit 7b7ecb7

Browse files
Don't call release_interfaces from controllers (#1910)
1 parent 9ce90ba commit 7b7ecb7

File tree

5 files changed

+5
-7
lines changed

5 files changed

+5
-7
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1273,7 +1273,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_deactivate(
12731273
joint_command_interface_[index].clear();
12741274
joint_state_interface_[index].clear();
12751275
}
1276-
release_interfaces();
12771276

12781277
subscriber_is_active_ = false;
12791278

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -163,10 +163,9 @@ TEST_P(TrajectoryControllerTestParameterized, cleanup)
163163
traj_controller_->update(
164164
rclcpp::Time(static_cast<uint64_t>(0.5 * 1e9)), rclcpp::Duration::from_seconds(0.5));
165165

166-
auto state = traj_controller_->get_node()->deactivate();
167-
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
166+
DeactivateTrajectoryController();
168167

169-
state = traj_controller_->get_node()->cleanup();
168+
auto state = traj_controller_->get_node()->cleanup();
170169
ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id());
171170

172171
executor.cancel();
@@ -237,8 +236,7 @@ TEST_P(TrajectoryControllerTestParameterized, correct_initialization_using_param
237236

238237
// deactivate
239238
std::vector<double> deactivated_positions{joint_pos_[0], joint_pos_[1], joint_pos_[2]};
240-
state = traj_controller_->get_node()->deactivate();
241-
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);
239+
DeactivateTrajectoryController();
242240

243241
// it should be holding the current point
244242
expectHoldingPointDeactivated(deactivated_positions);

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -434,6 +434,7 @@ class TrajectoryControllerTest : public ::testing::Test
434434
EXPECT_EQ(
435435
traj_controller_->get_node()->deactivate().id(),
436436
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
437+
traj_controller_->release_interfaces();
437438
}
438439
}
439440
}

parallel_gripper_controller/include/parallel_gripper_controller/parallel_gripper_action_controller_impl.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -404,7 +404,6 @@ controller_interface::CallbackReturn GripperActionController::on_deactivate(
404404
joint_command_interface_ = std::nullopt;
405405
joint_position_state_interface_ = std::nullopt;
406406
joint_velocity_state_interface_ = std::nullopt;
407-
release_interfaces();
408407
return controller_interface::CallbackReturn::SUCCESS;
409408
}
410409

parallel_gripper_controller/test/test_parallel_gripper_controller.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -132,6 +132,7 @@ TEST_F(GripperControllerTest, ActivateDeactivateActivateSuccess)
132132
ASSERT_EQ(
133133
this->controller_->on_deactivate(rclcpp_lifecycle::State()),
134134
controller_interface::CallbackReturn::SUCCESS);
135+
this->controller_->release_interfaces();
135136

136137
// re-assign interfaces
137138
std::vector<LoanedCommandInterface> command_ifs;

0 commit comments

Comments
 (0)