Skip to content

Commit

Permalink
fix tests for the new API
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Nov 20, 2023
1 parent 6d4fb2d commit 5499e54
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 2 deletions.
7 changes: 6 additions & 1 deletion admittance_controller/test/test_admittance_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,11 +122,16 @@ class TestableAdmittanceController : public admittance_controller::AdmittanceCon
return success;
}

rclcpp::NodeOptions get_node_options() const override { return node_options_; }

void set_node_options(const rclcpp::NodeOptions & node_options) { node_options_ = node_options; }

private:
rclcpp::WaitSet input_wrench_command_subscriber_wait_set_;
rclcpp::WaitSet input_pose_command_subscriber_wait_set_;
const std::string robot_description_ = ros2_control_test_assets::valid_6d_robot_urdf;
const std::string robot_description_semantic_ = ros2_control_test_assets::valid_6d_robot_srdf;
rclcpp::NodeOptions node_options_;
};

class AdmittanceControllerTest : public ::testing::Test
Expand Down Expand Up @@ -185,7 +190,7 @@ class AdmittanceControllerTest : public ::testing::Test
controller_interface::return_type SetUpControllerCommon(
const std::string & controller_name, const rclcpp::NodeOptions & options)
{
auto result = controller_->init(controller_name, "", 0, "", options);
auto result = controller_->init(controller_name, "", 0, "");

controller_->export_reference_interfaces();
assign_interfaces();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,8 @@ class TestableJointTrajectoryController
return ret;
}

rclcpp::NodeOptions get_node_options() const override { return node_options_; }

/**
* @brief wait_for_trajectory block until a new JointTrajectory is received.
* Requires that the executor is not spinned elsewhere between the
Expand Down Expand Up @@ -151,7 +153,10 @@ class TestableJointTrajectoryController

double get_cmd_timeout() { return cmd_timeout_; }

void set_node_options(const rclcpp::NodeOptions & node_options) { node_options_ = node_options; }

rclcpp::WaitSet joint_cmd_sub_wait_set_;
rclcpp::NodeOptions node_options_;
};

class TrajectoryControllerTest : public ::testing::Test
Expand Down Expand Up @@ -195,8 +200,9 @@ class TrajectoryControllerTest : public ::testing::Test
parameter_overrides.push_back(rclcpp::Parameter("state_interfaces", state_interface_types_));
parameter_overrides.insert(parameter_overrides.end(), parameters.begin(), parameters.end());
node_options.parameter_overrides(parameter_overrides);
traj_controller_->set_node_options(node_options);

auto ret = traj_controller_->init(controller_name_, "", 0, "", node_options);
auto ret = traj_controller_->init(controller_name_, "", 0, "");
if (ret != controller_interface::return_type::OK)
{
FAIL();
Expand Down

0 comments on commit 5499e54

Please sign in to comment.