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

466 add radar sensor #522

Merged
merged 8 commits into from
Nov 24, 2024
Merged
Show file tree
Hide file tree
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
6 changes: 6 additions & 0 deletions code/perception/launch/perception.launch
Original file line number Diff line number Diff line change
Expand Up @@ -79,4 +79,10 @@
<param name="point_cloud_topic" value="/carla/hero/LIDAR_filtered"/>
<param name="range_topic" value="/carla/hero/LIDAR_range"/>
</node>

<node pkg="perception" type="radar_node.py" name="radar_node" output="screen">
<param name="point_cloud_topic" value="/carla/hero/RADAR_filtered"/>
<param name="range_topic" value="/carla/hero/RADAR_range"/>
Comment on lines +84 to +85
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

💡 Codebase verification

Warning: RADAR topics mismatch detected

The RADAR topics referenced in perception.launch (/carla/hero/RADAR_filtered and /carla/hero/RADAR_range) don't match the actual topics used in the radar_node.py implementation:

  • radar_node.py subscribes to /carla/hero/RADAR
  • radar_node.py publishes to /paf/hero/Radar/velocity

Additionally, the node doesn't use the parameters point_cloud_topic and range_topic defined in the launch file.

  • Update perception.launch to use correct topics:
    <param name="source_topic" value="/carla/hero/RADAR"/>
    <param name="image_distance_topic" value="/paf/hero/Radar/velocity"/>
  • Or modify radar_node.py to use the launch file parameters
🔗 Analysis chain

Verify the existence of RADAR topics.

The node references filtered RADAR data topics. Let's verify these topics exist in the system.

🏁 Scripts executed

The following scripts were executed for the analysis:

Script:

#!/bin/bash
# Description: Search for RADAR topic definitions and usage
# Expected: Find corresponding topic definitions in sensor setup or CARLA configuration

# Search for RADAR topic definitions
rg -l "RADAR_filtered|RADAR_range" --type python --type xml

# Search for any RADAR-related configurations
fd -e yaml -e xml -e json | xargs rg "RADAR" -l

Length of output: 175


Script:

#!/bin/bash
# Let's check the content of the dev_objects.json to understand RADAR configuration
cat code/agent/config/dev_objects.json

# Let's also search for any RADAR-related topics in launch files
find . -name "*.launch" -type f -exec grep -l "RADAR" {} \;

# Search for any RADAR-related code in Python files (using find since rg doesn't support python)
find . -name "*.py" -type f -exec grep -l "RADAR" {} \;

Length of output: 6497


Script:

#!/bin/bash
# Let's check the radar_node.py to understand how these topics are used
cat code/perception/src/radar_node.py

# Also check the perception launch file to see the full context
cat code/perception/launch/perception.launch

Length of output: 5362

</node>

</launch>
54 changes: 54 additions & 0 deletions code/perception/src/radar_node.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
#!/usr/bin/env python
import rospy
import ros_numpy
import numpy as np
from sensor_msgs.msg import PointCloud2
from std_msgs.msg import Float32


class RadarNode:
"""See doc/perception/radar_node.md on
how to configure this node
"""

def callback(self, data):
"""Process radar Point2Cloud data and publish minimum velocity.

Extracts velocity information from radar data
and publishes the minimum velocity as a
Float32 message

Args:
data: Point2Cloud message containing radar data with velocity field
"""

coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data)
msg = np.min(coordinates["Velocity"])
self.dist_array_radar_publisher.publish(msg)
Comment on lines +25 to +27
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

⚠️ Potential issue

Add error handling for radar data processing

The callback lacks validation and error handling for the radar data processing.

Apply this diff to add proper error handling:

-        coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data)
-        msg = np.min(coordinates["Velocity"])
-        self.dist_array_radar_publisher.publish(msg)
+        try:
+            coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data)
+            if "Velocity" not in coordinates.dtype.names:
+                rospy.logerr("Radar data missing Velocity field")
+                return
+            if len(coordinates) == 0:
+                rospy.logwarn("Received empty radar data")
+                return
+            msg = np.min(coordinates["Velocity"])
+            self.dist_array_radar_publisher.publish(msg)
+        except Exception as e:
+            rospy.logerr(f"Error processing radar data: {e}")
📝 Committable suggestion

‼️ IMPORTANT
Carefully review the code before committing. Ensure that it accurately replaces the highlighted code, contains no missing lines, and has no issues with indentation. Thoroughly test & benchmark the code to ensure it meets the requirements.

Suggested change
coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data)
msg = np.min(coordinates["Velocity"])
self.dist_array_radar_publisher.publish(msg)
try:
coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data)
if "Velocity" not in coordinates.dtype.names:
rospy.logerr("Radar data missing Velocity field")
return
if len(coordinates) == 0:
rospy.logwarn("Received empty radar data")
return
msg = np.min(coordinates["Velocity"])
self.dist_array_radar_publisher.publish(msg)
except Exception as e:
rospy.logerr(f"Error processing radar data: {e}")


def listener(self):
"""
Initializes the node and it's publishers
"""
# run simultaneously.
rospy.init_node("radar_node")

# publisher for radar dist_array
self.dist_array_radar_publisher = rospy.Publisher(
rospy.get_param("~image_distance_topic", "/paf/hero/Radar/velocity"),
Float32,
queue_size=10,
)

rospy.Subscriber(
rospy.get_param("~source_topic", "/carla/hero/RADAR"),
PointCloud2,
self.callback,
)

rospy.spin()


if __name__ == "__main__":
radar_node = RadarNode()
radar_node.listener()
36 changes: 36 additions & 0 deletions doc/perception/radar_node.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
# Radar Node

**Summary:** This page explains what the radar sensor does.

- [Radar offsets](#radar-offsets)
- [Radar specification](#radar-specification)
- [Radar data output for each detected point](#radar-data-output-for-each-detected-point)
- [Todo](#todo)

## Radar offsets

- x: 2
- y: 0
- z: 0.7

## Radar specification

- points per second: 1500 points generated by all lasers per second
- maximum range: 100 meters
- horizontal fov: 30 degrees
- vertical fov: 30 degrees

## Radar data output for each detected point

- x
- y
- z
- Range
- Velocity
- AzimuthAngle
- ElevationAngle

## Todo

- Discuss further processing of radar data
- Combine lidar, radar and camera data
Loading