Skip to content

Commit 2479342

Browse files
authored
Minor cleanups across the tutorials. (#71)
The main goal of this commit is to synchronize the C++ and Python code so they look very similar to each other. Signed-off-by: Chris Lalancette <[email protected]>
1 parent de098f2 commit 2479342

11 files changed

+77
-78
lines changed

turtle_tf2_cpp/src/dynamic_frame_tf2_broadcaster.cpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ class DynamicFrameBroadcaster : public rclcpp::Node
3030
DynamicFrameBroadcaster()
3131
: Node("dynamic_frame_tf2_broadcaster")
3232
{
33-
tf_publisher_ = std::make_shared<tf2_ros::TransformBroadcaster>(this);
33+
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(this);
3434
timer_ = this->create_wall_timer(
3535
100ms, std::bind(&DynamicFrameBroadcaster::broadcast_timer_callback, this));
3636
}
@@ -40,8 +40,8 @@ class DynamicFrameBroadcaster : public rclcpp::Node
4040
{
4141
rclcpp::Time now = this->get_clock()->now();
4242
double x = now.seconds() * PI;
43-
geometry_msgs::msg::TransformStamped t;
4443

44+
geometry_msgs::msg::TransformStamped t;
4545
t.header.stamp = now;
4646
t.header.frame_id = "turtle1";
4747
t.child_frame_id = "carrot1";
@@ -53,10 +53,11 @@ class DynamicFrameBroadcaster : public rclcpp::Node
5353
t.transform.rotation.z = 0.0;
5454
t.transform.rotation.w = 1.0;
5555

56-
tf_publisher_->sendTransform(t);
56+
tf_broadcaster_->sendTransform(t);
5757
}
58+
5859
rclcpp::TimerBase::SharedPtr timer_;
59-
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_publisher_;
60+
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
6061
};
6162

6263
int main(int argc, char * argv[])

turtle_tf2_cpp/src/fixed_frame_tf2_broadcaster.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -28,18 +28,17 @@ class FixedFrameBroadcaster : public rclcpp::Node
2828
FixedFrameBroadcaster()
2929
: Node("fixed_frame_tf2_broadcaster")
3030
{
31-
tf_publisher_ = std::make_shared<tf2_ros::TransformBroadcaster>(this);
31+
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(this);
3232
timer_ = this->create_wall_timer(
3333
100ms, std::bind(&FixedFrameBroadcaster::broadcast_timer_callback, this));
3434
}
3535

3636
private:
3737
void broadcast_timer_callback()
3838
{
39-
rclcpp::Time now = this->get_clock()->now();
4039
geometry_msgs::msg::TransformStamped t;
4140

42-
t.header.stamp = now;
41+
t.header.stamp = this->get_clock()->now();
4342
t.header.frame_id = "turtle1";
4443
t.child_frame_id = "carrot1";
4544
t.transform.translation.x = 0.0;
@@ -50,10 +49,11 @@ class FixedFrameBroadcaster : public rclcpp::Node
5049
t.transform.rotation.z = 0.0;
5150
t.transform.rotation.w = 1.0;
5251

53-
tf_publisher_->sendTransform(t);
52+
tf_broadcaster_->sendTransform(t);
5453
}
54+
5555
rclcpp::TimerBase::SharedPtr timer_;
56-
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_publisher_;
56+
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
5757
};
5858

5959
int main(int argc, char * argv[])

turtle_tf2_cpp/src/static_turtle_tf2_broadcaster.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ class StaticFramePublisher : public rclcpp::Node
2525
explicit StaticFramePublisher(char * transformation[])
2626
: Node("static_turtle_tf2_broadcaster")
2727
{
28-
tf_publisher_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);
28+
tf_static_broadcaster_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);
2929

3030
// Publish static transforms once at startup
3131
this->make_transforms(transformation);
@@ -34,10 +34,9 @@ class StaticFramePublisher : public rclcpp::Node
3434
private:
3535
void make_transforms(char * transformation[])
3636
{
37-
rclcpp::Time now = this->get_clock()->now();
3837
geometry_msgs::msg::TransformStamped t;
3938

40-
t.header.stamp = now;
39+
t.header.stamp = this->get_clock()->now();
4140
t.header.frame_id = "world";
4241
t.child_frame_id = transformation[1];
4342

@@ -54,9 +53,10 @@ class StaticFramePublisher : public rclcpp::Node
5453
t.transform.rotation.z = q.z();
5554
t.transform.rotation.w = q.w();
5655

57-
tf_publisher_->sendTransform(t);
56+
tf_static_broadcaster_->sendTransform(t);
5857
}
59-
std::shared_ptr<tf2_ros::StaticTransformBroadcaster> tf_publisher_;
58+
59+
std::shared_ptr<tf2_ros::StaticTransformBroadcaster> tf_static_broadcaster_;
6060
};
6161

