Skip to content

Commit b9059c4

Browse files
[update] Update shebang of 'visualizer.py'
1 parent afd0708 commit b9059c4

File tree

1 file changed

+25
-15
lines changed

1 file changed

+25
-15
lines changed

script/visualizer.py

Lines changed: 25 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
1-
#!/usr/bin/python
2-
# -*- coding: utf-8 -*-
1+
#!/usr/bin/python3
2+
# -*- coding: utf-8 -*-
33

44
# ============================================
55
__author__ = "ShigemichiMatsuzaki"
@@ -14,8 +14,10 @@
1414
from cv_bridge import CvBridge
1515
import copy
1616

17+
1718
class Visualizer:
1819
""" """
20+
1921
def __init__(self):
2022
""" Constructor of Visualizer class
2123
@@ -24,14 +26,18 @@ def __init__(self):
2426
"""
2527
# Subscribers
2628
self.image_sub = message_filters.Subscriber('image', Image)
27-
self.start_point_sub = message_filters.Subscriber('start_point', PointStamped)
28-
self.end_point_sub = message_filters.Subscriber('end_point', PointStamped)
29+
self.start_point_sub = message_filters.Subscriber(
30+
'start_point', PointStamped)
31+
self.end_point_sub = message_filters.Subscriber(
32+
'end_point', PointStamped)
2933
# Time synchronizer
30-
self.ts = message_filters.TimeSynchronizer([self.image_sub, self.start_point_sub, self.end_point_sub], 100)
34+
self.ts = message_filters.TimeSynchronizer(
35+
[self.image_sub, self.start_point_sub, self.end_point_sub], 100)
3136
self.ts.registerCallback(self.image_points_callback)
3237

3338
# Publisher
34-
self.image_pub = rospy.Publisher('image_and_path', Image, queue_size=100)
39+
self.image_pub = rospy.Publisher(
40+
'image_and_path', Image, queue_size=100)
3541

3642
self.bridge = CvBridge()
3743

@@ -43,12 +49,14 @@ def image_points_callback(self, img_msg, start_point_msg, end_point_msg):
4349
start_point_msg(geometry_msgs/PointStamped)
4450
end_point_msg(geometry_msgs/PointStamped)
4551
"""
46-
# Convert the image message to
47-
cv_image = self.bridge.imgmsg_to_cv2(img_msg, desired_encoding='passthrough')
52+
# Convert the image message to
53+
cv_image = self.bridge.imgmsg_to_cv2(
54+
img_msg, desired_encoding='passthrough')
4855

4956
cv_image_with_line = self.draw_line(cv_image,
50-
(int(start_point_msg.point.x), int(start_point_msg.point.y)),
51-
(int(end_point_msg.point.x), int(end_point_msg.point.y)))
57+
(int(start_point_msg.point.x),
58+
int(start_point_msg.point.y)),
59+
(int(end_point_msg.point.x), int(end_point_msg.point.y)))
5260

5361
vis_img_msg = self.bridge.cv2_to_imgmsg(cv_image_with_line)
5462

@@ -61,26 +69,28 @@ def draw_line(self, cv_image, start_point, end_point):
6169
cv_image(OpenCV image)
6270
start_point_msg(geometry_msgs/PointStamped)
6371
end_point_msg(geometry_msgs/PointStamped)
64-
72+
6573
Return:
6674
OpenCV image with a line drawn
6775
"""
6876
ret_image = copy.deepcopy(cv_image)
6977

70-
cv2.line(ret_image, start_point, end_point, color=(0, 0, 255), thickness=10)
78+
cv2.line(ret_image, start_point, end_point,
79+
color=(0, 0, 255), thickness=10)
7180

7281
return ret_image
7382

83+
7484
def main():
7585
"""Main function to initialize the ROS node"""
7686
rospy.init_node("visualizer")
7787

7888
visualizer = Visualizer()
7989

8090
rospy.loginfo('visualizer is initialized')
81-
82-
rospy.spin()
91+
92+
rospy.spin()
8393

8494

85-
if __name__=='__main__':
95+
if __name__ == '__main__':
8696
main()

0 commit comments

Comments
 (0)