Skip to content

Commit

Permalink
feat: add radar feature
Browse files Browse the repository at this point in the history
Signed-off-by: yoshiri <[email protected]>
  • Loading branch information
YoshiRi committed Mar 21, 2024
1 parent 56f77a5 commit 8ee46d4
Show file tree
Hide file tree
Showing 2 changed files with 73 additions and 6 deletions.
6 changes: 6 additions & 0 deletions aip_xx1_launch/config/radar_simple_object_merger.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
/**:
ros__parameters:
update_rate_hz: 20.0
new_frame_id: "base_link"
timeout_threshold: 1.0
input_topics: ["/sensing/radar/front_center/detected_objects", "/sensing/radar/front_left/detected_objects", "/sensing/radar/rear_left/detected_objects", "/sensing/radar/rear_center/detected_objects", "/sensing/radar/rear_right/detected_objects", "/sensing/radar/front_right/detected_objects"]
73 changes: 67 additions & 6 deletions aip_xx1_launch/launch/radar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<let name="odometry_topic" value="/sensing/vehicle_velocity_converter/twist_with_covariance"/>
<let name="acceleration_topic" value="/localization/acceleration"/>
<let name="steering_angle_topic" value="/vehicle/status/steering_status_scalar"/>
<arg name="radar_tracks_msgs_converter_param_path" default="$(find-pkg-share common_sensor_launch)/config/radar_tracks_msgs_converter.param.yaml"/>

<group>
<push-ros-namespace namespace="radar"/>
Expand All @@ -14,7 +15,7 @@

<group>
<push-ros-namespace namespace="front_center"/>
<include file="$(find-pkg-share nebula_ros)/launch/continental_launch_all_hw.xml">
<include file="$(find-pkg-share nebula_ros)/launch/continental_launch_all_hw.xml" if="$(var launch_driver)">

<arg name="odometry_topic" value="$(var odometry_topic)"/>
<arg name="acceleration_topic" value="$(var acceleration_topic)"/>
Expand All @@ -33,11 +34,20 @@

<arg name="new_plug_orientation" value="0"/>
</include>

<include file="$(find-pkg-share radar_tracks_msgs_converter)/launch/radar_tracks_msgs_converter.launch.xml">
<arg name="input/radar_objects" value="objects_raw"/>
<arg name="input/odometry" value="$(var odometry_topic)"/>
<arg name="output/radar_detected_objects" value="detected_objects"/>
<arg name="output/radar_tracked_objects" value="tracked_objects"/>
<arg name="use_twist_compensation" value="false"/>
<arg name="param_path" value="$(var radar_tracks_msgs_converter_param_path)"/>
</include>
</group>

<group>
<push-ros-namespace namespace="front_left"/>
<include file="$(find-pkg-share nebula_ros)/launch/continental_launch_all_hw.xml">
<include file="$(find-pkg-share nebula_ros)/launch/continental_launch_all_hw.xml" if="$(var launch_driver)">

<arg name="odometry_topic" value="$(var odometry_topic)"/>
<arg name="acceleration_topic" value="$(var acceleration_topic)"/>
Expand All @@ -56,11 +66,20 @@

<arg name="new_plug_orientation" value="0"/>
</include>

<include file="$(find-pkg-share radar_tracks_msgs_converter)/launch/radar_tracks_msgs_converter.launch.xml">
<arg name="input/radar_objects" value="objects_raw"/>
<arg name="input/odometry" value="$(var odometry_topic)"/>
<arg name="output/radar_detected_objects" value="detected_objects"/>
<arg name="output/radar_tracked_objects" value="tracked_objects"/>
<arg name="use_twist_compensation" value="false"/>
<arg name="param_path" value="$(var radar_tracks_msgs_converter_param_path)"/>
</include>
</group>

<group>
<push-ros-namespace namespace="front_right"/>
<include file="$(find-pkg-share nebula_ros)/launch/continental_launch_all_hw.xml">
<include file="$(find-pkg-share nebula_ros)/launch/continental_launch_all_hw.xml" if="$(var launch_driver)">

<arg name="odometry_topic" value="$(var odometry_topic)"/>
<arg name="acceleration_topic" value="$(var acceleration_topic)"/>
Expand All @@ -79,11 +98,20 @@

<arg name="new_plug_orientation" value="0"/>
</include>

<include file="$(find-pkg-share radar_tracks_msgs_converter)/launch/radar_tracks_msgs_converter.launch.xml">
<arg name="input/radar_objects" value="objects_raw"/>
<arg name="input/odometry" value="$(var odometry_topic)"/>
<arg name="output/radar_detected_objects" value="detected_objects"/>
<arg name="output/radar_tracked_objects" value="tracked_objects"/>
<arg name="use_twist_compensation" value="false"/>
<arg name="param_path" value="$(var radar_tracks_msgs_converter_param_path)"/>
</include>
</group>

<group>
<push-ros-namespace namespace="rear_center"/>
<include file="$(find-pkg-share nebula_ros)/launch/continental_launch_all_hw.xml">
<include file="$(find-pkg-share nebula_ros)/launch/continental_launch_all_hw.xml" if="$(var launch_driver)">

<arg name="odometry_topic" value="$(var odometry_topic)"/>
<arg name="acceleration_topic" value="$(var acceleration_topic)"/>
Expand All @@ -102,11 +130,20 @@

<arg name="new_plug_orientation" value="0"/>
</include>

<include file="$(find-pkg-share radar_tracks_msgs_converter)/launch/radar_tracks_msgs_converter.launch.xml">
<arg name="input/radar_objects" value="objects_raw"/>
<arg name="input/odometry" value="$(var odometry_topic)"/>
<arg name="output/radar_detected_objects" value="detected_objects"/>
<arg name="output/radar_tracked_objects" value="tracked_objects"/>
<arg name="use_twist_compensation" value="false"/>
<arg name="param_path" value="$(var radar_tracks_msgs_converter_param_path)"/>
</include>
</group>

<group>
<push-ros-namespace namespace="rear_left"/>
<include file="$(find-pkg-share nebula_ros)/launch/continental_launch_all_hw.xml">
<include file="$(find-pkg-share nebula_ros)/launch/continental_launch_all_hw.xml" if="$(var launch_driver)">

<arg name="odometry_topic" value="$(var odometry_topic)"/>
<arg name="acceleration_topic" value="$(var acceleration_topic)"/>
Expand All @@ -125,11 +162,20 @@

<arg name="new_plug_orientation" value="0"/>
</include>

<include file="$(find-pkg-share radar_tracks_msgs_converter)/launch/radar_tracks_msgs_converter.launch.xml">
<arg name="input/radar_objects" value="objects_raw"/>
<arg name="input/odometry" value="$(var odometry_topic)"/>
<arg name="output/radar_detected_objects" value="detected_objects"/>
<arg name="output/radar_tracked_objects" value="tracked_objects"/>
<arg name="use_twist_compensation" value="false"/>
<arg name="param_path" value="$(var radar_tracks_msgs_converter_param_path)"/>
</include>
</group>

<group>
<push-ros-namespace namespace="rear_right"/>
<include file="$(find-pkg-share nebula_ros)/launch/continental_launch_all_hw.xml">
<include file="$(find-pkg-share nebula_ros)/launch/continental_launch_all_hw.xml" if="$(var launch_driver)">

<arg name="odometry_topic" value="$(var odometry_topic)"/>
<arg name="acceleration_topic" value="$(var acceleration_topic)"/>
Expand All @@ -148,6 +194,21 @@

<arg name="new_plug_orientation" value="0"/>
</include>

<include file="$(find-pkg-share radar_tracks_msgs_converter)/launch/radar_tracks_msgs_converter.launch.xml">
<arg name="input/radar_objects" value="objects_raw"/>
<arg name="input/odometry" value="$(var odometry_topic)"/>
<arg name="output/radar_detected_objects" value="detected_objects"/>
<arg name="output/radar_tracked_objects" value="tracked_objects"/>
<arg name="param_path" value="$(var radar_tracks_msgs_converter_param_path)"/>
</include>
</group>

<!-- merge radar objects -->
<let name="merger_param_path" value="$(find-pkg-share aip_xx1_launch)/config/radar_simple_object_merger.param.yaml"/>
<node pkg="simple_object_merger" exec="simple_object_merger_node" name="simple_object_merger" output="screen">
<remap from="~/output/objects" to="detected_objects"/>
<param from="$(var merger_param_path)"/>
</node>
</group>
</launch>

0 comments on commit 8ee46d4

Please sign in to comment.