6262
int main(int argc, char * argv[])
@@ -67,7 +67,7 @@ int main(int argc, char * argv[])
6767
if (argc != 8) {
6868
RCLCPP_INFO(
6969
logger, "Invalid number of parameters\nusage: "
70-
"ros2 run learning_tf2_cpp static_turtle_tf2_broadcaster "
70+
"$ ros2 run learning_tf2_cpp static_turtle_tf2_broadcaster "
7171
"child_frame_name x y z roll pitch yaw");
7272
return 1;
7373
}
@@ -76,7 +76,7 @@ int main(int argc, char * argv[])
7676
// necessary to check that the frame name passed is different
7777
if (strcmp(argv[1], "world") == 0) {
7878
RCLCPP_INFO(logger, "Your static turtle name cannot be 'world'");
79-
return 1;
79+
return 2;
8080
}
8181

8282
// Pass parameters and initialize node

turtle_tf2_cpp/src/turtle_tf2_broadcaster.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,7 @@ class FramePublisher : public rclcpp::Node
3030
: Node("turtle_tf2_frame_publisher")
3131
{
3232
// Declare and acquire `turtlename` parameter
33-
this->declare_parameter<std::string>("turtlename", "turtle");
34-
this->get_parameter("turtlename", turtlename_);
33+
turtlename_ = this->declare_parameter<std::string>("turtlename", "turtle");
3534

3635
// Initialize the transform broadcaster
3736
tf_broadcaster_ =
@@ -51,12 +50,11 @@ class FramePublisher : public rclcpp::Node
5150
private:
5251
void handle_turtle_pose(const std::shared_ptr<turtlesim::msg::Pose> msg)
5352
{
54-
rclcpp::Time now = this->get_clock()->now();
5553
geometry_msgs::msg::TransformStamped t;
5654

5755
// Read message content and assign it to
5856
// corresponding tf variables
59-
t.header.stamp = now;
57+
t.header.stamp = this->get_clock()->now();
6058
t.header.frame_id = "world";
6159
t.child_frame_id = turtlename_.c_str();
6260

@@ -79,6 +77,7 @@ class FramePublisher : public rclcpp::Node
7977
// Send the transformation
8078
tf_broadcaster_->sendTransform(t);
8179
}
80+
8281
rclcpp::Subscription<turtlesim::msg::Pose>::SharedPtr subscription_;
8382
std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
8483
std::string turtlename_;

turtle_tf2_cpp/src/turtle_tf2_listener.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -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
};

turtle_tf2_cpp/src/turtle_tf2_message_filter.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,7 @@ class PoseDrawer : public rclcpp::Node
3838
: Node("turtle_tf2_pose_drawer")
3939
{
4040
// Declare and acquire `target_frame` parameter
41-
this->declare_parameter<std::string>("target_frame", "turtle1");
42-
this->get_parameter("target_frame", target_frame_);
41+
target_frame_ = this->declare_parameter<std::string>("target_frame", "turtle1");
4342

4443
typedef std::chrono::duration<int> seconds_type;
4544
seconds_type buffer_timeout(1);
@@ -73,7 +72,7 @@ class PoseDrawer : public rclcpp::Node
7372
point_out.point.x,
7473
point_out.point.y,
7574
point_out.point.z);
76-
} catch (tf2::TransformException & ex) {
75+
} catch (const tf2::TransformException & ex) {
7776
RCLCPP_WARN(
7877
// Print exception which was caught
7978
this->get_logger(), "Failure %s\n", ex.what());

turtle_tf2_py/turtle_tf2_py/dynamic_frame_tf2_broadcaster.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ class DynamicFrameBroadcaster(Node):
2626

2727
def __init__(self):
2828
super().__init__('dynamic_frame_tf2_broadcaster')
29-
self.br = TransformBroadcaster(self)
29+
self.tf_broadcaster = TransformBroadcaster(self)
3030
self.timer = self.create_timer(0.1, self.broadcast_timer_callback)
3131

3232
def broadcast_timer_callback(self):
@@ -45,7 +45,7 @@ def broadcast_timer_callback(self):
4545
t.transform.rotation.z = 0.0
4646
t.transform.rotation.w = 1.0
4747

48-
self.br.sendTransform(t)
48+
self.tf_broadcaster.sendTransform(t)
4949

5050

5151
def main():

turtle_tf2_py/turtle_tf2_py/fixed_frame_tf2_broadcaster.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,11 +24,12 @@ class FixedFrameBroadcaster(Node):
2424

2525
def __init__(self):
2626
super().__init__('fixed_frame_tf2_broadcaster')
27-
self.br = TransformBroadcaster(self)
27+
self.tf_broadcaster = TransformBroadcaster(self)
2828
self.timer = self.create_timer(0.1, self.broadcast_timer_callback)
2929

3030
def broadcast_timer_callback(self):
3131
t = TransformStamped()
32+
3233
t.header.stamp = self.get_clock().now().to_msg()
3334
t.header.frame_id = 'turtle1'
3435
t.child_frame_id = 'carrot1'
@@ -40,7 +41,7 @@ def broadcast_timer_callback(self):
4041
t.transform.rotation.z = 0.0
4142
t.transform.rotation.w = 1.0
4243

43-
self.br.sendTransform(t)
44+
self.tf_broadcaster.sendTransform(t)
4445

4546

4647
def main():

turtle_tf2_py/turtle_tf2_py/static_turtle_tf2_broadcaster.py

Lines changed: 22 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -65,42 +65,44 @@ class StaticFramePublisher(Node):
6565
def __init__(self, transformation):
6666
super().__init__('static_turtle_tf2_broadcaster')
6767

68-
self._tf_publisher = StaticTransformBroadcaster(self)
68+
self.tf_static_broadcaster = StaticTransformBroadcaster(self)
6969

7070
# Publish static transforms once at startup
7171
self.make_transforms(transformation)
7272

7373
def make_transforms(self, transformation):
74-
static_transformStamped = TransformStamped()
75-
static_transformStamped.header.stamp = self.get_clock().now().to_msg()
76-
static_transformStamped.header.frame_id = 'world'
77-
static_transformStamped.child_frame_id = sys.argv[1]
78-
static_transformStamped.transform.translation.x = float(sys.argv[2])
79-
static_transformStamped.transform.translation.y = float(sys.argv[3])
80-
static_transformStamped.transform.translation.z = float(sys.argv[4])
74+
t = TransformStamped()
75+
76+
t.header.stamp = self.get_clock().now().to_msg()
77+
t.header.frame_id = 'world'
78+
t.child_frame_id = transformation[1]
79+
80+
t.transform.translation.x = float(transformation[2])
81+
t.transform.translation.y = float(transformation[3])
82+
t.transform.translation.z = float(transformation[4])
8183
quat = quaternion_from_euler(
82-
float(sys.argv[5]), float(sys.argv[6]), float(sys.argv[7]))
83-
static_transformStamped.transform.rotation.x = quat[0]
84-
static_transformStamped.transform.rotation.y = quat[1]
85-
static_transformStamped.transform.rotation.z = quat[2]
86-
static_transformStamped.transform.rotation.w = quat[3]
84+
float(transformation[5]), float(transformation[6]), float(transformation[7]))
85+
t.transform.rotation.x = quat[0]
86+
t.transform.rotation.y = quat[1]
87+
t.transform.rotation.z = quat[2]
88+
t.transform.rotation.w = quat[3]
8789

