diff --git a/.DS_Store b/.DS_Store
index 73ca0e5..96d584c 100644
Binary files a/.DS_Store and b/.DS_Store differ
diff --git a/Readme.md b/Readme.md
index e701edc..c51b601 100644
--- a/Readme.md
+++ b/Readme.md
@@ -1 +1,7 @@
-本工程为M2文档
\ No newline at end of file
+# 本工程为M2文档
+## 目录
+### 产品概述
+### 产品参数
+### 控制方式
+### 串口协议
+### ROS驱动
diff --git a/abc.md b/abc.md
deleted file mode 100644
index 6ff255f..0000000
--- a/abc.md
+++ /dev/null
@@ -1 +0,0 @@
-@@@@@
\ No newline at end of file
diff --git a/底盘/.DS_Store b/底盘/.DS_Store
new file mode 100644
index 0000000..c8cba2f
Binary files /dev/null and b/底盘/.DS_Store differ
diff --git a/底盘/ChassisM2.md b/底盘/ChassisM2.md
new file mode 100644
index 0000000..3238def
--- /dev/null
+++ b/底盘/ChassisM2.md
@@ -0,0 +1,204 @@
+# Autolabor M2 ROS 驱动模块
+
+## 1. 介绍
+Autolabor ROS驱动模块包含**CANBus驱动**和**Autolabor M2底盘驱动**,其主要功能包括与Autolabor_CANbus模块通信,并通过线速度和角速度控制Autolabor M2底盘行驶。
+
+#### 特性
+
+- 可直接获取CANBus网络内数据,并通过CAN指令控制车辆
+ - 获取动力轮编码器原始数值(角速度)
+ - 获取转向轮编码器原始数值(角速度)
+ - 分别控制动力轮的转速(角速度)
+ - 控制转向轮的绝对转向角度
+- 可通过线速度与角速度控制移动底盘,无需单独控制前轮转向
+- 提供实时机器人底盘位置信息,方便闭环控制
+- 双动力轮电子差速控制,保证机器人在行驶过程中始终满足阿克曼原理
+- 根据前轮转向优化车辆运动速度,在保证车辆在行驶精度前提下,确保车辆行驶的流畅性
+
+## 2. 节点
+
+### 2.1 canbus_driver
+该节点提供与底层AutoCan的通讯,将CAN网络中的数据进行解析并发布至canbus_msg话题中,并开启canbus_server服务,提供其他节点调用,用以发送CAN指令到CAN网络中。
+
+该节点的结构如图所示:
+
+
+
+
+#### 2.1.1 订阅话题
+
+无
+
+#### 2.1.2 发布话题
+/canbus_msg ([autolabor_canbus_driver/CanBusMessage](doc/CanBusMessage.md))
+~~~
+将底层CAN网络中的数据发布在ROS话题中,提供其他节点读取
+~~~
+
+#### 2.1.3 服务
+/canbus_server ([autolabor_canbus_driver/CanBusService](doc/CanBusService.md))
+~~~
+提供其他节点调用,用于往底层CAN网络中发布指令
+~~~
+
+#### 2.1.4 参数
+~port_name (str, default: /dev/ttyUSB0)
+
+~~~
+CANBus串口端口名
+~~~
+
+~baud_rate (int, default: 115200)
+~~~
+CANBus串口波特率
+~~~
+
+~parse_rate (int, default: 100)
+~~~
+数据解析器从串口获取新数据的频率
+~~~
+
+### 2.2 M2_driver
+
+此节点主要用于接收用户发送的速度信息,控制转向轮转动,并根据后轮当前角度结合阿克曼模型优化求解动力轮的转动速度,控制移动底盘进行移动,同时根据动力轮编码器的反馈,输出轮速里程计信息。
+
+该节点结构如下:
+
+
+
+
+
+#### 2.2.1 订阅话题
+
+/cmd_vel ([geometry_msgs/Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html))
+
+```
+外部节点发送的速度信息
+```
+
+/canbus_msg ([autolabor_canbus_driver/CanBusMessage](doc/CanBusMessage.md))
+
+```
+由canbus_driver发送的底层CANBus消息,其中包含转向轮当前绝对编码器以及动力轮的编码器信息
+```
+
+#### 2.2.2 发布话题
+
+/odom ([nav_msgs/Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html))
+
+```
+根据动力轮以及转向轮的编码器信息,依据车辆运动模型,计算出的轮速里程计信息
+```
+
+/wheel_angle ([std_msgs/Float64](http://docs.ros.org/api/std_msgs/html/msg/Float64.html))
+
+```
+前阿克曼转向轮实时绝对转角,单位rad
+```
+
+#### 2.2.3 服务
+
+/reset_odom ([std_srvs::Empty](http://docs.ros.org/api/std_srvs/html/srv/Empty.html))
+
+~~~
+里程计清零,将里程计的原点放置在执行指令的位置
+~~~
+
+#### 2.2.4 参数
+
+~odom_frame (str, default: odom)
+
+```
+里程计坐标系名称
+```
+
+~base_frame (str, default: base_link)
+
+```
+移动底盘坐标系名称
+```
+
+~poller_rate_hz (int, default: 20)
+
+```
+查询底盘参数的频率,单位 Hz
+```
+
+~publish_tf (bool, default: true)
+
+```
+设置是否发布odom->base_link的TF转换
+```
+
+#### 2.2.5 TF转换信息
+
+odom -> base_link
+
+```
+提供车体坐标系与里程计坐标系间转换关系
+```
+
+## 3 ROS使用说明
+
+### 3.1 底盘连接
+
+将M2的串口线插入笔记本电脑或工控机,打开底盘电源和急停开关
+
+打开Terminal输入
+
+```
+ll /dev/ttyUSB*
+```
+查看是否有设备列表,如果没有设备,请检查底盘与电脑的连接情况,如果设备多于一个,请通过拔插其他传感器设备,确定底盘的对应的设备节点名,假设节点名为 /dev/ttyUSB0。
+
+### 3.2 源码编译与执行
+
+下载源码
+
+```
+mkdir ~/github_ws
+cd ~/github_ws
+git clone http://git.autolabor.com.cn/Autolabor/autolabor_m2_ros_driver.git
+```
+编译源码
+
+```
+cd m2_driver_ros/
+catkin_make
+```
+加载环境变量
+
+```
+source devel/setup.bash
+```
+修改launch文件参数
+
+```
+gedit src/autolabor_canbus_driver/launch/m2_driver.launch
+```
+定位
+```
+
+```
+将value值改为之前查看的车底盘的设备节点名,修改后保存并关闭
+
+执行launch文件
+
+```
+roslaunch autolabor_canbus_driver m2_driver.launch
+```
+如果成功执行到这一步,并且没有发现任何错误,则车底层驱动就已经启动完毕,这个时候只要启动相应的控制节点就可以控制车底盘行走了。
+
+### 3.3 控制向前直行
+
+打开一个terminal
+
+执行 rostopic list 查看有无/cmd_vel 话题
+
+如果有的话,执行:
+
+```
+ rostopic pub -r 10 /cmd_vel geometry_msgs/Twist -- '[1.0,0.0,0.0]' '[0.0,0.0,0]'
+```
+
+此时车轮会开始转动,如果想要停止的话,必须在执行命令的terminal中执行Ctrl+C,停止发送。
\ No newline at end of file
diff --git a/底盘/CustomAutocan.md b/底盘/CustomAutocan.md
new file mode 100644
index 0000000..0def465
--- /dev/null
+++ b/底盘/CustomAutocan.md
@@ -0,0 +1,168 @@
+# AutolaborM2串口通讯协议
+
+AutolaborM2采用串口通讯,通讯波特率为***115200***。通讯消息分为无数据域和有数据域两种类型。其中无数据域类型主要用于查询指令。
+
+串口连接成功后,能收到机器人上报的里程计消息和车辆速度、转角消息,可依此作为机器人连接的判断。当前车辆上报得到左轮轮速和右轮轮速是直接从编码器给出的***角速度***,单位为rad。如果需要知道车轮线速度,则需要查询车辆轮半径,根据轮半径计算出车轮线速度。比如,角速度10rad/s,车轮半径0.15m,则线速度v = 10 * 0.15 = 1.5m/s
+
+机器人有三种急停方式:硬件开关急停、手柄远程急停、软件消息急停。三种急停均可使得车辆立即停止。其中***硬件急停优先级最高***,直接切断电机供电。在发送急停消息后,可根据查询机器人状态信息来判断是否成功进入急停。如果发现机器人进入急停状态,可根据查询消息,判定急停触发的来源。
+
+车辆的运动控制采用两轮自行车模型,控制量为***前轮转角和后轮转速***。其中转速为***相对速度***,需要用户根据查询到的车辆最大速度,计算出相对速度大小。比如,查询到车辆最大速度为2m/s,想要让车辆按照1m/s的速度运行,则需要发送 v = 1/2 = 0.5。
+
+## 1、两种数据消息
+
+* 无数据域消息
+ * 长度:6字节(1字节帧头0xFE + 4字节消息类型 + CRC8校验)
+
+* 有数据域消息
+ * 长度:14字节(1字节帧头0xFE + 4字节消息类型 + 8字节数据 + CRC8校验)
+
+## 2、查询指令
+
+* 查询指令:
+ * 4字节消息类型:0x0D,0x00,消息ID,0x00
+* 反馈指令:
+ * 4字节消息类型:0x2D,0x00,消息ID,0x00
+ * 8个字节的数据字节解析参考下面的表格,不同消息ID解析方式不同。
+* 针对不同指令,只有第三位消息ID不同。
+
+
+| 消息ID | 内容 | 格式| 读/写|备注|
+| --- | --- | --- | --- | --- |
+| 0x80 | 状态 |无数据域
[0]运行状态[1]-[7]保留|写
读|0x10:正常运行 0xff:急停状态|
+| 0x02 | 重置里程计 |无数据域|写|里程计的方向清零,即车辆朝向清零|
+| 0x11 | 剩余容量百分比 |无数据域
[0] uint8 [1]-[7]保留|写
读|
[0,100]% (采样频率=1Hz)|
+| 0x12 | 剩余可用时间 |无数据域
[0][1][2][3] uint32 [4]-[7]保留|写
读|
[0,360000]s (采样频率=1Hz)|
+| 0x13 | 剩余容量 |无数据域
[0][1][2][3] uint32 [4]-[7]保留|写
读|
[0,5000000]mAh (采样频率=1Hz)|
+| 0x14 | 电池电压 |无数据域
[0][1] uint16 [2]-[7]保留|写
读|
[0,500000]mV (采样频率=1Hz)|
+| 0x15 | 电池电流 |无数据域
[0][1][2][3] uint32 [4]-[7]保留|写
读|
[-750000,750000]mA 正:电池充电,负:电池放电(采样频率=1Hz)|
+| 0x16 | 手柄数据 | 无数据域
[0]-[7]详见 [手柄消息结构定义](#gamepad-struct) |写
读| |
+| 0x17 | 急停开关 | 无数据域
[0]bool[1]-[7]保留|写
读|
0:正常 1:急停 |
+| 0x18 | 查询软急停 | 无数据域
[0]bool[1]-[7]保留|写
读|
0:正常 1:急停 |
+| 0x19 | 查询手柄急停 | 无数据域
[0]bool[1]-[7]保留|写
读|
0:正常 1:急停 |
+| 0x1a | 查询最大线速度 | 无数据域
[0]-[3]float [4]-[7]保留 |写
读| 根据车轮大小计算出的最大线速度(m/s) |
+| 0x1b | 查询最大转角 | 无数据域
[0]-[3]float [4]-[7]保留 |写
读| 根据机械结构得到的最大转角(rad) |
+| 0x1c | 查询车辆宽度 | 无数据域
[0]-[3]float [4]-[7]保留 |写
读| 根据机械结构得到的车宽(m) |
+| 0x1d | 查询车辆长度 | 无数据域
[0]-[3]float [4]-[7]保留 |写
读| 根据机械结构得到的车长(m) |
+| 0x1e | 查询轮半径 | 无数据域
[0]-[3]float [4]-[7]保留 |写
读| 根据机械结构得到的车轮半径(m) |
+
+***范例***
+
+| 指令 | 单位| 写字节流 | 反馈字节流 |含义 |
+| ------------- | ------------- | ------------- | ------------- | ------------- |
+|状态查询||0xFE,0x0D,0x00,0x80,0x00,0xB2|0xFE,0x2D,0x00,0x80,0x00,0x10,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x09| 状态正常 |
+|重置编码器||0xFE,0x0D,0x00,0x02,0x00,0x0C||
+|剩余容量百分比||0xFE,0x0D,0x00,0x11,0x00,0xB5|0xFE,0x2D,0x00,0x11,0x00,0x64,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x79|容量100%|
+|剩余可用时间|秒|0xFE,0x0D,0x00,0x12,0x00,0xE0|0xFE,0x2D,0x00,0x12,0x00,0x50,0xC3,0x00,0x00,0x00,0x00,0x00,0x00,0xCC|剩余50000s|
+|剩余容量|mAh|0xFE,0x0D,0x00,0x13,0x00,0x24|0xFE,0x2D,0x00,0x13,0x00,0x50,0xC3,0x00,0x00,0x00,0x00,0x00,0x00,0x02|剩余50000mAh|
+|电池电压|10mV|0xFE,0x0D,0x00,0x14,0x00,0x4A|0xFE,0x2D,0x00,0x14,0x00,0x7D,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x99|1.25V|
+|电池电流|1mA|0xFE,0x0D,0x00,0x15,0x00,0x8E|0xFE,0x2D,0x00,0x15,0x00,0x4D,0x08,0x00,0x00,0x00,0x00,0x00,0x00,0x5A|2.125A|
+|急停开关||0xFE,0x0D,0x00,0x17,0x00,0x1F|0xFE,0x2D,0x00,0x17,0x00,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x58|急停开关按下|
+|查询软急停||0xFE,0x0D,0x00,0x18,0x00,0x07|0xFE,0x2D,0x00,0x18,0x00,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x26|软急停触发|
+|查询手柄急停||0xFE,0x0D,0x00,0x19,0x00,0xC3|0xFE,0x2D,0x00,0x19,0x00,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xE8|手柄急停按下|
+|查询最大线速度|m/s|0xFE,0x0D,0x00,0x1A,0x00,0x96|0xFE,0x2D,0x00,0x1A,0x00,0x00,0x00,0xC0,0x3F,0x00,0x00,0x00,0x00,0x94|最大线速度1.5m/s|
+|查询最大转角|rad|0xFE,0x0D,0x00,0x1B,0x00,0x52|0xFE,0x2D,0x00,0x1B,0x00,0x92,0x0A,0x06,0x3F,0x00,0x00,0x00,0x00,0xBC|最大转角:0.523Rad(30度)|
+|查询车辆宽度|m|0xFE,0x0D,0x00,0x1C,0x00,0x3C|0xFE,0x2D,0x00,0x1C,0x00,0x00,0x00,0x00,0x3F,0x00,0x00,0x00,0x00,0x9D| 0.5m|
+|查询车辆长度|m|0xFE,0x0D,0x00,0x1D,0x00,0xF8|0xFE,0x2D,0x00,0x1D,0x00,0x66,0x66,0x26,0x3F,0x00,0x00,0x00,0x00,0x83| 0.65m|
+|查询轮半径|m|0xFE,0x0D,0x00,0x1E,0x00,0xAD|0xFE,0x2D,0x00,0x1E,0x00,0x9A,0x99,0x19,0x3E,0x00,0x00,0x00,0x00,0xD2| 0.15m|
+
+## 3、控制指令(有数据域消息类型)
+
+* 运动控制(v,theta)
+ * 运动控制具有超时机制,需要在200ms内发送一帧数据,否则会认为数据超时,车辆停止运动。
+ * v: 车辆最大速度的百分比,取值范围[-1,-1],对应从倒退最大速度到前进最大速度。
+ * theta: 前轮转角,单位rad,弧度制。车辆向左转为正。
+ * 4字节消息:0x2D,0x00,0x01,0x00
+ * 8字节数据:前4字节表示v,后4字节表示theta
+ * 数据类型:float
+ * 范例:0xFE,0x2D,0x00,0x01,0x00,0xCD,0xCC,0xCC,0x3D,0xCD,0xCC,0x4C,0x3E,0x82
+ * 指令含义:v:0.1相对速度,theta:0.2rad
+
+* 紧急停止指令(Emergency)
+ * 急停触发:0xFE,0x2F,0xFF,0xFF,0x00,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xDA
+ * 急停解除:0xFE,0x2F,0xFF,0xFF,0x00,0x10,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x53
+ * 该消息可以直接关停底盘的电机输出。
+
+
+## 4、反馈消息
+
+反馈消息将持续发送,40ms间隔。可以使用反馈消息作为车辆连接的依据。
+
+* 里程计xy坐标
+ * 车辆上电后的位置,为里程计原点,车头方向为x,车左侧为y。
+ * 4字节消息类型:0x2D,0x00,0x21,0x00
+ * 8字节数据内容:前4个字节为x坐标,单位m。后字节为y坐标,单位m。
+ * 数据类型为float
+ * 范例:0xFE,0x2D,0x00,0x21,0x00,0xCD,0xCC,0xCC,0x3D,0xCD,0xCC,0x4C,0x3E,0x1A
+ * 说明:x:0.1m y:0.2m
+
+* 里程计朝向
+ * 车辆上电后的朝向,为0方向,逆时针为正。
+ * 4字节消息类型:0x2D,0x00,0x22,0x00
+ * 8字节数据内容:前4个字节为朝向角,单位为rad。
+ * 数据类型为float
+ * 范例:0xFE,0x2D,0x00,0x22,0x00,0x9A,0x99,0x99,0x3E,0x00,0x00,0x00,0x00,0xD9
+ * 说明:0.3rad
+
+* 左电机速度
+ * 4字节消息类型:0x2D,0x11,0x11,0x00
+ * 8字节数据内容:前4个字节为速度,单位rad/s
+ * 数据类型:float
+ * 范例:0xFE,0x2D,0x11,0x11,0x00,0xCD,0xCC,0xCC,0x3D,0x00,0x00,0x00,0x00,0xC5
+ * 含义:0.1rad/s,如果要转换为m/s,需要乘以车轮半径
+
+* 右电机速度:
+ * 4字节消息类型:0x2D,0x10,0x11,0x00
+ * 8字节数据内容:前4个字节为速度,单位rad/s
+ * 数据类型:float
+ * 范例:0xFE,0x2D,0x10,0x11,0x00,0xCD,0xCC,0x4C,0x3E,0x00,0x00,0x00,0x00,0xB4
+ * 含义:0.2rad/s,如果要转换为m/s,需要乘以车轮半径
+
+* 转向角度:
+ * 4字节消息类型:0x2D,0x20,0x11,0x00
+ * 8字节数据内容:前4个字节为角度,单位rad
+ * 数据类型:float
+ 范例:0xFE,0x2D,0x20,0x11,0x00,0xCD,0xCC,0xCC,0x3D,0x00,0x00,0x00,0x00,0x26
+ * 含义:0.1rad,正方向为向左转
+
+
+## 5、CRC8校验
+
+* 使用CRC-8/MAXIM方式计算
+
+* 示例:在线计算crc8
+
+![img](img/crc8-maxim.png)
+
+
+
+* 查表法计算crc8
+
+```
+const uint8_t CRC8Table[]={
+ 0, 94, 188, 226, 97, 63, 221, 131, 194, 156, 126, 32, 163, 253, 31, 65,
+ 157, 195, 33, 127, 252, 162, 64, 30, 95, 1, 227, 189, 62, 96, 130, 220,
+ 35, 125, 159, 193, 66, 28, 254, 160, 225, 191, 93, 3, 128, 222, 60, 98,
+ 190, 224, 2, 92, 223, 129, 99, 61, 124, 34, 192, 158, 29, 67, 161, 255,
+ 70, 24, 250, 164, 39, 121, 155, 197, 132, 218, 56, 102, 229, 187, 89, 7,
+ 219, 133, 103, 57, 186, 228, 6, 88, 25, 71, 165, 251, 120, 38, 196, 154,
+ 101, 59, 217, 135, 4, 90, 184, 230, 167, 249, 27, 69, 198, 152, 122, 36,
+ 248, 166, 68, 26, 153, 199, 37, 123, 58, 100, 134, 216, 91, 5, 231, 185,
+ 140, 210, 48, 110, 237, 179, 81, 15, 78, 16, 242, 172, 47, 113, 147, 205,
+ 17, 79, 173, 243, 112, 46, 204, 146, 211, 141, 111, 49, 178, 236, 14, 80,
+ 175, 241, 19, 77, 206, 144, 114, 44, 109, 51, 209, 143, 12, 82, 176, 238,
+ 50, 108, 142, 208, 83, 13, 239, 177, 240, 174, 76, 18, 145, 207, 45, 115,
+ 202, 148, 118, 40, 171, 245, 23, 73, 8, 86, 180, 234, 105, 55, 213, 139,
+ 87, 9, 235, 181, 54, 104, 138, 212, 149, 203, 41, 119, 244, 170, 72, 22,
+ 233, 183, 85, 11, 136, 214, 52, 106, 43, 117, 151, 201, 74, 20, 246, 168,
+ 116, 42, 200, 150, 21, 75, 169, 247, 182, 232, 10, 84, 215, 137, 107, 53 };
+
+uint8_t can_crc8_calculate(uint8_t *p, uint8_t counter)
+{
+ uint8_t crc8 = 0;
+ for( ; counter > 0; counter--){
+ crc8 = CRC8Table[crc8^*p];
+ p++;
+ }
+ return(crc8);
+}
+```
diff --git a/底盘/conf.json b/底盘/conf.json
new file mode 100644
index 0000000..5142037
--- /dev/null
+++ b/底盘/conf.json
@@ -0,0 +1,66 @@
+{
+ "_readme": [
+ "注:uri 必须保障唯一性,若有重复引用,请使用 rewrite 注册新的 uri",
+ "由于设计缺陷,rewrite 时只能自定义最后一级路径",
+ "uri 格式 1 - 相对文档:a/b/c",
+ "uri 格式 2 - 相对站内:/usedoc/ap1/a/b/c",
+ "uri 格式 3 - 绝对地址:https://www.baidu.com",
+ "_readme 本身并没有什么软用"
+ ],
+ "index": "receipt",
+ "rewrite": {
+
+ },
+ "plugin": {
+ "emoji": false,
+ "taskList": true,
+ "tex": true,
+ "flowChart": true,
+ "sequenceDiagram": true
+ },
+ "menu": {
+ "toc": {
+ "startLevel": "1",
+ "overLevel": "1"
+ },
+ "items": [
+ {
+ "name": "Autolabor M2 ",
+ "uri": "/usedoc/navigationKit2/version_two/user_guide/quick_start/receipt"
+ },
+
+ {
+ "name": "Autolabor M2底盘",
+ "isOpen": true,
+ "items": [
+ {
+ "name": "产品概述",
+ "uri": "overview"
+ },
+
+ {
+ "name": "产品参数",
+ "uri": "intro"
+ },
+
+ {
+ "name": "控制方式",
+ "uri": "use"
+ },
+
+ {
+ "name": "串口协议",
+ "uri": "CustomAutocan"
+ },
+
+ {
+ "name": "ROS驱动",
+ "uri": "ChassisM2"
+ }
+
+
+ ]
+ }
+ ]
+ }
+}
\ No newline at end of file
diff --git a/底盘/img/.DS_Store b/底盘/img/.DS_Store
new file mode 100644
index 0000000..1f23840
Binary files /dev/null and b/底盘/img/.DS_Store differ
diff --git a/底盘/img/1.png b/底盘/img/1.png
new file mode 100644
index 0000000..b770713
Binary files /dev/null and b/底盘/img/1.png differ
diff --git a/底盘/img/2.png b/底盘/img/2.png
new file mode 100644
index 0000000..a2bc077
Binary files /dev/null and b/底盘/img/2.png differ
diff --git a/底盘/img/canbus_driver.png b/底盘/img/canbus_driver.png
new file mode 100644
index 0000000..3f31614
Binary files /dev/null and b/底盘/img/canbus_driver.png differ
diff --git a/底盘/img/crc8-maxim.png b/底盘/img/crc8-maxim.png
new file mode 100644
index 0000000..41413ab
Binary files /dev/null and b/底盘/img/crc8-maxim.png differ
diff --git a/底盘/img/pm1_driver.png b/底盘/img/pm1_driver.png
new file mode 100644
index 0000000..0fc236f
Binary files /dev/null and b/底盘/img/pm1_driver.png differ
diff --git a/底盘/intro.md b/底盘/intro.md
new file mode 100644
index 0000000..ca9ed31
--- /dev/null
+++ b/底盘/intro.md
@@ -0,0 +1,108 @@
+# 产品参数
+
+
+
+ 尺寸 |
+ 1040 mm*700mm *430 mm
|
+ 驱动形式 |
+ 双轮独立驱动
|
+
+
+ 轴距 |
+ 650mm |
+ 转向形式 |
+ 阿卡曼转向 |
+
+
+ 轮距 |
+ 600mm |
+ 悬挂形式 |
+ 四轮双叉臂式独立悬挂 |
+
+
+ 最大速度 |
+ 10km/h |
+ 电池参数 |
+ 磷酸铁锂 90AH 24V |
+
+
+ 总质量 |
+ 80kg |
+ 续航时间 |
+ 12小时 |
+
+
+ 最小转弯半径 |
+ 1.2m |
+ 续航里程 |
+ 80公里 |
+
+
+ 最大爬坡度 |
+ 30° |
+ 编码器 |
+ 4096线 |
+
+
+ 离地高度 |
+ 110mm |
+ 对外通信接口 |
+ RS232 |
+
+
+ 驻车 |
+ 电子驻车 |
+ 防护等级 |
+ IP54 |
+
+
+ 驱动电机 |
+ 500W |
+ 对外供电 |
+ 24V |
+
+
+ 转向电机 |
+ 250W |
+ 遥控距离 |
+ 50M |
+
+
+
+# 产品尺寸
+
+
+![1.png](img/1.png)
+
+
+
+# 控制手柄参数
+该手柄有自动休眠功能,长时间不操作,省电模块被激活后自动进入休眠模式,按下开机键即可唤醒手柄。
+
+参数名称 | 参数内容
+:-------------: | :-------------:
+使用时间 | 约10小时
+无线频率 | 2.4GHz
+接收范围 | 50m
+
+
+* * *
+
+# 控制面板
+
+
+控制面板清单:
+
+名称 | 个数 | 说明
+:-------------: | :-------------: | :-------------:
+紧急停止 | 1 | 在紧急情况下请按下该紧急停止按钮
+电源 | 1 | 电源开启关闭按钮
+充电接口(IN) | 1 | 为内置电池充电
+电量显示 | 1 | 以百分比的形式显示AP1电池电量
+手柄接收 | 1 | 手柄接收器插口
+RS232串口 | 1 | 使用串口数据线连接下位机与上位机,进行通信
+
+
+
+
+
diff --git a/底盘/overview.md b/底盘/overview.md
new file mode 100644
index 0000000..c1168da
--- /dev/null
+++ b/底盘/overview.md
@@ -0,0 +1,49 @@
+# 产品概述
+ Autolabor M2采用前转向的阿克曼结构,四轮双叉臂式独立悬挂,具有100公斤强大负载能力。80公里续航里程。轻松应对各种复杂路况。车规级零部件,稳定可靠,防护等级IP54。配合高精度编码器可以实现高速运动和精准转向,有效提升稳定性和精度。
+
+* * *
+
+# 主要特性
+* 可靠耐用,操作简单,无需组装,开机直接使用
+* 高通过性,爬坡能力十足,续航能力强
+* 高精度工业级编码器,定位精准
+* 高负载,负重可达100KG
+* 适应场景广泛,轻松应对各种复杂路况
+* 兼容多个系统,支持多种开发平台、控制方式
+* 支持ROS开发,提供ROS驱动包与运动模型
+* 雷达、摄像头、惯导等多种传感器随意组合搭配,拆装方便
+* 使用文档齐全,配备后续用户支持,并不断更新开发教程
+
+* * *
+
+
+# 产品清单
+
+名称 | 数量 | 备注
+:---:|:---:|---
+M2移动平台 | 1辆 |
+M2充电器 | 1个 |
+M2控制手柄| 1套 |
+串口数据线 | 1根 |
+配套工具 | 1套 |
+
+* * *
+
+# 使用提醒
+
+* 产品边缘锋利,请小心接触,避免划伤
+* 产品表面为金属材质,请勿与电路板直接接触
* 操控平台时避免速度过快,引起碰撞
* 搬运时以及设置作业时,请勿落下或倒置
+* 非专业人员,请不要私自拆卸
* 不使用非原厂标配的电池、电源、充电座
* 运行时请勿用手触碰
+* 不要在有水的地方,存在腐蚀性、易燃性气体的环境内和靠近可燃性物质的地方使用
* 不要放置在加热器或者大型卷线电阻器等发热体周围
+* 切勿将电机直接与商用电源连接
+
+* * *
+
+# 电池安全
+* 请在有人看护的状态下充电,若人员离开请拔掉充电插头
+* 充电器在充电工作时,会向外界散发一定的热量,充电器与产品应放在通风干燥的环境中使用
* 正常充电时,充电指示灯为红色,当转为绿色时为充满
+* 停止充电时,应先拔下插头,然后取下电池端插头
+* 产品长期不用,需三个月至半年补充一次电
+* 产品电池不可将电完全用完,否则会严重受损,容易造成不可修复
+
+* * *
\ No newline at end of file
diff --git a/底盘/use.md b/底盘/use.md
new file mode 100644
index 0000000..3bc41ba
--- /dev/null
+++ b/底盘/use.md
@@ -0,0 +1,119 @@
+# 控制方式
+M2可以使用手柄控制和上位机控制两种方式来控制,手柄控制权限高于上位机控制,下面将分别概述这两种控制方式。
+
+## 手柄控制
+
+### 概述
+
+我们配送一个控制手柄用于控制M2移动。
+
+![2.png](img/2.png)
+
+### 使用说明
+
+#### 手柄操作步骤
+
+1. 长按手柄HOME键,灯光亮起,自动匹配。
+2. 匹配成功后,手柄会震动一下,跑马灯最左侧与最右侧灯常亮。
+3. 同时按下顶部L、LZ、R、RZ四键,手柄解锁。
+4. 在遥控底盘运动、调整线速度、调整角速度的时候需要长按L、LZ、R、RZ四键中任意一键。
+
+
+
+#### 手柄按键说明
+
+我们对于M2的手柄控制设计有几种速度档位,如下表。
+
+
+
+ 档位 |
+ 0档 |
+ 1档 |
+ 2档 |
+ 3档 |
+ 4档 |
+ 5档 |
+
+
+ 速度 |
+ 16% |
+ 33% |
+ 50% |
+ 66% |
+ 83% |
+ 100% |
+
+
+
+
+
+
+ 按键 |
+ 功能 |
+ 备注 |
+
+
+ 左侧摇杆键 |
+ 控制M2前进与后退 |
+ 控制摇杆推动的力度控制速度,轻推低速移动,推到底为当前档位最高速 |
+
+
+ 右侧摇杆键 |
+ 控制M2左右转向 |
+ 控制摇杆推动的力度控制角度,轻推小角度转向,推到底为最大角转向,松开自动回正 |
+
+
+
+ 中区“—”键 |
+ 速度减档 |
+ 每按一下,速度降低一档,最低不得高于最底档,如0档 |
+
+
+ 中区“+”键 |
+ 速度加档 |
+ 每按一下,速度提高一档,最高不得高于最高档,如5档 |
+
+
+ 左区4控制键 |
+ 前/后/左/右控制运动方向 |
+ |
+
+
+
+ 右区4控制键 |
+ 前/后/左/右控制运动方向 |
+ |
+
+
+ HOME键 |
+ 开机/急停 |
+ 紧急情况下,可按HOME键,M2会紧急刹车 |
+
+
+ 顶部4控制键 |
+ 解锁/防误触 |
+ 手柄连接成功后,需同时按下4键解锁,控制时需长按任意一键,行驶过程中松开,M2会缓刹 |
+
+
+
+
+
+
+
+
+* * *
+
+## 上位机控制
+### 概述
+使用M2配送的串口数据线与上位机相连,按照预定义的**协议规则**,向下位机(底层硬件平台)发送指令,控制移动平台。
+
+### 使用说明
+使用接口线将下位机与上位机连接起来,向下位机发送指令。
+
+### 指令发送方式
+用户可按照自己的开发场景,选择不同的方式发送指令:
+
+* 使用**串口调试助手**直接向下位机发送指令
+* 基于ROS开发可使用我们提供的**ROS驱动包**与下位机通信发送接收指令
+
+