-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
WIP adding launch file (still need to make node and port over changes)
- Loading branch information
1 parent
8fdef3e
commit 8773d74
Showing
3 changed files
with
65 additions
and
21 deletions.
There are no files selected for viewing
3 changes: 3 additions & 0 deletions
3
src/perception/radar_object_detection/config/nuscenes_config.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,3 @@ | ||
radar_object_detection_node: | ||
ros__parameters: | ||
lidar_topic: /RADAR_TOP |
27 changes: 27 additions & 0 deletions
27
...perception/radar_object_detection/radar_object_detection_launch/launch/nuscenes_launch.py
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,27 @@ | ||
from launch import LaunchDescription | ||
from launch_ros.actions import Node | ||
from ament_index_python.packages import get_package_share_directory | ||
import os | ||
|
||
|
||
def generate_launch_description(): | ||
ld = LaunchDescription() | ||
config = os.path.join( | ||
get_package_share_directory('radar_object_detection'), | ||
'config', | ||
'nuscenes_config.yaml' | ||
) | ||
|
||
# nodes | ||
radar_detection = Node( | ||
package='radar_vis', | ||
executable='radar_vis_node', | ||
name='radar_velocity_detection_node', | ||
parameters=[config], | ||
arguments=['--ros-args', '--log-level', 'info'] | ||
) | ||
|
||
# finalize | ||
ld.add_action(radar_detection) | ||
|
||
return ld |
56 changes: 35 additions & 21 deletions
56
src/perception/radar_object_detection/radar_vis/src/radar_det.py
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,21 +1,35 @@ | ||
class RadarVelocityDetectionNode(Node): | ||
def __init__(self): | ||
super().__init__('radar_velocity_detection_node') | ||
self.subscription = self.create_subscription( | ||
PointCloud2, | ||
'/RADAR_TOP', | ||
self.listener_callback, | ||
10) | ||
self.publisher_ = self.create_publisher(Float32, 'velocity', 10) | ||
self.get_logger().info('Radar Velocity Detection Node has been started') | ||
def listener_callback(self, msg): | ||
points_array = ros2_numpy.point_cloud2.pointcloud2_to_array(msg) | ||
velocities = self.detect_velocities(points_array) | ||
avg_velocity = np.mean(velocities) if velocities.size > 0 else 0.0 | ||
self.publisher_.publish(Float32(data=avg_velocity)) | ||
self.get_logger().info(f'Average velocity: {avg_velocity:.2f} m/s') | ||
|
||
def detect_velocities(self, points_array): | ||
# Assuming velocity is in fields 'vx' and 'vy' | ||
velocities = np.sqrt(points_array['vx']**2 + points_array['vy']**2) | ||
return velocities | ||
import rclpy | ||
from rclpy.node import Node | ||
from std_msgs.msg import Float32 | ||
from radar_velocity_detection.msg import RadarDetections | ||
import numpy as np | ||
|
||
class RadarVelocityDetectionNode(Node): | ||
def __init__(self): | ||
super().__init__('radar_velocity_detection_node') | ||
Check failure on line 9 in src/perception/radar_object_detection/radar_vis/src/radar_det.py GitHub Actions / Autopep8src/perception/radar_object_detection/radar_vis/src/radar_det.py#L3-L9
|
||
self.subscription = self.create_subscription( | ||
RadarDetections, | ||
'/RADAR_TOP', | ||
self.listener_callback, | ||
10) | ||
self.publisher_ = self.create_publisher(Float32, 'velocity', 10) | ||
|
||
def listener_callback(self, msg): | ||
velocities = self.detect_velocities(msg.detections) | ||
avg_velocity = np.mean(velocities) if len(velocities) > 0 else 0.0 | ||
self.publisher_.publish(Float32(data=avg_velocity)) | ||
self.get_logger().info(f'Average velocity: {avg_velocity:.2f} m/s') | ||
|
||
def detect_velocities(self, detections): | ||
velocities = [np.sqrt(d.vx**2 + d.vy**2) for d in detections] | ||
return velocities | ||
|
||
def main(args=None): | ||
rclpy.init(args=args) | ||
node = RadarVelocityDetectionNode() | ||
rclpy.spin(node) | ||
Check failure on line 30 in src/perception/radar_object_detection/radar_vis/src/radar_det.py GitHub Actions / Autopep8src/perception/radar_object_detection/radar_vis/src/radar_det.py#L24-L30
|
||
node.destroy_node() | ||
rclpy.shutdown() | ||
|
||
if __name__ == '__main__': | ||
main() |