88-
self._tf_publisher.sendTransform(static_transformStamped)
90+
self.tf_static_broadcaster.sendTransform(t)
8991

9092

9193
def main():
9294
logger = rclpy.logging.get_logger('logger')
9395

9496
# obtain parameters from command line arguments
95-
if len(sys.argv) < 8:
97+
if len(sys.argv) != 8:
9698
logger.info('Invalid number of parameters. Usage: \n'
9799
'$ ros2 run turtle_tf2_py static_turtle_tf2_broadcaster'
98100
'child_frame_name x y z roll pitch yaw')
99-
sys.exit(0)
100-
else:
101-
if sys.argv[1] == 'world':
102-
logger.info('Your static turtle name cannot be "world"')
103-
sys.exit(0)
101+
sys.exit(1)
102+
103+
if sys.argv[1] == 'world':
104+
logger.info('Your static turtle name cannot be "world"')
105+
sys.exit(2)
104106

105107
# pass parameters and initialize node
106108
rclpy.init()

turtle_tf2_py/turtle_tf2_py/turtle_tf2_broadcaster.py

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -60,12 +60,11 @@ def __init__(self):
6060
super().__init__('turtle_tf2_frame_publisher')
6161

6262
# Declare and acquire `turtlename` parameter
63-
self.declare_parameter('turtlename', 'turtle')
64-
self.turtlename = self.get_parameter(
65-
'turtlename').get_parameter_value().string_value
63+
self.turtlename = self.declare_parameter(
64+
'turtlename', 'turtle').get_parameter_value().string_value
6665

6766
# Initialize the transform broadcaster
68-
self.br = TransformBroadcaster(self)
67+
self.tf_broadcaster = TransformBroadcaster(self)
6968

7069
# Subscribe to a turtle{1}{2}/pose topic and call handle_turtle_pose
7170
# callback function on each message
@@ -74,7 +73,7 @@ def __init__(self):
7473
f'/{self.turtlename}/pose',
7574
self.handle_turtle_pose,
7675
1)
77-
self.subscription
76+
self.subscription # prevent unused variable warning
7877

7978
def handle_turtle_pose(self, msg):
8079
t = TransformStamped()
@@ -101,7 +100,7 @@ def handle_turtle_pose(self, msg):
101100
t.transform.rotation.w = q[3]
102101

103102
# Send the transformation
104-
self.br.sendTransform(t)
103+
self.tf_broadcaster.sendTransform(t)
105104

106105

107106
def main():

0 commit comments

Comments
 (0)