58 lines
2.3 KiB
XML
Executable File
58 lines
2.3 KiB
XML
Executable File
<!--move2grab-->
|
||
<!--SPARK技术讨论与反馈群:8346256-->
|
||
<launch>
|
||
<!-- Arguments -->
|
||
<arg name="slam_methods" default="gmapping" doc="slam type [gmapping, cartographer, hector, karto, frontier_exploration]"/>
|
||
<arg name="configuration_basename" default="spark_lds_2d.lua"/>
|
||
<arg name="open_rviz" default="true"/>
|
||
<arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/>
|
||
<!-- 摄像机类型 -->
|
||
<arg name="camera_type_tel" default="astrapro" doc="camera type [astrapro, astra, d435...]"/>
|
||
|
||
<!--spark底盘驱动,机器人描述,底盘,相机-->
|
||
<include file="$(find spark_bringup)/launch/driver_bringup.launch">
|
||
<arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
|
||
<arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/>
|
||
</include>
|
||
|
||
|
||
<!--UARM机械臂-->
|
||
<include file="$(find swiftpro)/launch/pro_control_nomoveit.launch"/>
|
||
|
||
<!-- 3D sensor -->
|
||
<arg name="3d_sensor" default="3i_lidar"/>
|
||
<!-- 启动雷达 -->
|
||
<include file="$(find lidar_driver_transfer)/launch/$(arg lidar_type_tel).launch">
|
||
</include>
|
||
|
||
|
||
<!-- SLAM: Gmapping, Cartographer, Hector, Karto, Frontier_exploration-->
|
||
<include file="$(find spark_slam)/launch/spark_$(arg slam_methods).launch">
|
||
<arg name="configuration_basename" value="$(arg configuration_basename)"/>
|
||
</include>
|
||
|
||
<!-- Move base -->
|
||
<arg name="custom_param_file" default="$(find spark_navigation)/param/$(arg 3d_sensor)_costmap_params.yaml"/>
|
||
<include file="$(find spark_navigation)/launch/includes/move_base.launch.xml">
|
||
<arg name="custom_param_file" value="$(arg custom_param_file)"/>
|
||
</include>
|
||
|
||
|
||
<!-- rviz -->
|
||
<group if="$(arg open_rviz)">
|
||
<node pkg="rviz" type="rviz" name="rviz" required="true" args="-d $(find move2grasp)/rviz/spark_$(arg slam_methods)_$(arg camera_type_tel).rviz"/>
|
||
</group>
|
||
|
||
|
||
<node pkg="move2grasp" type="move.py" name="move" />
|
||
<group if="$(eval arg('camera_type_tel')=='d435')">
|
||
<node pkg="move2grasp" type="grasp_d435.py" name="grasp" output="screen">
|
||
<remap from="/camera/rgb/image_raw" to="/camera/color/image_raw" if="$(eval arg('camera_type_tel')=='d435')"/>
|
||
</node>
|
||
</group>
|
||
<group if="$(eval arg('camera_type_tel')=='astrapro')">
|
||
<node pkg="move2grasp" type="grasp_pro_new.py" name="grasp" />
|
||
</group>
|
||
|
||
</launch>
|