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

Commit

Permalink
feat(#211): publish closest point in front of the car
Browse files Browse the repository at this point in the history
  • Loading branch information
timdreier committed Mar 11, 2023
1 parent 7672d40 commit 8bfc626
Show file tree
Hide file tree
Showing 8 changed files with 231 additions and 41 deletions.
2 changes: 1 addition & 1 deletion build/Taskfile
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ task:shell() {
##########################################
task:install() {
task:install:git_hooks
task:gitconfig:copy
# task:gitconfig:copy
install:gpu-support
docker:install
}
Expand Down
2 changes: 1 addition & 1 deletion build/docker/agent/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ RUN apt-get update && apt-get install -y \
ros-noetic-ackermann-msgs ros-noetic-derived-object-msgs \
ros-noetic-carla-msgs ros-noetic-pcl-conversions \
ros-noetic-rviz ros-noetic-rqt ros-noetic-pcl-ros ros-noetic-rosbridge-suite ros-noetic-rosbridge-server \
ros-noetic-robot-pose-ekf \
ros-noetic-robot-pose-ekf ros-noetic-ros-numpy \
ros-noetic-py-trees-ros ros-noetic-rqt-py-trees ros-noetic-rqt-reconfigure

SHELL ["/bin/bash", "-c"]
Expand Down
109 changes: 82 additions & 27 deletions code/agent/config/dev_objects.json
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,18 @@
"id": "OpenDRIVE",
"reading_frequency": 1
},
{
"type": "sensor.pseudo.actor_list",
"id": "actor_list"
},
{
"type": "vehicle.lincoln.mkz_2020",
"id": "hero",
"role_name": "hero",
"spawn_point": {
"x": 986.0,
"y": -5442.0,
"z": 371.0,
"x": 983.5,
"y": -5373.2,
"z": 371.5,
"yaw": -90.0,
"pitch": 0.0,
"roll": 0.0
Expand All @@ -22,9 +26,9 @@
"type": "sensor.camera.rgb",
"id": "Center",
"spawn_point": {
"x": 0.7,
"y": 0.4,
"z": 1.60,
"x": 0.0,
"y": 0.0,
"z": 1.70,
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0,
Expand All @@ -33,26 +37,77 @@
"chromatic_aberration_intensity": 0.5,
"chromatic_aberration_offset": 0.0
},
"image_size_x": 300,
"image_size_y": 200,
"fov": 100,
"attached_objects": [
{
"type": "actor.pseudo.control",
"id": "control"
}
]
"image_size_x": 1920,
"image_size_y": 1080,
"fov": 120
},
{
"type": "sensor.camera.rgb",
"id": "Left",
"spawn_point": {
"x": 0.0,
"y": 0.0,
"z": 1.70,
"roll": 0.0,
"pitch": 0.0,
"yaw": 90.0,
"lens_circle_multiplier": 3.0,
"lens_circle_falloff": 3.0,
"chromatic_aberration_intensity": 0.5,
"chromatic_aberration_offset": 0.0
},
"image_size_x": 1920,
"image_size_y": 1080,
"fov": 120
},
{
"type": "sensor.camera.rgb",
"id": "Right",
"spawn_point": {
"x": 0.0,
"y": 0.0,
"z": 1.70,
"roll": 0.0,
"pitch": 0.0,
"yaw": -90.0,
"lens_circle_multiplier": 3.0,
"lens_circle_falloff": 3.0,
"chromatic_aberration_intensity": 0.5,
"chromatic_aberration_offset": 0.0
},
"image_size_x": 1920,
"image_size_y": 1080,
"fov": 120
},
{
"type": "sensor.camera.rgb",
"id": "Back",
"spawn_point": {
"x": 0.0,
"y": 0.0,
"z": 1.70,
"roll": 0.0,
"pitch": 0.0,
"yaw": 180.0,
"lens_circle_multiplier": 3.0,
"lens_circle_falloff": 3.0,
"chromatic_aberration_intensity": 0.5,
"chromatic_aberration_offset": 0.0
},
"image_size_x": 1920,
"image_size_y": 1080,
"fov": 120
},
{
"type": "sensor.lidar.ray_cast",
"id": "LIDAR",
"spawn_point": {
"x": 0.7,
"y": 0.4,
"z": 1.60,
"x": 0.0,
"y": 0.0,
"z": 1.70,
"roll": 0.0,
"pitch": 0.0,
"yaw": -45.0
"yaw": 0.0
},
"range": 85,
"rotation_frequency": 10,
Expand All @@ -69,9 +124,9 @@
"type": "sensor.other.radar",
"id": "RADAR",
"spawn_point": {
"x": 0.7,
"y": 0.4,
"z": 1.60,
"x": 0.0,
"y": 0.0,
"z": 1.70,
"roll": 0.0,
"pitch": 0.0,
"yaw": -45.0
Expand All @@ -85,13 +140,13 @@
"type": "sensor.other.gnss",
"id": "GPS",
"spawn_point": {
"x": 0.0,
"x": 0.7,
"y": 0.0,
"z": 1.60
},
"noise_alt_stddev": 0.00000,
"noise_lat_stddev": 0.00000,
"noise_lon_stddev": 0.00000,
"noise_alt_stddev": 0.000005,
"noise_lat_stddev": 0.000005,
"noise_lon_stddev": 0.000005,
"noise_alt_bias": 0.0,
"noise_lat_bias": 0.0,
"noise_lon_bias": 0.0
Expand All @@ -105,7 +160,7 @@
"z": 1.60,
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0
"yaw": -45.0
},
"noise_accel_stddev_x": 0.001,
"noise_accel_stddev_y": 0.001,
Expand Down
53 changes: 41 additions & 12 deletions code/agent/config/rviz_config.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,10 @@ Panels:
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded: ~
Expanded:
- /PointCloud23
Splitter Ratio: 0.5
Tree Height: 417
Tree Height: 308
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expand Down Expand Up @@ -88,7 +89,7 @@ Visualization Manager:
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Min Color: 0; 0; 0
Expand All @@ -103,7 +104,7 @@ Visualization Manager:
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
Value: false
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Expand All @@ -116,7 +117,7 @@ Visualization Manager:
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Min Color: 0; 0; 0
Expand All @@ -131,7 +132,7 @@ Visualization Manager:
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
Value: false
- Alpha: 1
Buffer Length: 1
Class: rviz/Path
Expand All @@ -156,6 +157,34 @@ Visualization Manager:
Topic: /paf/hero/trajectory
Unreliable: false
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Min Color: 0; 0; 0
Name: PointCloud2
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.20000000298023224
Style: Flat Squares
Topic: /carla/hero/LIDAR_filtered
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Expand Down Expand Up @@ -184,7 +213,7 @@ Visualization Manager:
Views:
Current:
Class: rviz/Orbit
Distance: 34.785499572753906
Distance: 5.234607219696045
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Expand All @@ -200,19 +229,19 @@ Visualization Manager:
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.19039836525917053
Pitch: 0.1753983497619629
Target Frame: <Fixed Frame>
Yaw: 4.520427227020264
Yaw: 4.805431365966797
Saved: ~
Window Geometry:
Camera:
collapsed: false
Displays:
collapsed: false
Height: 1376
Height: 1136
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd000000040000000000000304000004c6fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b0000022a000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d006500720061010000026b000002960000001600ffffff000000010000010f000004c6fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000004c6000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009b80000003efc0100000002fb0000000800540069006d00650100000000000009b80000030700fffffffb0000000800540069006d0065010000000000000450000000000000000000000599000004c600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd000000040000000000000304000003d6fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001bd000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000001fe000002130000001600ffffff000000010000010f000003d6fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000003d6000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007380000003efc0100000002fb0000000800540069006d00650100000000000007380000030700fffffffb0000000800540069006d0065010000000000000450000000000000000000000319000003d600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
Expand All @@ -221,6 +250,6 @@ Window Geometry:
collapsed: false
Views:
collapsed: false
Width: 2488
Width: 1848
X: 1992
Y: 27
2 changes: 2 additions & 0 deletions code/perception/launch/perception.launch
Original file line number Diff line number Diff line change
Expand Up @@ -26,4 +26,6 @@
<param name="debug" value="true"/>
<param name="self_diagnose" value="true"/>
</node>

<node pkg="perception" type="lidar_distance.py" name="lidar_distance" output="screen"></node>
</launch>
59 changes: 59 additions & 0 deletions code/perception/src/lidar_distance.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
#!/usr/bin/env python
import rospy
import ros_numpy
import numpy as np
import lidar_filter_utility
from sensor_msgs.msg import PointCloud2, Range

class LidarDistance():

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

def callback(self, data):
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)

rospy.loginfo(len(coordinates))
# Filter coordinates based in generated bit_mask
coordinates = coordinates[bit_mask]
rospy.loginfo(len(coordinates))

# Create pointcloud from manipulated data
coordinates_manipulated = ros_numpy.point_cloud2.array_to_pointcloud2(coordinates)
coordinates_manipulated.header = data.header

# Publish manipulated pointCloud2
self.pub_pointcloud.publish(coordinates_manipulated)

# https://stackoverflow.com/questions/1401712/how-can-the-euclidean-distance-be-calculated-with-numpy
coordinates_xyz = np.array(lidar_filter_utility.remove_field_name(coordinates, 'intensity').tolist())
distances = np.array([np.linalg.norm(c - [0, 0, 0]) for c in coordinates_xyz])

if len(distances) > 0:
range_msg = Range()
range_msg.max_range = max(distances)
range_msg.min_range = min(distances)
range_msg.range = min(distances)

self.pub_range.publish(range_msg)

def listener(self):
# In ROS, nodes are uniquely named. If two nodes with the same
# name are launched, the previous one is kicked off. The
# 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.Subscriber("/carla/hero/LIDAR", PointCloud2, self.callback)

# spin() simply keeps python from exiting until this node is stopped
rospy.spin()


if __name__ == '__main__':
lidar_distance = LidarDistance()
lidar_distance.listener()
Loading

0 comments on commit 8bfc626

Please sign in to comment.