|
35 | 35 | #include "hardware_interface/loaned_command_interface.hpp" |
36 | 36 | #include "hardware_interface/loaned_state_interface.hpp" |
37 | 37 | #include "rclcpp/parameter_value.hpp" |
| 38 | +#include "rclcpp/version.h" |
| 39 | +#if RCLCPP_VERSION_GTE(18, 0, 0) |
| 40 | +#include "rclcpp/node_interfaces/node_interfaces.hpp" |
| 41 | +#endif |
38 | 42 | #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" |
39 | 43 | #include "semantic_components/force_torque_sensor.hpp" |
40 | 44 | #include "test_asset_6d_robot_description.hpp" |
@@ -160,8 +164,13 @@ class AdmittanceControllerTest : public ::testing::Test |
160 | 164 | controller_interface::return_type SetUpControllerCommon( |
161 | 165 | const std::string & controller_name, const rclcpp::NodeOptions & options) |
162 | 166 | { |
163 | | - auto result = |
164 | | - controller_->init(controller_name, controller_->robot_description_, 0, "", options); |
| 167 | + controller_interface::ControllerInterfaceParams params; |
| 168 | + params.controller_name = controller_name; |
| 169 | + params.robot_description = controller_->robot_description_; |
| 170 | + params.update_rate = 0; |
| 171 | + params.node_namespace = ""; |
| 172 | + params.node_options = options; |
| 173 | + auto result = controller_->init(params); |
165 | 174 |
|
166 | 175 | controller_->export_reference_interfaces(); |
167 | 176 | assign_interfaces(); |
@@ -215,7 +224,15 @@ class AdmittanceControllerTest : public ::testing::Test |
215 | 224 |
|
216 | 225 | void broadcast_tfs() |
217 | 226 | { |
| 227 | +#if RCLCPP_VERSION_GTE(18, 0, 0) |
| 228 | + static tf2_ros::TransformBroadcaster br( |
| 229 | + rclcpp::node_interfaces::NodeInterfaces( |
| 230 | + test_broadcaster_node_->get_node_parameters_interface(), |
| 231 | + test_broadcaster_node_->get_node_topics_interface())); |
| 232 | +#else |
218 | 233 | static tf2_ros::TransformBroadcaster br(test_broadcaster_node_); |
| 234 | +#endif |
| 235 | + |
219 | 236 | geometry_msgs::msg::TransformStamped transform_stamped; |
220 | 237 |
|
221 | 238 | transform_stamped.header.stamp = test_broadcaster_node_->now(); |
|
0 commit comments