@@ -52,15 +52,21 @@ static const double EPS = 1e-3;
5252TEST (tf2_ros, buffer_client)
5353{
5454 rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(" tf_action_node" );
55- std::unique_ptr<tf2_ros::BufferClient> client = std::make_unique<tf2_ros::BufferClient>(node, " tf_action" );
55+ std::unique_ptr<tf2_ros::BufferClient> client = std::make_unique<tf2_ros::BufferClient>(
56+ node,
57+ " tf_action" );
5658
5759 rclcpp::executors::SingleThreadedExecutor executor;
5860
5961 executor.add_node (node);
6062
63+ std::cout << " FOOO" << std::endl;
64+
6165 // Start spinning in a thread
6266 std::thread spin_thread = std::thread (
63- std::bind (&rclcpp::executors::SingleThreadedExecutor::spin, &executor));
67+ [&executor]() {
68+ executor.spin ();
69+ });
6470
6571 // make sure that things are set up
6672 ASSERT_TRUE (client->waitForServer (std::chrono::seconds (4 )));
@@ -72,19 +78,17 @@ TEST(tf2_ros, buffer_client)
7278 p1.point .y = 0.0 ;
7379 p1.point .z = 0.0 ;
7480
75- try
76- {
81+ try {
7782 geometry_msgs::msg::PointStamped p2 = client->transform (p1, " b" );
78- RCLCPP_INFO (node->get_logger (),
79- " p1: (%.2f, %.2f, %.2f), p2: (%.2f, %.2f, %.2f)" , p1.point .x ,
80- p1.point .y , p1.point .z , p2.point .x , p2.point .y , p2.point .z );
83+ RCLCPP_INFO (
84+ node->get_logger (),
85+ " p1: (%.2f, %.2f, %.2f), p2: (%.2f, %.2f, %.2f)" , p1.point .x ,
86+ p1.point .y , p1.point .z , p2.point .x , p2.point .y , p2.point .z );
8187
8288 EXPECT_NEAR (p2.point .x , -5.0 , EPS);
8389 EXPECT_NEAR (p2.point .y , -6.0 , EPS);
8490 EXPECT_NEAR (p2.point .z , -7.0 , EPS);
85- }
86- catch (tf2::TransformException& ex)
87- {
91+ } catch (tf2::TransformException & ex) {
8892 RCLCPP_ERROR (node->get_logger (), " Failed to transform: %s" , ex.what ());
8993 ASSERT_FALSE (" Should not get here" );
9094 }
@@ -96,23 +100,26 @@ TEST(tf2_ros, buffer_client)
96100TEST (tf2_ros, buffer_client_different_types)
97101{
98102 rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(" tf_action_node" );
99- std::unique_ptr<tf2_ros::BufferClient> client = std::make_unique<tf2_ros::BufferClient>(node, " tf_action" );
103+ std::unique_ptr<tf2_ros::BufferClient> client = std::make_unique<tf2_ros::BufferClient>(
104+ node,
105+ " tf_action" );
100106
101107 rclcpp::executors::SingleThreadedExecutor executor;
102108
103109 executor.add_node (node);
104110
105111 // Start spinning in a thread
106112 std::thread spin_thread = std::thread (
107- std::bind (&rclcpp::executors::SingleThreadedExecutor::spin, &executor));
113+ [&executor]() {
114+ executor.spin ();
115+ });
108116
109117 // make sure that things are set up
110118 ASSERT_TRUE (client->waitForServer (std::chrono::seconds (4 )));
111119
112120 tf2::Stamped<KDL::Vector> k1 (KDL::Vector (0 , 0 , 0 ), tf2::TimePoint (), " a" );
113121
114- try
115- {
122+ try {
116123 tf2::Stamped<btVector3> b1;
117124 client->transform (k1, b1, " b" );
118125 RCLCPP_ERROR (node->get_logger (), " Bullet: (%.4f, %.4f, %.4f)" , b1[0 ], b1[1 ], b1[2 ]);
@@ -122,9 +129,7 @@ TEST(tf2_ros, buffer_client_different_types)
122129 EXPECT_NEAR (b1[2 ], -7.0 , EPS);
123130 EXPECT_EQ (b1.frame_id_ , " b" );
124131 EXPECT_EQ (k1.frame_id_ , " a" );
125- }
126- catch (tf2::TransformException& ex)
127- {
132+ } catch (tf2::TransformException & ex) {
128133 RCLCPP_ERROR (node->get_logger (), " Failed to transform: %s" , ex.what ());
129134 ASSERT_FALSE (" Should not get here" );
130135 }
@@ -134,7 +139,7 @@ TEST(tf2_ros, buffer_client_different_types)
134139
135140}
136141
137- int main (int argc, char ** argv)
142+ int main (int argc, char ** argv)
138143{
139144 // This is needed because we need to wait a little bit for the other nodes
140145 std::this_thread::sleep_for (std::chrono::milliseconds (1000 ));
0 commit comments