Skip to content
This repository has been archived by the owner on Nov 16, 2023. It is now read-only.

Commit

Permalink
feat(#211): Added parametrization
Browse files Browse the repository at this point in the history
  • Loading branch information
timdreier committed Mar 16, 2023
1 parent 8bfc626 commit 939b47b
Show file tree
Hide file tree
Showing 3 changed files with 30 additions and 6 deletions.
10 changes: 9 additions & 1 deletion code/perception/launch/perception.launch
Original file line number Diff line number Diff line change
Expand Up @@ -27,5 +27,13 @@
<param name="self_diagnose" value="true"/>
</node>

<node pkg="perception" type="lidar_distance.py" name="lidar_distance" output="screen"></node>
<node pkg="perception" type="lidar_distance.py" name="lidar_distance" output="screen">
<param name="max_y" value="1.5"/>
<param name="min_y" value="-1.5"/>
<param name="min_x" value="2.5"/>
<param name="min_z" value="-1.5"/>
<param name="max_z" value="0"/>
<param name="point_cloud_topic" value="/carla/hero/LIDAR_filtered"/>
<param name="range_topic" value="/carla/hero/LIDAR_range"/>
</node>
</launch>
26 changes: 21 additions & 5 deletions code/perception/src/lidar_distance.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,14 +7,25 @@

class LidarDistance():

pub_pointcloud = rospy.Publisher('/carla/hero/LIDAR_filtered', PointCloud2)
pub_range = rospy.Publisher('/carla/hero/LIDAR_range', Range)

def callback(self, data):
""" Callback function to process PointCloud2 and publish a Range message
from the contained points and a PointCloud2
:param data:
:return:
"""
coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data)

# https://stackoverflow.com/questions/44295375/how-to-slice-a-numpy-ndarray-made-up-of-numpy-void-numbers
bit_mask = lidar_filter_utility.bounding_box(coordinates, max_x=1, min_x=-1, min_y=1, min_z=-1.5, max_z=0)
bit_mask = lidar_filter_utility.bounding_box(
coordinates,
max_x = rospy.get_param('~max_x', np.inf),
min_x= rospy.get_param('~min_x', np.inf),
max_y=rospy.get_param('~max_y', np.inf),
min_y=rospy.get_param('~min_y', np.inf),
max_z=rospy.get_param('~max_z', np.inf),
min_z=rospy.get_param('~min_z', np.inf),
)

rospy.loginfo(len(coordinates))
# Filter coordinates based in generated bit_mask
Expand Down Expand Up @@ -46,7 +57,12 @@ def listener(self):
# anonymous=True flag means that rospy will choose a unique
# name for our 'listener' node so that multiple listeners can
# run simultaneously.
rospy.init_node('lidar_distance', anonymous=True)
rospy.init_node('lidar_distance')

namespace = rospy.get_namespace()

self.pub_pointcloud = rospy.Publisher(rospy.get_param('~point_cloud_topic', '/carla/hero/' + rospy.get_namespace() + '_filtered'), PointCloud2)
self.pub_range = rospy.Publisher(rospy.get_param('~range_topic', '/carla/hero/' + rospy.get_namespace() + '_range'), Range)

rospy.Subscriber("/carla/hero/LIDAR", PointCloud2, self.callback)

Expand Down
Empty file.

0 comments on commit 939b47b

Please sign in to comment.