mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
relocated launch files
This commit is contained in:
52
scout_bringup/launch/scout_nav_2d.launch
Normal file
52
scout_bringup/launch/scout_nav_2d.launch
Normal file
@@ -0,0 +1,52 @@
|
||||
<launch>
|
||||
<node name="scout_base_node" pkg="scout_base" type="scout_base_node" output="screen">
|
||||
<param name="port_name" type="string" value="can0" />
|
||||
|
||||
<param name="odom_frame" type="string" value="odom" />
|
||||
<param name="base_frame" type="string" value="base_link" />
|
||||
|
||||
<param name="simulated_robot" type="bool" value="false" />
|
||||
</node>
|
||||
|
||||
<node name="sensor_hub_raw_imu" pkg="scout_base" type="imu_broadcast_node" output="screen"/>
|
||||
<include file="$(find scout_base)/launch/sensor_rslidar16.launch" />
|
||||
|
||||
<!--
|
||||
<include file="$(find scout_base)/launch/sensor_d435i.launch" />
|
||||
-->
|
||||
|
||||
<param name="robot_description" textfile="$(find scout_base)/urdf/agilex_scout.urdf" />
|
||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
|
||||
|
||||
<!--
|
||||
<node pkg="tf2_ros" type="static_transform_publisher" name="lidar3d_tf_broadcaster" args="0.25 0 0.4 0 0 0 1 base_link rslidar" />
|
||||
<node pkg="tf2_ros" type="static_transform_publisher" name="imu_tf_broadcaster" args="0.0 0 0.0 0 0 0 1 base_link imu" />
|
||||
-->
|
||||
|
||||
<node name="pointcloud_to_laserscan" pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan_node">
|
||||
<remap from="cloud_in" to="/rslidar_points"/>
|
||||
<rosparam>
|
||||
transform_tolerance: 0.01
|
||||
min_height: 0.2
|
||||
max_height: 0.5
|
||||
|
||||
angle_min: -3.14
|
||||
angle_max: 3.14
|
||||
angle_increment: 0.01256
|
||||
scan_time: 0.1
|
||||
range_min: 0.2
|
||||
range_max: 60.0
|
||||
use_inf: true
|
||||
|
||||
#concurrency_level affects number of pc queued for processing and the number of threadsused
|
||||
# 0: Detect number of cores
|
||||
# 1: Single threaded
|
||||
# 2: inf : Parallelism level
|
||||
concurrency_level: 1
|
||||
</rosparam>
|
||||
</node>
|
||||
|
||||
<!-- <param name="robot_description" textfile="$(find scout_base)/model/agilex_scout.urdf" />
|
||||
<param name="robot_description" command="$(find xacro)/xacro '$(find scout_base)/model/scout.urdf.xacro'" />
|
||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" /> -->
|
||||
</launch>
|
||||
Reference in New Issue
Block a user