Skip to content

Commit ac58998

Browse files
committed
fix tests for the new API
1 parent 3fc0f50 commit ac58998

File tree

2 files changed

+14
-2
lines changed

2 files changed

+14
-2
lines changed

admittance_controller/test/test_admittance_controller.hpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -122,11 +122,16 @@ class TestableAdmittanceController : public admittance_controller::AdmittanceCon
122122
return success;
123123
}
124124

125+
rclcpp::NodeOptions get_node_options() const override { return node_options_; }
126+
127+
void set_node_options(const rclcpp::NodeOptions & node_options) { node_options_ = node_options; }
128+
125129
private:
126130
rclcpp::WaitSet input_wrench_command_subscriber_wait_set_;
127131
rclcpp::WaitSet input_pose_command_subscriber_wait_set_;
128132
const std::string robot_description_ = ros2_control_test_assets::valid_6d_robot_urdf;
129133
const std::string robot_description_semantic_ = ros2_control_test_assets::valid_6d_robot_srdf;
134+
rclcpp::NodeOptions node_options_;
130135
};
131136

132137
class AdmittanceControllerTest : public ::testing::Test
@@ -185,7 +190,8 @@ class AdmittanceControllerTest : public ::testing::Test
185190
controller_interface::return_type SetUpControllerCommon(
186191
const std::string & controller_name, const rclcpp::NodeOptions & options)
187192
{
188-
auto result = controller_->init(controller_name, "", "", options);
193+
controller_->set_node_options(options);
194+
auto result = controller_->init(controller_name, "", "");
189195

190196
controller_->export_reference_interfaces();
191197
assign_interfaces();

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,8 @@ class TestableJointTrajectoryController
6767
return ret;
6868
}
6969

70+
rclcpp::NodeOptions get_node_options() const override { return node_options_; }
71+
7072
/**
7173
* @brief wait_for_trajectory block until a new JointTrajectory is received.
7274
* Requires that the executor is not spinned elsewhere between the
@@ -146,7 +148,10 @@ class TestableJointTrajectoryController
146148

147149
double get_cmd_timeout() { return cmd_timeout_; }
148150

151+
void set_node_options(const rclcpp::NodeOptions & node_options) { node_options_ = node_options; }
152+
149153
rclcpp::WaitSet joint_cmd_sub_wait_set_;
154+
rclcpp::NodeOptions node_options_;
150155
};
151156

152157
class TrajectoryControllerTest : public ::testing::Test
@@ -190,8 +195,9 @@ class TrajectoryControllerTest : public ::testing::Test
190195
parameter_overrides.push_back(rclcpp::Parameter("state_interfaces", state_interface_types_));
191196
parameter_overrides.insert(parameter_overrides.end(), parameters.begin(), parameters.end());
192197
node_options.parameter_overrides(parameter_overrides);
198+
traj_controller_->set_node_options(node_options);
193199

194-
auto ret = traj_controller_->init(controller_name_, "", "", node_options);
200+
auto ret = traj_controller_->init(controller_name_, "", "");
195201
if (ret != controller_interface::return_type::OK)
196202
{
197203
FAIL();

0 commit comments

Comments
 (0)