diff --git a/source/conf.json b/source/conf.json
index c51400f..5e17ecf 100644
--- a/source/conf.json
+++ b/source/conf.json
@@ -210,6 +210,31 @@
}
]
},
+ {
+ "name": "二次开发",
+ "items":[
+ {
+ "name": "AutolaborOS",
+ "uri": "version_two/development/OSintro"
+ },
+ {
+ "name": "激光SLAM",
+ "uri": "version_two/development/slamintro"
+ },
+ {
+ "name": "激光SLAM-多点导航",
+ "uri": "version_two/development/multiGoalintro"
+ },
+ {
+ "name": "视觉SLAM/VSLAM",
+ "uri": "version_two/development/vslamintro"
+ },
+ {
+ "name": "定位循迹",
+ "uri": "version_two/development/locationintro"
+ }
+ ]
+ },
{
"name": "常见问题",
"items":[
diff --git a/source/version_two/development/OSintro.md b/source/version_two/development/OSintro.md
new file mode 100644
index 0000000..0e08b83
--- /dev/null
+++ b/source/version_two/development/OSintro.md
@@ -0,0 +1,264 @@
+# AutolaborOS
+
+## AutolaborOS 是什么
+
+AutolaborOS 由 Autolabor 推出的免费开源机器人操作系统,基于 ubuntu18.04 与 ROS Melodic 开发而成,包含 ROS Melodic 、常用 ROS包(Cartographer、Gmapping、Navigation ···),机器人底盘与传感器驱动包,机器人仿真应用,以及激光SLAM导航、自动巡迹导航应用等。
+
+使用 AutolaborOS 调试机器人,你甚至都不用安装在电脑上,U盘启动,随身携带,即插即用。
+
+## 目的
+
+为解决繁琐的 ROS 环境安装问题,节省时间成本,降低技术壁垒。使用该系统学习ROS、开发机器人、实现自己的算法,做一些有趣的事情。
+
+## AutolaborOS 能实现哪些功能
+
+AutolaborOS 秉持小而实用的原则,对原生的Ubuntu系统的功能模块进行了精简,在原有的基础上增加了ROS开发中使用到的常见功能包。
+
+既保证了简洁性,又增加了实用性。按需构建,有非常良好的可扩展性。
+
+现AutolaborOS已有的功能:
+
+* 2D/3D SLAM 建图导航(单目标/多目标)
+* 自动循迹
+* 多车跟随(模拟器)
+* 模拟器
+
+## 目录说明
+
+注:以下内容基于AutolaborOS 2.2.4
+
+```
+catkin_ws
+├── script //执行脚本
+├── src //源码
+
+catkin_ws/src/driver/
+├── car
+│ ├── autolabor_canbus_driver //PM1底盘驱动
+│ └── autolabor_pro1_driver //AP1底盘驱动
+├── depth_camera
+│ ├── iai_kinect2-master //kinect V2 相机驱动
+│ └── pico_zense_driver //Vzense DCAM710 相机驱动
+├── imu
+│ ├── ah100b //ah100b,ah200c 惯导驱动
+│ ├── rviz_imu_plugin //rviz 惯导可视化插件,显示惯导图像
+│ └── tl740d //tl740d 转角仪驱动
+├── joystick
+│ └── joystick_drivers // 罗技F710 遥控手柄驱动
+├── lidar
+│ ├── rplidar_ros //思岚A2 雷达驱动
+│ ├── rslidar //速腾RS16 雷达驱动
+│ ├── urg_node //北洋Hokuyo UST-10LX 雷达驱动
+│ └── wr_fslidar // 砝石FS-D10 雷达驱动
+└── location
+ └── marvelmind // marvelmind 定位标签驱动
+
+catkin_ws/src/launch/
+├── autolabor_navigation_launch //导航launch
+│ ├── launch
+│ │ ├── real_environment //实车launch
+│ │ │ ├── first_generation_base.launch //单雷达版本-传感器驱动
+│ │ │ ├── first_generation_mapping.launch //单雷达版本-建图
+│ │ │ ├── first_generation_navigation.launch //单雷达版本-导航
+│ │ │ ├── second_generation_advanced_base.launch //双雷达版本-传感器驱动(含定位标签)
+│ │ │ ├── second_generation_basic_base.launch //双雷达版本-传感器驱动
+│ │ │ ├── second_generation_mapping.launch //双雷达版本-建图
+│ │ │ ├── second_generation_multigoal_navigation.launch //双雷达版本-多点导航
+│ │ │ ├── second_generation_navigation.launch //双雷达版本-导航
+│ │ │ ├── second_generation_tracking.launch //双雷达版本-循迹
+│ │ │ ├── third_generation_base.launch //多线雷达版本-传感器驱动
+│ │ │ ├── third_generation_cartographer_3d.launch //多线雷达版本-建图
+│ │ │ └── third_generation_navigation_3d.launch //多线雷达版本-导航
+│ │ └── simulated_environment //模拟器launch
+│ │ ├── common_stage_simulation.launch //模拟场景地图
+│ │ ├── first_generation_base_simulation.launch
+│ │ ├── first_generation_mapping_simulation.launch
+│ │ ├── first_generation_navigation_simulation.launch
+│ │ ├── second_generation_advanced_base_simulation.launch
+│ │ ├── second_generation_basic_base_simulation.launch
+│ │ ├── second_generation_driver_simulation.launch
+│ │ ├── second_generation_mapping_simulation.launch
+│ │ ├── second_generation_multicar_following_simulation.launch //多车跟随
+│ │ ├── second_generation_multicar_navigation_simulation.launch //多车导航
+│ │ ├── second_generation_multigoal_navigation_simulation.launch //多目标导航
+│ │ ├── second_generation_navigation_simulation.launch
+│ │ └── second_generation_tracking_simulation.launch
+│ ├── map //建图保存的地图文件
+│ │ ├── map_3d.pbstream //3d slam 地图文件,用于定位,不可修改(保存地图后生成)
+│ │ ├── map_3d.pgm //3d slam 地图文件,用于导航,可修改(保存地图后生成)
+│ │ ├── map_3d.yaml //map_3d.pgm 的解释文件(保存地图后生成)
+│ │ ├── map.pbstream //2d slam 地图文件,用于定位导航,不可修改
+│ │ ├── map_simulation.pbstream //模拟器地图文件
+│ │ ├── simulation_stage.png //模拟器环境地图
+│ │ └── simulation_stage.yaml //simulation_stage.png 的解释文件
+│ ├── params //配置文件
+│ │ ├── cartographer
+│ │ │ ├── first_generation_location.lua //单雷达版本-定位
+│ │ │ ├── first_generation_mapping.lua //单雷达版本-建图
+│ │ │ ├── map_builder.lua //cartographer 配置文件
+│ │ │ ├── map_builder_server.lua //cartographer 配置文件
+│ │ │ ├── pose_graph.lua //cartographer 配置文件
+│ │ │ ├── second_generation_location.lua //双雷达版本-定位
+│ │ │ ├── second_generation_mapping.lua //双雷达版本-建图
+│ │ │ ├── second_generation_multicar_location.lua //双雷达版本-多车定位(模拟器)
+│ │ │ ├── third_generation_location.lua //多线雷达版本-定位
+│ │ │ ├── third_generation_mapping.lua //多线雷达版本-建图
+│ │ │ ├── trajectory_builder_2d.lua //cartographer 配置文件
+│ │ │ ├── trajectory_builder_3d.lua //cartographer 配置文件
+│ │ │ └── trajectory_builder.lua //cartographer 配置文件
+│ │ ├── common
+│ │ │ ├── back_lidar_config.yaml //后雷达过滤配置文件
+│ │ │ └── front_lidar_config.yaml //前雷达过滤配置文件
+│ │ └── navigation
+│ │ ├── costmap //代价地图配置文件
+│ │ │ ├── 3d_global_costmap_params.yaml //3d slam 全局代价地图
+│ │ │ ├── 3d_local_costmap_params.yaml //3d slam 局部代价地图
+│ │ │ ├── one_laser_global_costmap_params.yaml //单雷达版本-全局代价地图
+│ │ │ ├── one_laser_local_costmap_params.yaml //单雷达版本-局部代价地图
+│ │ │ ├── two_laser_global_costmap_params_for_tracking.yaml //双雷达版本-循迹-全局代价地图
+│ │ │ ├── two_laser_global_costmap_params.yaml //双雷达版本-全局代价地图
+│ │ │ └── two_laser_local_costmap_params.yaml //双雷达版本-局部代价地图
+│ │ ├── global_planer //全局规划配置文件
+│ │ │ ├── global_planner_params.yaml //用于导航
+│ │ │ ├── navfn_params.yaml //用于多车(模拟器)
+│ │ │ └── tracking_planner_params.yaml //用于循迹
+│ │ ├── local_planer //局部规划配置文件
+│ │ │ ├── navigation_teb_local_planner_params.yaml //用于导航
+│ │ │ └── tracking_teb_local_planner_params.yaml //用于循迹
+│ │ └── move_base //ROS Navigation 配置文件
+│ │ ├── navigation_move_base.yaml //用于导航
+│ │ └── tracking_move_base.yaml //用于循迹
+│ └── rviz //rviz配置文件
+│ ├── 3d_mapping.rviz //3d slam-建图
+│ ├── 3d_navigation.rviz //3d slam-导航
+│ ├── first_generation_create_map.rviz //单雷达版本-建图
+│ ├── first_generation_navigation.rviz //单雷达版本-导航
+│ ├── second_generation_create_map.rviz //双雷达版本-建图
+│ ├── second_generation_multicar_navigation.rviz //双雷达版本-多车导航(模拟器)
+│ ├── second_generation_multigoal_navigation.rviz //双雷达版本-多点导航
+│ ├── second_generation_navigation.rviz //双雷达版本-导航
+│ └── second_generation_tracking.rviz //双雷达版本-循迹
+└── autolabor_test_launch //测试
+ ├── launch
+ │ ├── car_test.launch //键盘遥控
+ │ ├── fslidar_test.launch //砝石FS-D10双雷达测试
+ │ ├── imu_test.launch //惯导测试
+ │ ├── kinect2_test.launch //kinect V2测试
+ │ ├── robot_calibration.launch //AP1标定
+ │ └── tag_test.launch //定位标签测试
+ └── rviz //rviz配置文件
+ ├── car.rviz //键盘遥控
+ ├── fslidar.rviz //砝石FS-D10双雷达测试
+ ├── robot_calibration.rviz //AP1标定
+ └── tag.rviz //定位标签测试
+
+
+catkin_ws/src/mapping/ //建图源码
+├── cartographer //cartographer算法源码
+├── cartographer_ros//cartographer算法源码-适配ROS
+├── openslam_gmapping //gmapping算法源码
+└── slam_gmapping //gmapping-适配ROS
+
+
+catkin_ws/src/navigation/ //ROS Navigation 源码
+├── amcl //粒子滤波定位
+├── base_local_planner //局部规划
+├── carrot_planner //全局规划
+├── clear_costmap_recovery //恢复行为
+├── costmap_2d //障碍物地图
+├── dwa_local_planner //dwa局部规划
+├── fake_localization //OS中未使用
+├── global_planner //全局规划
+├── location_fusion //定位融合(定位标签+里程计)
+├── loop_path_planner //循迹全局规划
+├── map_server //地图服务
+├── move_base //movebase
+├── move_slow_and_clear //恢复行为
+├── multi_car_goal //多车-前车向后车发目标(模拟器)
+├── nav_core //导航核心接口
+├── navfn //全局规划
+├── navigation //ROS Navigation元
+├── path_rviz_plugin //循迹rviz插件,功能按钮组
+├── path_server //用于循迹中录制路线
+│ ├── path_data
+│ │ ├── default_path.path //循迹中保存的路径数据
+├── record_path_planner //循迹全局规划
+├── rotate_recovery //恢复行为
+├── teb_local_planner //局部规划
+└── voxel_grid //用于障碍物地图
+
+
+catkin_ws/src/simulation/ //模拟器
+├── autolabor_description //机器人模型
+│ ├── launch
+│ │ ├── display_autolabor_mini.launch
+│ │ └── display_autolabor_pro1.launch
+│ ├── meshes
+│ │ ├── autolabor_mini.stl
+│ │ ├── pro1_body_color.dae //AP1模型文件-主体
+│ │ └── pro1_wheel_color.dae //AP1模型文件-轮子
+│ ├── rviz
+│ │ └── urdf.rviz
+│ └── urdf
+│ ├── autolabor_mini.urdf
+│ ├── first_generation_model.xacro //单雷达版本-机器人描述(类似urdf)
+│ ├── second_generation_model.xacro //双雷达版本-机器人描述(类似urdf)
+│ └── third_generation_model.xacro //多线雷达版本-机器人描述(类似urdf)
+├── autolabor_simulation_base //机器人底盘模拟
+├── autolabor_simulation_lidar //雷达模拟
+├── autolabor_simulation_location //定位标签模拟
+├── autolabor_simulation_object //运动物体模拟
+└── autolabor_simulation_stage //场景模拟
+
+
+catkin_ws/src/tool/
+├── autolabor_keyboard_control //键盘控制(必须要插实体键盘)
+├── cartographer_initialpose //cartographer初始化定位
+├── image_pipeline //图像处理,OS中未使用
+├── joy_to_twist //手柄转速度驱动包
+├── navi_multi_goals_pub_rviz_plugin //rviz插件-多点导航
+├── rviz_autolabor_calibration //rviz插件-AP1标定
+├── rviz_keyboard_twist //rviz插件-键盘控制
+└── rviz_navigation_tools //rviz插件-多车导航工具,切换机器人(模拟器)
+
+
+
+script //执行脚本
+├── 3d_suit //多线雷达版本
+│ ├── create_map_start
+│ ├── create_map_stop
+│ ├── navigation_start
+│ └── navigation_stop
+├── box_suit //单雷达版本
+│ ├── create_map_start
+│ ├── create_map_stop
+│ ├── navigation_start
+│ └── navigation_stop
+├── common
+│ ├── add_keyboard_udev //用于键盘控制,加键盘权限
+│ └── rebuild //工作空间编译脚本
+├── simulation //模拟器
+│ ├── create_map_start
+│ ├── create_map_stop
+│ ├── navigation_start
+│ ├── navigation_stop
+│ ├── tracking_start
+│ └── tracking_stop
+├── test //测试
+│ ├── car_test
+│ ├── fslidar_test
+│ ├── imu_test
+│ ├── kinect2_test
+│ ├── pico_test
+│ ├── robot_calibration
+│ ├── rplidar_test
+│ ├── rslidar_test
+│ └── tag_test
+└── track_suit //双雷达版本
+ ├── create_map_start
+ ├── create_map_stop
+ ├── navigation_start
+ ├── navigation_stop
+ ├── tracking_start //开始循迹
+ └── tracking_stop //停止循迹
+```
\ No newline at end of file
diff --git a/source/version_two/development/imgs/slamintro1.jpg b/source/version_two/development/imgs/slamintro1.jpg
new file mode 100644
index 0000000..a975948
Binary files /dev/null and b/source/version_two/development/imgs/slamintro1.jpg differ
diff --git a/source/version_two/development/imgs/slamintro2.png b/source/version_two/development/imgs/slamintro2.png
new file mode 100644
index 0000000..98068f3
Binary files /dev/null and b/source/version_two/development/imgs/slamintro2.png differ
diff --git a/source/version_two/development/imgs/slamintro3.png b/source/version_two/development/imgs/slamintro3.png
new file mode 100644
index 0000000..30b64ee
Binary files /dev/null and b/source/version_two/development/imgs/slamintro3.png differ
diff --git a/source/version_two/development/imgs/slamintro4.gif b/source/version_two/development/imgs/slamintro4.gif
new file mode 100644
index 0000000..f6df65a
Binary files /dev/null and b/source/version_two/development/imgs/slamintro4.gif differ
diff --git a/source/version_two/development/imgs/software_intro_1.jpg b/source/version_two/development/imgs/software_intro_1.jpg
new file mode 100644
index 0000000..995c016
Binary files /dev/null and b/source/version_two/development/imgs/software_intro_1.jpg differ
diff --git a/source/version_two/development/imgs/software_intro_2.jpg b/source/version_two/development/imgs/software_intro_2.jpg
new file mode 100644
index 0000000..9692ca5
Binary files /dev/null and b/source/version_two/development/imgs/software_intro_2.jpg differ
diff --git a/source/version_two/development/imgs/software_intro_3.jpg b/source/version_two/development/imgs/software_intro_3.jpg
new file mode 100644
index 0000000..f48806f
Binary files /dev/null and b/source/version_two/development/imgs/software_intro_3.jpg differ
diff --git a/source/version_two/development/imgs/software_intro_4.jpg b/source/version_two/development/imgs/software_intro_4.jpg
new file mode 100644
index 0000000..8e2e031
Binary files /dev/null and b/source/version_two/development/imgs/software_intro_4.jpg differ
diff --git a/source/version_two/development/imgs/software_intro_5.jpg b/source/version_two/development/imgs/software_intro_5.jpg
new file mode 100644
index 0000000..a77758d
Binary files /dev/null and b/source/version_two/development/imgs/software_intro_5.jpg differ
diff --git a/source/version_two/development/imgs/software_intro_6.png b/source/version_two/development/imgs/software_intro_6.png
new file mode 100644
index 0000000..b35ea86
Binary files /dev/null and b/source/version_two/development/imgs/software_intro_6.png differ
diff --git a/source/version_two/development/imgs/software_intro_7.png b/source/version_two/development/imgs/software_intro_7.png
new file mode 100644
index 0000000..e1b70c7
Binary files /dev/null and b/source/version_two/development/imgs/software_intro_7.png differ
diff --git a/source/version_two/development/imgs/software_intro_8.png b/source/version_two/development/imgs/software_intro_8.png
new file mode 100644
index 0000000..747f0e9
Binary files /dev/null and b/source/version_two/development/imgs/software_intro_8.png differ
diff --git a/source/version_two/development/locationintro.md b/source/version_two/development/locationintro.md
new file mode 100644
index 0000000..74b218b
--- /dev/null
+++ b/source/version_two/development/locationintro.md
@@ -0,0 +1,4 @@
+# 定位循迹
+
+## 目录
+
diff --git a/source/version_two/development/multiGoalintro.md b/source/version_two/development/multiGoalintro.md
new file mode 100644
index 0000000..3a15674
--- /dev/null
+++ b/source/version_two/development/multiGoalintro.md
@@ -0,0 +1,4 @@
+# 激光SLAM-多点导航
+
+## 目录
+
diff --git a/source/version_two/development/slamintro.md b/source/version_two/development/slamintro.md
new file mode 100644
index 0000000..c975e93
--- /dev/null
+++ b/source/version_two/development/slamintro.md
@@ -0,0 +1,246 @@
+# 激光SLAM
+
+## 目录
+
+* SLAM介绍
+* 基于激光SLAM的机器人自主导航
+* Autolabor Pro1 SLAM 导航功能详解
+ * 2D SLAM 实现原理
+ * 3D SLAM 实现原理
+
+
+## SLAM介绍
+
+**SLAM**,全称是 Simultaneous Localization and Mapping,同时定位与地图构建。
+
+SLAM 技术解决的是,我在哪里?(**定位**Localization )我周围是什么样?(**建图**Mapping)这两个问题。
+
+移动设备从未知环境中的某一点开始运动,根据传感器获取到的数据,即时计算获取传感器的位置并绘制周围的环境。
+
+![](imgs/slamintro1.jpg)
+
+SLAM 的应用很广泛,有扫地机器人、无人驾驶汽车、无人机,三维场景重建等。
+
+根据使用传感器不同,SLAM的可分为激光SLAM和视觉SLAM(VSLAM),本文介绍的是激光SLAM,对视觉SLAM相关知识感兴趣的可以[看这里]()。
+
+
+## 基于激光SLAM的机器人自主导航
+
+激光SLAM导航,指的是使用激光雷达采集的数据进行建图与定位(SLAM),并在构建的环境地图中自动导航(规划+控制)。
+
+![](imgs/slamintro2.png)
+
+地图构建完成后,给出目标点,根据当前位置信息与已知环境地图规划出可行走路径,控制机器人运动,最终达到目标点。
+
+![](imgs/slamintro3.png)
+
+以上只是简单概述了机器人导航的流程,但 SLAM 与 路径规划/Planning 都是很复杂的内容,在此不做过多的探讨。
+
+
+## Autolabor Pro1 SLAM 导航功能详解
+
+Autolabor SLAM 导航使用的是谷歌开源的 [Cartographer](https://github.com/googlecartographer/cartographer_ros),支持多平台和传感器配置,提供2D和3D实时同步定位与建图,使用回环检测消除建图产生的累积误差,建图效果更好,在国内外众多机器人应用上得到了广泛使用。
+
+> Cartographer is a system that provides real-time simultaneous localization and mapping (SLAM) in 2D and 3D across multiple platforms and sensor configurations.
+
+
+![](imgs/slamintro4.gif)
+
+
+
+### 2D SLAM 实现原理
+
+
+#### 传感器介绍
+
+2D SLAM 用到的传感器有:
+
+
+* 单线激光雷达x2,安装在AP1前后底部
+* 编码器/轮速里程计x2,安装在车体内部前侧
+
+
+![](imgs/software_intro_6.png)
+
+#### 2D SLAM 建图
+
+![](imgs/software_intro_1.jpg)
+
+| 步骤 | 输入数据 | 操作 | 输出数据 | 使用ROS包 |
+|--|--|--|--|--|
+|1 | 左编码器数据 右编码器数据 | 使用运动模型计算编码器数据,得到符合ROS标准的里程计数据| 里程计数据| [autolabor_pro_driver](http://www.autolabor.com.cn/usedoc/ap1/sendCommand?hmsr=csdn)|
+|2 | 前雷达数据 后雷达数据 | 过滤并融合前后激光雷达采集的数据,得到机器人周围环境点云数据| 雷达点云数据 | [cartographer_ros](https://google-cartographer-ros.readthedocs.io/en/latest/) [laser_filters](http://wiki.ros.org/laser_filters) |
+|3 | 里程计数据 点云数据 | 点云匹配| 相对位姿数据 子地图数据 | [cartographer_ros](https://google-cartographer-ros.readthedocs.io/en/latest/)|
+|4 | 相对位姿数据 子地图数据 | 回环检测,得到子地图拼接的全地图数据 | 地图数据 | [cartographer_ros](https://google-cartographer-ros.readthedocs.io/en/latest/)|
+
+
+Cartographer 2D 建图 launch配置示例
+
+```
+
+
+
+
+
+
+
+
+```
+
+#### 2D SLAM 导航
+
+![](imgs/software_intro_2.jpg)
+
+| 步骤 | 输入数据 | 操作 | 输出数据 | 使用ROS包 |
+|--|--|--|--|--|
+|1 | 左编码器数据 右编码器数据 | 使用运动模型计算编码器数据,得到符合ROS标准的里程计数据| 里程计数据| [autolabor_pro_driver](http://www.autolabor.com.cn/usedoc/ap1/sendCommand?hmsr=csdn)|
+|2|前雷达数据 后雷达数据 里程计数据 地图数据|将机器人的实时数据与已构建的地图进行匹配|当前机器人在环境中的位姿| [cartographer_ros](https://google-cartographer-ros.readthedocs.io/en/latest/)|
+|3| 目标机器人位姿| 给机器人制定一个目标点| |[move_base](http://wiki.ros.org/move_base/)|
+|4| 当前机器人位姿 地图数据 目标机器人位姿| 根据机器人当前位姿与地图数据,进行全局规划路线| 路径数据(初步预估导航路线) |[global_planner(dijkstra) ](http://wiki.ros.org/global_planner)|
+|5| 路径数据 地图数据 前雷达数据 后雷达数据 | 根据规划路径开始导航,进行过程中随着实际环境、障碍物变化,进行局部路径规划,实时避障| 局部路径规划 避障 |[costmap_2d ](http://wiki.ros.org/cost_map)[teb_local_planner](http://wiki.ros.org/teb_local_planner)|
+|6| 速度信息 /cmd_vel | 向底发送速度命令 | |[move_base](http://wiki.ros.org/move_base/)|
+
+说明:
+
+ 1. move_base, global_planner(dijkstra), costmap_2d 这些功能包(package)都从属于
+ Navigation 导航这个大的功能包集,teb_local_planner 是navigation包的一个插件。
+ 2. 机器人导航过程中,会按照周围环境、实时障碍物做调整不断规划调整路径,向底层发布指令,步骤五和六是一个多次的过程,并非一次就结束了。
+
+Cartographer 2D 导航 launch配置示例
+
+```
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+```
+
+
+
+### 3D SLAM 实现原理
+
+
+#### 传感器介绍
+
+3D SLAM 用到的传感器有:
+
+* 多线激光雷达,安装在AP1前后底部
+* 单线激光雷达x2,安装在AP1前后底部
+* 编码器/轮速里程计x2,安装在车体内部前侧
+* 惯导,安装在AP1车顶板上
+
+
+
+![](imgs/software_intro_7.png)
+
+#### 3D SLAM 建图
+
+![](imgs/software_intro_4.jpg)
+
+| 步骤 | 输入数据 | 操作 | 输出数据 | 使用ROS包 |
+|--|--|--|--|--|
+|1 | 左编码器数据 右编码器数据 | 使用运动模型计算编码器数据,得到符合ROS标准的里程计数据| 里程计数据| [autolabor_pro_driver](http://www.autolabor.com.cn/usedoc/ap1/sendCommand?hmsr=csdn)|
+|2 | 多线雷达数据 惯导数据 里程计数据 | 点云匹配| 相对位姿数据 子地图数据 | [cartographer_ros](https://google-cartographer-ros.readthedocs.io/en/latest/)|
+|3 | 相对位姿数据 子地图数据 | 回环检测,得到子地图拼接的全地图数据 | 地图数据 | [cartographer_ros](https://google-cartographer-ros.readthedocs.io/en/latest/)|
+
+
+
+Cartographer 3D 建图 launch配置示例
+
+```
+
+
+
+
+
+
+
+
+```
+
+#### 3D SLAM 导航
+
+![](imgs/software_intro_5.jpg)
+
+| 步骤 | 输入数据 | 操作 | 输出数据 | 使用ROS包 |
+|--|--|--|--|--|
+|1 | 左编码器数据 右编码器数据 | 使用运动模型计算编码器数据,得到符合ROS标准的里程计数据| 里程计数据| [autolabor_pro_driver](http://www.autolabor.com.cn/usedoc/ap1/sendCommand?hmsr=csdn)|
+|2|多线雷达数据 惯导数据 里程计数据 地图数据|将机器人的实时数据与已构建的地图进行匹配|当前机器人在环境中的位姿| [cartographer_ros](https://google-cartographer-ros.readthedocs.io/en/latest/)|
+|3| 目标机器人位姿| 给机器人制定一个目标点| |[move_base](http://wiki.ros.org/move_base/)|
+|4| 当前机器人位姿 地图数据 目标机器人位姿| 根据机器人当前位姿与地图数据,进行全局规划路线| 路径数据(初步预估导航路线) |[global_planner(dijkstra) ](http://wiki.ros.org/global_planner)|
+|5| 路径数据 地图数据 前雷达数据 后雷达数据 多线雷达数据 | 根据规划路径开始导航,进行过程中随着实际环境、障碍物变化,进行局部路径规划,实时避障| 局部路径规划 避障 |[costmap_2d ](http://wiki.ros.org/cost_map)[teb_local_planner](http://wiki.ros.org/teb_local_planner)|
+|6| 速度信息 /cmd_vel | 向底发送速度命令 | |[move_base](http://wiki.ros.org/move_base/)|
+
+说明:
+
+ 1. move_base, global_planner(dijkstra), costmap_2d 这些功能包(package)都从属于
+ Navigation 导航这个大的功能包集,teb_local_planner 是navigation包的一个插件。
+ 2. 机器人导航过程中,会按照周围环境、实时障碍物做调整不断规划调整路径,向底层发布指令,步骤五和六是一个多次的过程,并非一次就结束了。
+
+
+Cartographer 3D 导航 launch配置示例
+
+```
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+```
\ No newline at end of file
diff --git a/source/version_two/development/vslamintro.md b/source/version_two/development/vslamintro.md
new file mode 100644
index 0000000..762cca8
--- /dev/null
+++ b/source/version_two/development/vslamintro.md
@@ -0,0 +1,4 @@
+# 视觉SLAM
+
+## 目录
+
diff --git a/source/version_two/location/guide/advanced.md b/source/version_two/location/guide/advanced.md
new file mode 100644
index 0000000..04b29e0
--- /dev/null
+++ b/source/version_two/location/guide/advanced.md
@@ -0,0 +1,5 @@
+# 定位循迹 - 进阶使用
+
+## 地图拼接
+
+固定定位标签
\ No newline at end of file
diff --git a/source/version_two/location/guide/doc.md b/source/version_two/location/guide/doc.md
index 3c1f3cf..968c818 100644
--- a/source/version_two/location/guide/doc.md
+++ b/source/version_two/location/guide/doc.md
@@ -1,4 +1,4 @@
-# 定位循迹
+# 定位循迹 - 快速上手
注:实现功能需要定位系统。