@@ -36,12 +36,11 @@ class FrameListener : public rclcpp::Node
3636 turtle_spawned_(false )
3737 {
3838 // Declare and acquire `target_frame` parameter
39- this ->declare_parameter <std::string>(" target_frame" , " turtle1" );
40- this ->get_parameter (" target_frame" , target_frame_);
39+ target_frame_ = this ->declare_parameter <std::string>(" target_frame" , " turtle1" );
4140
4241 tf_buffer_ =
4342 std::make_unique<tf2_ros::Buffer>(this ->get_clock ());
44- transform_listener_ =
43+ tf_listener_ =
4544 std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
4645
4746 // Create a client to spawn a turtle
@@ -67,15 +66,15 @@ class FrameListener : public rclcpp::Node
6766
6867 if (turtle_spawning_service_ready_) {
6968 if (turtle_spawned_) {
70- geometry_msgs::msg::TransformStamped transformStamped ;
69+ geometry_msgs::msg::TransformStamped t ;
7170
7271 // Look up for the transformation between target_frame and turtle2 frames
7372 // and send velocity commands for turtle2 to reach target_frame
7473 try {
75- transformStamped = tf_buffer_->lookupTransform (
74+ t = tf_buffer_->lookupTransform (
7675 toFrameRel, fromFrameRel,
7776 tf2::TimePointZero);
78- } catch (tf2::TransformException & ex) {
77+ } catch (const tf2::TransformException & ex) {
7978 RCLCPP_INFO (
8079 this ->get_logger (), " Could not transform %s to %s: %s" ,
8180 toFrameRel.c_str (), fromFrameRel.c_str (), ex.what ());
@@ -86,13 +85,13 @@ class FrameListener : public rclcpp::Node
8685
8786 static const double scaleRotationRate = 1.0 ;
8887 msg.angular .z = scaleRotationRate * atan2 (
89- transformStamped .transform .translation .y ,
90- transformStamped .transform .translation .x );
88+ t .transform .translation .y ,
89+ t .transform .translation .x );
9190
9291 static const double scaleForwardSpeed = 0.5 ;
9392 msg.linear .x = scaleForwardSpeed * sqrt (
94- pow (transformStamped .transform .translation .x , 2 ) +
95- pow (transformStamped .transform .translation .y , 2 ));
93+ pow (t .transform .translation .x , 2 ) +
94+ pow (t .transform .translation .y , 2 ));
9695
9796 publisher_->publish (msg);
9897 } else {
@@ -105,10 +104,10 @@ class FrameListener : public rclcpp::Node
105104 // Initialize request with turtle name and coordinates
106105 // Note that x, y and theta are defined as floats in turtlesim/srv/Spawn
107106 auto request = std::make_shared<turtlesim::srv::Spawn::Request>();
107+ request->name = " turtle2" ;
108108 request->x = 4.0 ;
109109 request->y = 2.0 ;
110110 request->theta = 0.0 ;
111- request->name = " turtle2" ;
112111
113112 // Call request
114113 using ServiceResponseFuture =
@@ -127,6 +126,7 @@ class FrameListener : public rclcpp::Node
127126 }
128127 }
129128 }
129+
130130 // Boolean values to store the information
131131 // if the service for spawning turtle is available
132132 bool turtle_spawning_service_ready_;
@@ -135,7 +135,7 @@ class FrameListener : public rclcpp::Node
135135 rclcpp::Client<turtlesim::srv::Spawn>::SharedPtr spawner_{nullptr };
136136 rclcpp::TimerBase::SharedPtr timer_{nullptr };
137137 rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_{nullptr };
138- std::shared_ptr<tf2_ros::TransformListener> transform_listener_ {nullptr };
138+ std::shared_ptr<tf2_ros::TransformListener> tf_listener_ {nullptr };
139139 std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
140140 std::string target_frame_;
141141};
0 commit comments