Skip to content

Commit b087f8d

Browse files
committed
added few comments
1 parent 97b6dc6 commit b087f8d

1 file changed

Lines changed: 16 additions & 12 deletions

File tree

GEMstack/onboard/perception/pedestrian_detection.py

Lines changed: 16 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -83,16 +83,17 @@ def initialize(self):
8383

8484
# Lidar Tranform topic publisher
8585
self.rosbag_lidar_livox_pub = rospy.Publisher("/livox/transformed_lidar", PointCloud2, queue_size=1)
86-
# self.rosbag_lidar_ouster_pub = rospy.Publisher("/ouster/transformed_lidar", PointCloud2, queue_size=1)
86+
self.rosbag_lidar_ouster_pub = rospy.Publisher("/ouster/transformed_lidar", PointCloud2, queue_size=1)
8787

8888
self.rosbag_cam_sub = rospy.Subscriber('/oak/rgb/image_raw',Image, self.image_callback,queue_size=1)
8989
self.rosbag_lidar_livox_sub = rospy.Subscriber('/livox/lidar',PointCloud2, self.lidar_livox_callback,queue_size=1)
90-
# self.rosbag_lidar_ouster_sub = rospy.Subscriber('/ouster/points',PointCloud2, self.lidar_ouster_callback,queue_size=1)
90+
self.rosbag_lidar_ouster_sub = rospy.Subscriber('/ouster/points',PointCloud2, self.lidar_ouster_callback,queue_size=1)
9191

9292
pass
9393

9494

95-
def publish_base_link(self):
95+
# Publishes baselink to map transformation for visualization
96+
def publish_base_link_to_map(self):
9697

9798
br = tf2_ros.TransformBroadcaster()
9899
transform = TransformStamped()
@@ -113,6 +114,8 @@ def publish_base_link(self):
113114
transform.transform.rotation.w = 1.0 # No rotation
114115
br.sendTransform(transform)
115116

117+
118+
# Livox Lidar data
116119
def lidar_livox_callback(self,pointcloud : PointCloud2):
117120

118121
transform = self.tf_buffer.lookup_transform('base_link', pointcloud.header.frame_id, rospy.Time(0), rospy.Duration(1.0))
@@ -124,20 +127,21 @@ def lidar_livox_callback(self,pointcloud : PointCloud2):
124127
self.rosbag_lidar_livox_pub.publish(transformed_cloud)
125128

126129
if(self.visualization):
127-
self.publish_base_link()
130+
self.publish_base_link_to_map()
128131

129-
# def lidar_ouster_callback(self,pointcloud : PointCloud2):
132+
# Ouster Lidar data
133+
def lidar_ouster_callback(self,pointcloud : PointCloud2):
130134

131-
# transform = self.tf_buffer.lookup_transform('base_link', pointcloud.header.frame_id, rospy.Time(0), rospy.Duration(1.0))
135+
transform = self.tf_buffer.lookup_transform('base_link', pointcloud.header.frame_id, rospy.Time(0), rospy.Duration(1.0))
132136

133-
# # Transform the point cloud
134-
# transformed_cloud = do_transform_cloud(pointcloud, transform)
137+
# Transform the point cloud
138+
transformed_cloud = do_transform_cloud(pointcloud, transform)
135139

136-
# # Publish transformed point cloud
137-
# self.rosbag_lidar_livox_pub.publish(transformed_cloud)
140+
# Publish transformed point cloud
141+
self.rosbag_lidar_livox_pub.publish(transformed_cloud)
138142

139-
# if(self.visualization):
140-
# self.publish_base_link()
143+
if(self.visualization):
144+
self.publish_base_link_to_map()
141145

142146

143147
# Use cv2.Mat for GEM Car, Image for RosBag

0 commit comments

Comments
 (0)