Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adds a ring field to the published pointcloud #431

Closed
wants to merge 3 commits into from
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 14 additions & 0 deletions carla_ros_bridge/src/carla_ros_bridge/lidar.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,8 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy
self.lidar_publisher = rospy.Publisher(self.get_topic_prefix(),
PointCloud2,
queue_size=10)

self.channels = int(self.carla_actor.attributes.get('channels'))
self.listen()

# pylint: disable=arguments-differ
Expand All @@ -72,15 +74,27 @@ def sensor_data_updated(self, carla_lidar_measurement):
PointField('y', 4, PointField.FLOAT32, 1),
PointField('z', 8, PointField.FLOAT32, 1),
PointField('intensity', 12, PointField.FLOAT32, 1),
PointField('ring', 16, PointField.UINT16, 1)
]

lidar_data = numpy.fromstring(
bytes(carla_lidar_measurement.raw_data), dtype=numpy.float32)
lidar_data = numpy.reshape(
lidar_data, (int(lidar_data.shape[0] / 4), 4))

ring = None

for i in range(self.channels):
current_ring_points_count = carla_lidar_measurement.get_point_count(i)
ring = numpy.vstack((ring, numpy.full((current_ring_points_count, 1), i)))

ring = numpy.delete(ring, 0, axis=0)
lidar_data = numpy.hstack((lidar_data, ring))

# we take the oposite of y axis
# (as lidar point are express in left handed coordinate system, and ros need right handed)
lidar_data[:, 1] *= -1

point_cloud_msg = create_cloud(header, fields, lidar_data)
self.lidar_publisher.publish(point_cloud_msg)

Expand Down