@@ -45,9 +45,9 @@ class TestWrenchTransformer : public ::testing::Test
4545 std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> executor_;
4646
4747 void setup_static_transform (
48- const std::string & parent_frame, const std::string & child_frame,
49- double x = 0.0 , double y = 0.0 , double z = 0.0 , double qx = 0.0 , double qy = 0.0 ,
50- double qz = 0.0 , double qw = 1.0 )
48+ const std::string & parent_frame, const std::string & child_frame, double x = 0.0 ,
49+ double y = 0.0 , double z = 0.0 , double qx = 0.0 , double qy = 0.0 , double qz = 0.0 ,
50+ double qw = 1.0 )
5151 {
5252 auto tf_node = std::make_shared<rclcpp::Node>(" static_tf_broadcaster" );
5353 executor_->add_node (tf_node);
@@ -71,11 +71,9 @@ class TestWrenchTransformer : public ::testing::Test
7171 }
7272
7373 std::shared_ptr<force_torque_sensor_broadcaster::WrenchTransformer> create_transformer_node (
74- const std::string & broadcaster_namespace = " test_broadcaster" ,
75- bool use_filtered_input = false ,
74+ const std::string & broadcaster_namespace = " test_broadcaster" , bool use_filtered_input = false ,
7675 const std::vector<std::string> & target_frames = {" base_link" },
77- const std::string & output_topic_prefix = " ~/wrench_transformed" ,
78- double tf_timeout = 0.1 )
76+ const std::string & output_topic_prefix = " ~/wrench_transformed" , double tf_timeout = 0.1 )
7977 {
8078 rclcpp::NodeOptions options;
8179 std::vector<rclcpp::Parameter> parameters;
@@ -130,7 +128,7 @@ TEST_F(TestWrenchTransformer, NodeInitialization)
130128 rclcpp::NodeOptions options;
131129 std::vector<rclcpp::Parameter> parameters;
132130 parameters.emplace_back (" target_frames" , std::vector<std::string>{" base_link" });
133-
131+
134132 options.parameter_overrides (parameters);
135133
136134 auto node = std::make_shared<force_torque_sensor_broadcaster::WrenchTransformer>(options);
@@ -144,13 +142,15 @@ TEST_F(TestWrenchTransformer, NodeInitialization)
144142TEST_F (TestWrenchTransformer, ParameterLoadingFromYamlFile)
145143{
146144 rclcpp::NodeOptions options;
147- options.arguments ({" --ros-args" , " --params-file" , std::string (TEST_FILES_DIRECTORY) + " /test_wrench_transformer.yaml" });
145+ options.arguments (
146+ {" --ros-args" , " --params-file" ,
147+ std::string (TEST_FILES_DIRECTORY) + " /test_wrench_transformer.yaml" });
148148 auto node = std::make_shared<force_torque_sensor_broadcaster::WrenchTransformer>(options);
149149 executor_->add_node (node);
150150 node->init ();
151-
151+
152152 ASSERT_NE (node, nullptr );
153-
153+
154154 // Verify parameters were loaded from YAML
155155 EXPECT_EQ (node->get_parameter (" broadcaster_namespace" ).as_string (), " test_broadcaster" );
156156 EXPECT_EQ (node->get_parameter (" use_filtered_input" ).as_bool (), false );
@@ -164,9 +164,7 @@ TEST_F(TestWrenchTransformer, ParameterLoadingFromYamlFile)
164164
165165TEST_F (TestWrenchTransformer, MultipleTargetFrames)
166166{
167- auto node = create_transformer_node (
168- " test_broadcaster" , false ,
169- {" base_link" , " end_effector" });
167+ auto node = create_transformer_node (" test_broadcaster" , false , {" base_link" , " end_effector" });
170168
171169 executor_->spin_some (std::chrono::milliseconds (100 ));
172170
@@ -188,8 +186,10 @@ TEST_F(TestWrenchTransformer, MultipleTargetFrames)
188186 wait_for_publisher (end_effector_sub);
189187
190188 ASSERT_NE (node, nullptr );
191- EXPECT_GT (base_link_sub->get_publisher_count (), 0u ) << " Publisher not found on /fts_wrench_transformer/wrench_transformed_base_link" ;
192- EXPECT_GT (end_effector_sub->get_publisher_count (), 0u ) << " Publisher not found on /fts_wrench_transformer/wrench_transformed_end_effector" ;
189+ EXPECT_GT (base_link_sub->get_publisher_count (), 0u )
190+ << " Publisher not found on /fts_wrench_transformer/wrench_transformed_base_link" ;
191+ EXPECT_GT (end_effector_sub->get_publisher_count (), 0u )
192+ << " Publisher not found on /fts_wrench_transformer/wrench_transformed_end_effector" ;
193193}
194194
195195TEST_F (TestWrenchTransformer, PublishSubscribeFlow)
@@ -216,7 +216,8 @@ TEST_F(TestWrenchTransformer, PublishSubscribeFlow)
216216 auto subscriber_node = std::make_shared<rclcpp::Node>(" test_subscriber" );
217217 auto output_subscriber = subscriber_node->create_subscription <geometry_msgs::msg::WrenchStamped>(
218218 " /fts_wrench_transformer/wrench_transformed_base_link" , rclcpp::SystemDefaultsQoS (),
219- [&received_msg](const geometry_msgs::msg::WrenchStamped::SharedPtr msg) { received_msg = msg; });
219+ [&received_msg](const geometry_msgs::msg::WrenchStamped::SharedPtr msg)
220+ { received_msg = msg; });
220221 executor_->add_node (subscriber_node);
221222
222223 wait_for_discovery ();
@@ -252,8 +253,8 @@ TEST_F(TestWrenchTransformer, PublishSubscribeFlow)
252253TEST_F (TestWrenchTransformer, PublishSubscribeMultipleFrames)
253254{
254255 // Create transformer node first so its TF listener can receive transforms
255- auto transformer_node = create_transformer_node (
256- " test_broadcaster" , false , {" base_link" , " end_effector" });
256+ auto transformer_node =
257+ create_transformer_node ( " test_broadcaster" , false , {" base_link" , " end_effector" });
257258 executor_->spin_some (std::chrono::milliseconds (100 ));
258259
259260 // Setup static transforms
@@ -273,14 +274,18 @@ TEST_F(TestWrenchTransformer, PublishSubscribeMultipleFrames)
273274 // Create subscriber nodes to receive output messages for both frames
274275 geometry_msgs::msg::WrenchStamped::SharedPtr received_base_link;
275276 geometry_msgs::msg::WrenchStamped::SharedPtr received_end_effector;
276-
277+
277278 auto subscriber_node = std::make_shared<rclcpp::Node>(" test_subscriber" );
278- auto base_link_subscriber = subscriber_node->create_subscription <geometry_msgs::msg::WrenchStamped>(
279- " /fts_wrench_transformer/wrench_transformed_base_link" , rclcpp::SystemDefaultsQoS (),
280- [&received_base_link](const geometry_msgs::msg::WrenchStamped::SharedPtr msg) { received_base_link = msg; });
281- auto end_effector_subscriber = subscriber_node->create_subscription <geometry_msgs::msg::WrenchStamped>(
282- " /fts_wrench_transformer/wrench_transformed_end_effector" , rclcpp::SystemDefaultsQoS (),
283- [&received_end_effector](const geometry_msgs::msg::WrenchStamped::SharedPtr msg) { received_end_effector = msg; });
279+ auto base_link_subscriber =
280+ subscriber_node->create_subscription <geometry_msgs::msg::WrenchStamped>(
281+ " /fts_wrench_transformer/wrench_transformed_base_link" , rclcpp::SystemDefaultsQoS (),
282+ [&received_base_link](const geometry_msgs::msg::WrenchStamped::SharedPtr msg)
283+ { received_base_link = msg; });
284+ auto end_effector_subscriber =
285+ subscriber_node->create_subscription <geometry_msgs::msg::WrenchStamped>(
286+ " /fts_wrench_transformer/wrench_transformed_end_effector" , rclcpp::SystemDefaultsQoS (),
287+ [&received_end_effector](const geometry_msgs::msg::WrenchStamped::SharedPtr msg)
288+ { received_end_effector = msg; });
284289 executor_->add_node (subscriber_node);
285290
286291 wait_for_discovery ();
@@ -299,8 +304,10 @@ TEST_F(TestWrenchTransformer, PublishSubscribeMultipleFrames)
299304
300305 // Verify messages were received and transformed
301306 ASSERT_NE (transformer_node, nullptr );
302- ASSERT_TRUE (received_base_link != nullptr ) << " Transformed message for base_link was not received" ;
303- ASSERT_TRUE (received_end_effector != nullptr ) << " Transformed message for end_effector was not received" ;
307+ ASSERT_TRUE (received_base_link != nullptr )
308+ << " Transformed message for base_link was not received" ;
309+ ASSERT_TRUE (received_end_effector != nullptr )
310+ << " Transformed message for end_effector was not received" ;
304311 EXPECT_EQ (received_base_link->header .frame_id , " base_link" );
305312 EXPECT_EQ (received_end_effector->header .frame_id , " end_effector" );
306313}
0 commit comments