123456789101112131415161718192021222324252627282930313233343536373839 |
- <launch>
- <!-- 使用仿真时间, 如果是实际的小车, 设置成 false -->
- <param name="use_sim_time" value="true" />
- <!-- 地图服务: 加载和提供地图数据给其他节点使用 -->
- <node name="map_server" pkg="map_server" type="map_server" args="$(find slam_karto)/map/ros_yfm_0.02.yaml" output="screen">
- <param name="frame_id" value="map"/>
- </node>
- <!-- 启动代价地图 -->
- <node name="costmap_node" pkg="costmap_2d" type="costmap_2d_node" >
- <rosparam file="$(find costmap_2d)/launch/example_params.yaml" command="load" ns="costmap" />
- </node>
- <node name="laserScan2pointCloud" pkg="turn_on_robot" type="laserScan2pointCloud" output="screen" />
- <!-- 启动定位 -->
- <node name="location_beam_model" pkg="location_beam_model" type="lidar_loc" output="screen" />
- <!-- <node name="laser2base_link_TFpub" pkg="location_beam_model" type="laser2base_link_TFpub" /> -->
- <!-- 激光里程计 -->
- <node pkg="slam_hdl_graph" type="odom_laser_node" name="odom_laser" output="log" >
- <rosparam command="load" file="$(find slam_hdl_graph)/config/scan_match.yaml" />
- </node>
- <!-- <node pkg="hdl_graph_slam" type="map2odom_publisher.py" name="map2odom_publisher" output="screen"/> -->
- <!-- 启动rviz -->
- <node name="rviz" pkg="rviz" type="rviz" args="-d $(find slam_hdl_graph)/rviz/hdl_graph_slam.rviz"/>
-
- <!-- 启动数据回放 -->
- <node pkg="rosbag" type="play" name="player" output="screen" args="--clock /home/mj/agv_slam/point_cloud_data/ros_yfm.bag"/>
- <!-- 一些静态TF变换 -->
- <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_base_link" args="0 0 0.2 0 0 0 base_footprint base_link 100" output="screen" /> <!-- 100 是发布频率 -->
- <node pkg="tf" type="static_transform_publisher" name="base_link_to_laser" args="0 0 0 0 0 0 base_link laser 100" output="screen" />
- <node name="odom2base" pkg="location_beam_model" type="odom2base" output="screen" />
- </launch>
|