mirror of
https://git.ti.com/git/mmwave_radar/mmwave_ti_ros.git
synced 2026-05-21 01:12:08 +00:00
Modified launch file for radar driver on J7. Added launch file for multiple radar case
This commit is contained in:
@@ -7,26 +7,31 @@
|
||||
<launch>
|
||||
|
||||
<!-- Input arguments -->
|
||||
<arg name="device" value="6843" doc="TI mmWave sensor device type [1443, 1642, 6843]"/>
|
||||
<arg name="device_type" value="6843" doc="TI mmWave sensor device type [1443, 1642, 6843]"/>
|
||||
<arg name="config" value="3d" doc="TI mmWave sensor device configuration [3d_best_range_res (not supported by 1642 EVM), 2d_best_range_res]"/>
|
||||
<arg name="max_allowed_elevation_angle_deg" default="90" doc="Maximum allowed elevation angle in degrees for detected object data [0 > value >= 90]}"/>
|
||||
<arg name="max_allowed_azimuth_angle_deg" default="90" doc="Maximum allowed azimuth angle in degrees for detected object data [0 > value >= 90]}"/>
|
||||
<arg name="device_num" default="0"/>
|
||||
<arg name="com_user" default="/dev/ttyUSB0"/>
|
||||
<arg name="com_data" default="/dev/ttyUSB1"/>
|
||||
<arg name="node_start_delay" default="0"/>
|
||||
<arg name="tf_args" default="0 0 0 0 0 0" doc="Values to be used for tf transformation"/>
|
||||
|
||||
<!-- mmWave_Manager node -->
|
||||
<node pkg="ti_mmwave_rospkg" type="ti_mmwave_rospkg" name="ti_mmwave" ns="radar_0" output="screen">
|
||||
<param name="command_port" value="/dev/ttyUSB0" />
|
||||
<node pkg="ti_mmwave_rospkg" type="ti_mmwave_rospkg" name="ti_mmwave" ns="radar_$(arg device_num)" output="screen" launch-prefix="bash -c 'sleep $(arg node_start_delay); $0 $@'">
|
||||
<param name="command_port" value="$(arg com_user)" />
|
||||
<param name="command_rate" value="115200" />
|
||||
<param name="data_port" value="/dev/ttyUSB1" />
|
||||
<param name="data_port" value="$(arg com_data)" />
|
||||
<param name="data_rate" value="921600" />
|
||||
<param name="max_allowed_elevation_angle_deg" value="$(arg max_allowed_elevation_angle_deg)" />
|
||||
<param name="max_allowed_azimuth_angle_deg" value="$(arg max_allowed_azimuth_angle_deg)" />
|
||||
<param name="frame_id" value="ti_mmwave_0"/>
|
||||
<remap from="/ti_mmwave/radar_scan_pcl" to="/ti_mmwave/radar_scan_pcl_0"/>
|
||||
<param name="frame_id" value="ti_mmwave_$(arg device_num)"/>
|
||||
<remap from="/ti_mmwave/radar_scan_pcl" to="/ti_mmwave/radar_scan_pcl_$(arg device_num)"/>
|
||||
</node>
|
||||
|
||||
<!-- mmWaveQuickConfig node (terminates after configuring mmWave sensor) -->
|
||||
<node pkg="ti_mmwave_rospkg" type="mmWaveQuickConfig" name="ti_mmwave_config" ns="radar_0" args="$(find ti_mmwave_rospkg)/cfg/6843_3d.cfg" output="screen" />
|
||||
<node pkg="ti_mmwave_rospkg" type="mmWaveQuickConfig" name="ti_mmwave_config" ns="radar_$(arg device_num)" args="$(find ti_mmwave_rospkg)/cfg/6843_3d.cfg" output="screen" launch-prefix="bash -c 'sleep $(arg node_start_delay); $0 $@'"/>
|
||||
|
||||
<node pkg="tf" type="static_transform_publisher" name="radar_baselink_0" args="0 0 0 0 0 0 ti_mmwave_pcl ti_mmwave_0 100"/>
|
||||
<node pkg="tf" type="static_transform_publisher" name="radar_baselink_$(arg device_num)" args="$(arg tf_args) ti_mmwave_pcl ti_mmwave_$(arg device_num) 100" launch-prefix="bash -c 'sleep $(arg node_start_delay); $0 $@'"/>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -0,0 +1,34 @@
|
||||
<!--
|
||||
This file will launch the mmWave sensor node and configure a TI mmWave 6843 sensor using a 3D config. This launch file is intended
|
||||
to be used to launch the mmWave sensor node on TI's TDA4VM Jacinto Processors, as such a separate command must be used to launch rViz
|
||||
for visualization on a PC.
|
||||
-->
|
||||
|
||||
<launch>
|
||||
|
||||
<include file="$(find ti_mmwave_rospkg)/launch/6843_3d_TDA4VM.launch">
|
||||
<arg name="device_num" value="0" />
|
||||
<arg name="tf_args" value="0 0 0 0 0 0" />
|
||||
<arg name="com_user" value="/dev/ttyUSB0"/>
|
||||
<arg name="com_data" value="/dev/ttyUSB1"/>
|
||||
</include>
|
||||
|
||||
<include file="$(find ti_mmwave_rospkg)/launch/6843_3d_TDA4VM.launch">
|
||||
<arg name="device_num" value="1" />
|
||||
<arg name="tf_args" value="5 5 0 0 0 0" />
|
||||
<arg name="com_user" value="/dev/ttyUSB2"/>
|
||||
<arg name="com_data" value="/dev/ttyUSB3"/>
|
||||
<arg name="node_start_delay" value="20"/>
|
||||
</include>
|
||||
|
||||
<!--
|
||||
<include file="$(find ti_mmwave_rospkg)/launch/6843_3d_TDA4VM.launch">
|
||||
<arg name="tf_args" value="-5 5 0 0 0 0 ti_mmwave_pcl ti_mmwave_2 100" />
|
||||
</include>
|
||||
|
||||
<include file="$(find ti_mmwave_rospkg)/launch/6843_3d_TDA4VM.launch">
|
||||
<arg name="tf_args" value="0 10 0 0 0 0 ti_mmwave_pcl ti_mmwave_3 100" />
|
||||
</include>
|
||||
-->
|
||||
|
||||
</launch>
|
||||
Reference in New Issue
Block a user