feat: 重构底盘和套件
|
@ -0,0 +1,145 @@
|
|||
# Autolabor ROS 驱动模块
|
||||
|
||||
## 1. 介绍
|
||||
|
||||
Autolabor ROS驱动模块包括**CANBus驱动**和**Autolabor CAN系列(PM1/M2) 底盘驱动**
|
||||
,主要用于实现与Autolabor_CANbus模块的通信,并通过线速度和角速度来控制Autolabor
|
||||
CAN系列底盘的行驶。该模块提供了全面的底盘控制策略和状态反馈机制,使得底盘的操作既直观又高效。
|
||||
|
||||
### 特性
|
||||
|
||||
- **CANBus数据获取和控制**: 直接从CANBus网络获取数据并通过CAN指令控制车辆。能够获取动力轮和转向轮编码器的原始数值,并独立控制动力轮的转速及转向轮的绝对转向角度。
|
||||
- **高级速度控制**: 通过线速度和角速度直接控制移动底盘,无需单独控制后轮转向。这一特性简化了驱动操作并增强了操作的直观性。
|
||||
- **实时位置信息**: 提供实时的机器人底盘位置信息,便于进行闭环控制,确保导航和定位的精确性。
|
||||
- **电子差速控制**: 采用双动力轮电子差速控制,保证机器人在行驶过程中始终满足阿克曼原理,从而提高行驶稳定性和精度。
|
||||
- **运动优化**: 根据后轮转向动态优化车辆的运动速度,确保在维持行驶精度的前提下,提升车辆行驶的流畅性。
|
||||
- **驻车和急停控制**: 驱动包括了高级的驻车和急停特性,能够在紧急情况下快速响应,立即停车,保障操作安全。
|
||||
- **电量反馈和状态监控**: 驱动能够实时监控底盘的电量状态,并反馈至ROS系统,同时持续监控底盘各部件的状态,及时报告任何异常情况,确保系统的可靠运行。
|
||||
|
||||
## 2. 编译与安装
|
||||
|
||||
### 2.1 引入ROS环境变量
|
||||
|
||||
在启动ROS相关程序前,确保ROS环境变量已经正确配置。在终端执行以下命令以导入环境变量:
|
||||
|
||||
```bash
|
||||
source /opt/ros/noetic/setup.bash
|
||||
```
|
||||
|
||||
### 2.2 添加串口权限或配置udev规则
|
||||
|
||||
为确保程序可以正常访问底盘的串口,需要给予相应的权限。可以通过以下命令临时赋予权限:
|
||||
|
||||
```bash
|
||||
sudo chmod 666 /dev/ttyUSB0
|
||||
```
|
||||
|
||||
或者设置udev规则,为串口设定固定的设备名称,详情参见[Autolabor官方文档](http://www.autolabor.com.cn/usedoc/navigationKit2/common/q_a/doc1#1)。
|
||||
|
||||
### 2.3 修改launch文件
|
||||
|
||||
在启动底盘前,需要在launch文件中指定正确的串口地址。编辑`m2keyboard.launch`文件,确保`port_name`的值反映了当前设备的串口地址:
|
||||
|
||||
```xml
|
||||
|
||||
<param name="port_name" value="/dev/ttyUSB0"/>
|
||||
```
|
||||
|
||||
### 2.4 启动launch
|
||||
|
||||
编译并加载ROS工作环境后,使用以下命令启动底盘:
|
||||
|
||||
```bash
|
||||
roslaunch autolabor_canbus_driver m2keyboard.launch
|
||||
```
|
||||
|
||||
确保在图形界面的终端运行以避免X11Server相关的错误。
|
||||
|
||||
## 3. 节点使用详细信息
|
||||
|
||||
### 3.1 启动launch
|
||||
|
||||
完成配置后,通过`roslaunch`命令启动底盘控制程序。这将激活包括底盘驱动、键盘控制以及其他必要节点。确保在图形用户界面的终端中运行此命令,以避免遇到X11Server相关的错误。
|
||||
|
||||
### 3.2 控制运动
|
||||
|
||||
#### a. 键盘控制
|
||||
|
||||
运行键盘控制节点后,使用键盘上的指令控制底盘前进、后退、左转和右转。观察RViz中的`base_link`是否根据指令正确移动。此外,监测各轮的运动是否平滑且响应及时。
|
||||
|
||||
#### b. cmd_vel vs ackerman_vel
|
||||
|
||||
- **`cmd_vel`(标准速度控制)**:
|
||||
使用`geometry_msgs/Twist`消息类型发送线速度和角速度指令,控制底盘的整体移动方向和速度。
|
||||
|
||||
- **`ackerman_vel`(阿克曼转向速度控制)**:
|
||||
除了标准的线速度和角速度外,额外控制前轮的转角,适用于需要精确转向控制的场景。
|
||||
|
||||
### 3.3 使用rqt_gui工具发送指令和服务
|
||||
|
||||
#### a. 发送控制指令
|
||||
|
||||
通过`rqt_gui`发送以下指令:
|
||||
|
||||
- **紧急停车** (`/m2_driver/emergency_stop`): 立即停止底盘运动。
|
||||
- **刹车** (`/m2_driver/brake_set`): 控制底盘的刹车系统。
|
||||
- **里程计清零** (`/m2_driver/reset_odom`): 重置底盘的里程计数据。
|
||||
- **转向中心对齐** (`/m2_driver/steer_center_bias`): 调整转向轮的中心位置。
|
||||
|
||||
#### b. 调用服务节点
|
||||
|
||||
- **查询底盘参数** (`/m2_driver/chassis_parameter`): 获取或设置底盘的配置参数,如轮间距、轮直径等。
|
||||
|
||||
#### c. 绘图监听
|
||||
|
||||
使用rqt的绘图功能来实时监控和分析以下数据:
|
||||
|
||||
- **前轮转角** (`/m2_driver/wheel_angle`): 显示实时转向角度。
|
||||
- **左右轮速度** (`/m2_driver/left_wheel_vel`, `/m2_driver/right_wheel_vel`): 监控各动力轮的速度。
|
||||
|
||||
#### d. 话题查看
|
||||
|
||||
关注以下话题以获取底盘状态和电量信息:
|
||||
|
||||
- **车辆状态** (`/m2_driver/chassis_info`): 提供底盘的详细状态,如电量、温度等。
|
||||
- **电量信息** (`/m2_driver/chassis_monitor`): 监测底盘的电池电量和健康状态。
|
||||
|
||||
### 3.4 参数说明
|
||||
|
||||
在底盘驱动的配置中,可以通过设置以下参数来定制驱动的行为和性能:
|
||||
|
||||
- **`odom_frame`**: 用于发布里程计信息的坐标系名称,默认为`"odom"`。这是底盘位置信息的参考坐标系。
|
||||
- **`base_frame`**: 底盘的基础坐标系名称,默认为`"base_link"`。这是底盘上各个组件和传感器的相对参考点。
|
||||
- **`poller_rate_hz`**: 设置查询CAN总线信息的频率,单位是赫兹(Hz),默认为1Hz。这影响电量及状态数据更新的实时性。
|
||||
- **`publish_tf`**: 是否发布TF变换数据,布尔值,用于控制是否在ROS网络中发布从`odom`到`base_link`的转换,默认关闭。
|
||||
|
||||
### 3.5 话题订阅与发布
|
||||
|
||||
#### 订阅话题
|
||||
|
||||
底盘驱动节点订阅以下话题,以接收外部控制命令和系统指令:
|
||||
|
||||
- **`/m2_driver/cmd_vel`** (`geometry_msgs/Twist`): 接收标凈的速度指令,控制底盘的线速度和角速度。
|
||||
- **`/m2_driver/ackerman_vel`** (`geometry_msgs/Twist`): 接收针对阿克曼转向系统的速度和转向角度指令。
|
||||
- **`/m2_driver/steer_center_bias`** (`std_msgs/Float64`): 接收用于调整转向中心的偏置值,用于微调转向准确性。
|
||||
- **`/m2_driver/brake_set`** (`std_msgs/Bool`): 接收制动指令,用于控制底盘的停止和启动。
|
||||
- **`/m2_driver/reset_odom`** (`std_msgs/Empty`): 接收里程计重置指令,用于归零里程计数据。
|
||||
- **`/m2_driver/emergency_stop`** (`std_msgs/Bool`): 接收紧急停车指令,用于立即停止所有底盘运动。
|
||||
|
||||
#### 发布话题
|
||||
|
||||
底盘驱动节点发布以下话题,提供底盘的状态信息和运动反馈:
|
||||
|
||||
- **`/odom`** (`nav_msgs/Odometry`): 发布底盘的里程计信息,包括位置和速度。
|
||||
- **`/m2_driver/chassis_info`** (`autolabor_canbus_driver/ChassisStatusInfo`): 发布底盘的状态信息,如电量、温度等。
|
||||
- **`/m2_driver/chassis_monitor`** (`autolabor_canbus_driver/ChassisMonitorInfo`): 发布底盘的监控信息,提供实时的健康状况和性能数据。
|
||||
- **`/m2_driver/wheel_angle`** (`std_msgs/Float64`): 发布当前前轮的转角,单位为弧度。
|
||||
- **`/m2_driver/left_wheel_vel`** (`std_msgs/Float64`): 发布左轮的速度,单位为米/秒。
|
||||
- **`/m2_driver/right_wheel_vel`** (`std_msgs/Float64`): 发布右轮的速度,单位为米/秒。
|
||||
|
||||
### 3.6 服务节点
|
||||
|
||||
底盘驱动提供以下ROS服务以支持参数查询和配置:
|
||||
|
||||
- **`/m2_driver/chassis_parameter`** (`autolabor_canbus_driver/ChassisParameterServer`):
|
||||
这个服务端点用于查询或设置底盘的参数。如果参数已经设置,则返回当前参数;如果未设置,则返回失败。这使得用户可以动态地调整底盘配置,以适应不同的工作条件和需求。
|
|
@ -0,0 +1,225 @@
|
|||
# AutolaborM2串口通讯协议
|
||||
|
||||
AutolaborM2采用串口通讯,通讯波特率为***115200***。通讯消息分为无数据域和有数据域两种类型。其中无数据域类型主要用于查询指令。
|
||||
|
||||
串口连接成功后,能收到机器人上报的里程计消息和车辆速度、转角消息,可依此作为机器人连接的判断。当前车辆上报得到左轮轮速和右轮轮速是直接从编码器给出的
|
||||
***角速度***
|
||||
,单位为rad。如果需要知道车轮线速度,则需要查询车辆轮半径,根据轮半径计算出车轮线速度。比如,角速度10rad/s,车轮半径0.15m,则线速度v =
|
||||
10 * 0.15 = 1.5m/s
|
||||
|
||||
机器人有三种急停方式:硬件开关急停、手柄远程急停、软件消息急停。三种急停均可使得车辆立即停止。其中***硬件急停优先级最高***
|
||||
,直接切断电机供电。在发送急停消息后,可根据查询机器人状态信息来判断是否成功进入急停。如果发现机器人进入急停状态,可根据查询消息,判定急停触发的来源。
|
||||
|
||||
M2底盘为阿卡曼转向结构,机器人的运动控制采用***两轮自行车模型***,控制量为***前轮转角和后轮转速***。其中转速为
|
||||
***相对速度***,需要用户根据查询到的车辆最大速度,计算出相对速度大小。比如,查询到车辆最大速度为2m/s,想要让车辆按照1m/s的速度运行,则需要发送
|
||||
v = 1/2 = 0.5。
|
||||
|
||||
机器人速度控制时,会检查TCU,左电机ECU,右电机ECU状态,如果状态异常,则不会执行控制指令。此时,会向上位机报告异常状态,异常状态中包括急停、编码器数据异常、电流保护和机械刹车。
|
||||
|
||||
## 1、两种数据消息
|
||||
|
||||
* 无数据域消息
|
||||
* 长度:6个字节(1个字节帧头FE + 4字节消息类型 + CRC8校验)
|
||||
|
||||
![NoDataPackage.png](./imgs/NoDataPackage.png)
|
||||
|
||||
* 有数据域消息
|
||||
* 长度:14个字节(1个字节帧头FE + 4字节消息类型 + 8字节数据(小端模式) + CRC8校验)
|
||||
|
||||
![WithDataPackage.png](./imgs/WithDataPackage.png)
|
||||
|
||||
## 2、查询指令
|
||||
|
||||
* 查询指令:无数据域包
|
||||
* 反馈指令:有数据域包
|
||||
|
||||
| 消息ID | 内容 | 反馈数据(8字节) | 数据含义 |
|
||||
|-------------|---------|--------------------------|--------------------------------------------|
|
||||
| 0D 00 80 00 | 状态 | [0]运行状态[1]-[7]保留 | 10:正常运行 ff:急停状态 |
|
||||
| 0D 00 11 00 | 剩余容量百分比 | [0] uint8 [1]-[7]保留 | [0 100]% (采样频率=1Hz) |
|
||||
| 0D 00 12 00 | 剩余可用时间 | [0]-[3] uint32 [4]-[7]保留 | [0 360000]s (采样频率=1Hz) |
|
||||
| 0D 00 13 00 | 剩余容量 | [0]-[3] uint32 [4]-[7]保留 | [0 5000000]mAh (采样频率=1Hz) |
|
||||
| 0D 00 14 00 | 电池电压 | [0][1] uint16 [2]-[7]保留 | [0 500000]mV (采样频率=1Hz) |
|
||||
| 0D 00 15 00 | 电池电流 | [0]-[3] uint32 [4]-[7]保留 | [-750000 750000]mA 正:电池充电,负:电池放电(采样频率=1Hz) |
|
||||
| 0D 00 17 00 | 急停开关 | [0]bool[1]-[7]保留 | 0:正常 1:急停 |
|
||||
| 0D 00 18 00 | 查询软急停 | [0]bool[1]-[7]保留 | 0:正常 1:急停 |
|
||||
| 0D 00 19 00 | 查询手柄急停 | [0]bool[1]-[7]保留 | 0:正常 1:急停 |
|
||||
| 0D 00 1a 00 | 查询最大线速度 | [0]-[3]float [4]-[7]保留 | 根据车轮大小计算出的最大线速度(m/s) |
|
||||
| 0D 00 1b 00 | 查询最大转角 | [0]-[3]float [4]-[7]保留 | 根据机械结构得到的最大转角(rad) |
|
||||
| 0D 00 1c 00 | 查询车辆宽度 | [0]-[3]float [4]-[7]保留 | 根据机械结构得到的车宽(m) |
|
||||
| 0D 00 1d 00 | 查询车辆长度 | [0]-[3]float [4]-[7]保留 | 根据机械结构得到的车长(m) |
|
||||
| 0D 00 1e 00 | 查询轮半径 | [0]-[3]float [4]-[7]保留 | 根据机械结构得到的车轮半径(m) |
|
||||
|
||||
***查询范例***
|
||||
|
||||
| 指令 | 单位 | 写字节流 |
|
||||
|---------|------|---------------------|
|
||||
| 状态查询 | | `FE 0D 00 08 00 B2` |
|
||||
| 剩余容量百分比 | | `FE 0D 00 11 00 B5` |
|
||||
| 剩余可用时间 | 秒 | `FE 0D 00 12 00 E0` |
|
||||
| 剩余容量 | mAh | `FE 0D 00 13 00 2A` |
|
||||
| 电池电压 | 10mV | `FE 0D 00 14 00 4A` |
|
||||
| 电池电流 | 1mA | `FE 0D 00 15 00 8E` |
|
||||
| 急停开关 | | `FE 0D 00 17 00 1F` |
|
||||
| 查询软急停 | | `FE 0D 00 18 00 07` |
|
||||
| 查询手柄急停 | | `FE 0D 00 19 00 C3` |
|
||||
| 查询最大线速度 | m/s | `FE 0D 00 1A 00 96` |
|
||||
| 查询最大转角 | rad | `FE 0D 00 1B 00 52` |
|
||||
| 查询车辆宽度 | m | `FE 0D 00 1C 00 3C` |
|
||||
| 查询车辆长度 | m | `FE 0D 00 1D 00 F8` |
|
||||
| 查询轮半径 | m | `FE 0D 00 1E 00 AD` |
|
||||
|
||||
***查询结果:***
|
||||
|
||||
| 指令 | 反馈字节流 | 含义 |
|
||||
|---------|---------------------------------------------|---------------|
|
||||
| 状态查询 | `FE 2D 00 80 00 10 00 00 00 00 00 00 00 09` | 状态正常 |
|
||||
| 剩余容量百分比 | `FE 2D 00 11 00 64 00 00 00 00 00 00 00 79` | 容量100% |
|
||||
| 剩余可用时间 | `FE 2D 00 12 00 50 C3 00 00 00 00 00 00 CC` | 剩余50000s |
|
||||
| 剩余容量 | `FE 2D 00 13 00 50 C3 00 00 00 00 00 00 02` | 剩余50000mAh |
|
||||
| 电池电压 | `FE 2D 00 14 00 7D 00 00 00 00 00 00 00 99` | 1.25V |
|
||||
| 电池电流 | `FE 2D 00 15 00 4D 08 00 00 00 00 00 00 5A` | 2.125A |
|
||||
| 急停开关 | `FE 2D 00 17 00 01 00 00 00 00 00 00 00 58` | 急停开关按下 |
|
||||
| 查询软急停 | `FE 2D 00 18 00 01 00 00 00 00 00 00 00 26` | 软急停触发 |
|
||||
| 查询手柄急停 | `FE 2D 00 19 00 01 00 00 00 00 00 00 00 E8` | 手柄急停按下 |
|
||||
| 查询最大线速度 | `FE 2D 00 1A 00 00 00 C0 3F 00 00 00 00 94` | 最大线速度1.5m/s |
|
||||
| 查询最大转角 | `FE 2D 00 1B 00 92 0A 06 3F 00 00 00 00 BC` | 最大转角:0.523Rad |
|
||||
| 查询车辆宽度 | `FE 2D 00 1C 00 00 00 00 3F 00 00 00 00 9D` | 0.5m |
|
||||
| 查询车辆长度 | `FE 2D 00 1D 00 66 66 26 3F 00 00 00 00 83` | 0.65m |
|
||||
| 查询轮半径 | `FE 2D 00 1E 00 9A 99 19 3E 00 00 00 00 D2` | 0.15m |
|
||||
|
||||
## 3、控制指令(有数据域消息类型)
|
||||
|
||||
* 运动控制(v theta)
|
||||
* 运动控制具有超时机制,需要在200ms内发送一帧数据,否则会认为数据超时,车辆停止运动。
|
||||
* v: 车辆最大速度的百分比,取值范围[-1 -1],对应从倒退最大速度到前进最大速度。
|
||||
* theta: 前轮转角,单位rad,弧度制。车辆向左转为正。
|
||||
* 4字节消息类型:`2D 00 01 00`
|
||||
* 8字节数据:前4字节表示v,后4字节表示theta
|
||||
* 数据类型:float
|
||||
* 范例:`FE 2D 00 01 00 CD CC CC 3D CD CC 4C 3E 82`
|
||||
* 指令含义:v:0.1相对速度,theta:0.2rad
|
||||
|
||||
* 重置里程计
|
||||
* 4字节消息类型:`0D 00 02 00`
|
||||
* 范例:`FE 0D 00 02 00 0C`
|
||||
|
||||
* 驻车控制
|
||||
* 发送机械刹车指令
|
||||
* 4字节消息类型: `2D 00 03 00`
|
||||
* 8字节数据:第一个字节表示是否刹车,1为刹车,0为释放
|
||||
* 刹车指令:`FE 2D 00 03 00 01 00 00 00 00 00 00 00 07`
|
||||
* 释放刹车:`FE 2D 00 03 00 00 00 00 00 00 00 00 00 44`
|
||||
|
||||
* 调整零位
|
||||
* 4字节消息类型: `2D 00 04 00`
|
||||
* 8字节数据:前4个字节表示float,偏移量
|
||||
* 逆时针偏移1度: `FE 2D 00 04 00 00 00 80 BF 00 00 00 00 D6`
|
||||
* 顺时针偏移1度: `FE 2D 00 04 00 00 00 80 3F 00 00 00 00 1D`
|
||||
|
||||
* 紧急停止指令(Emergency)
|
||||
* 4字节消息类型:`2F FF FF 00`
|
||||
* 8字节数据:第1个字节表示急停类型,FF表示急停,10表示解除急停
|
||||
* 急停触发:`FE 2F FF FF 00 FF 00 00 00 00 00 00 00 DA`
|
||||
* 急停解除:`FE 2F FF FF 00 10 00 00 00 00 00 00 00 53`
|
||||
* 该消息可以直接关停底盘的电机输出。
|
||||
|
||||
## 4、反馈消息
|
||||
|
||||
反馈消息将持续发送,40ms间隔。可以使用反馈消息作为车辆连接的依据。
|
||||
|
||||
* 整车速度和转角
|
||||
* 4字节消息类型:`2D 00 20 00`
|
||||
* 8字节数据内容:前4字节为车辆速度v,单位m/s。后4字节为前轮转角,单位rad。
|
||||
* 数据类型:float
|
||||
|
||||
* 里程计xy坐标
|
||||
* 车辆上电后的位置,为里程计原点,车头方向为x,车左侧为y。
|
||||
* 4字节消息类型:`2D 00 21 00`
|
||||
* 8字节数据内容:前4个字节为x坐标,单位m。后4字节为y坐标,单位m。
|
||||
* 数据类型为float
|
||||
* 范例:`FE 2D 00 21 00 CD CC CC 3D CD CC 4C 3E 1A`
|
||||
* 说明:x:0.1m y:0.2m
|
||||
|
||||
* 里程计朝向
|
||||
* 车辆上电后的朝向为0度,逆时针为正。
|
||||
* 4字节消息类型:`2D 00 22 00`
|
||||
* 8字节数据内容:前4个字节为朝向角,单位为rad。
|
||||
* 数据类型为float
|
||||
* 范例:`FE 2D 00 22 00 9A 99 99 3E 00 00 00 00 D9`
|
||||
* 说明:0.3rad
|
||||
|
||||
* 左电机速度
|
||||
* 4字节消息类型:`2D 11 11 00`
|
||||
* 8字节数据内容:前4个字节为速度,单位rad/s
|
||||
* 数据类型:float
|
||||
* 范例:`FE 2D 11 11 00 CD CC CC 3D 00 00 00 00 C5`
|
||||
* 含义:0.1rad/s,如果要转换为m/s,需要乘以车轮半径
|
||||
|
||||
* 右电机速度:
|
||||
* 4字节消息类型:`2D 10 11 00`
|
||||
* 8字节数据内容:前4个字节为速度,单位rad/s
|
||||
* 数据类型:float
|
||||
* 范例:`FE 2D 10 11 00 CD CC 4C 3E 00 00 00 00 B4`
|
||||
* 含义:0.2rad/s,如果要转换为m/s,需要乘以车轮半径
|
||||
|
||||
* 转向角度:
|
||||
* 4字节消息类型:`2D 20 11 00`
|
||||
* 8字节数据内容:前4个字节为角度,单位rad
|
||||
* 数据类型:float
|
||||
范例:`FE 2D 20 11 00 CD CC CC 3D 00 00 00 00 26`
|
||||
* 含义:0.1rad,正方向为向左转
|
||||
|
||||
* 异常状态报告:
|
||||
* 4字节消息:`2D 00 23 00`
|
||||
* 8字节数据内容:[0]:TCU状态;[1]:左轮ECU状态 [2]:右轮ECU状态。每个字节0位为急停,1位为数据超时,2位为电流超限,3位为刹车状态
|
||||
* 范例:`FE 2D 00 23 00 01 02 05 00 00 00 00 00 0E`
|
||||
* 含义:TCU节点急停状态,左轮ECU编码器数据超时,右轮ECU急停状态且电流超限。
|
||||
|
||||
## 5、CRC8校验
|
||||
|
||||
* 使用CRC-8/MAXIM方式计算
|
||||
|
||||
* 示例:在线计算crc8(http://www.ip33.com/crc.html)
|
||||
|
||||
![img](./imgs/crc8-maxim.png)
|
||||
|
||||
<span id = "crc8-table"></span>
|
||||
|
||||
* 查表法计算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);
|
||||
}
|
||||
```
|
||||
|
||||
## 6 跨平台串口工具
|
||||
|
||||
推荐一款跨平台的串口工具Comtools: (https://github.com/Neutree/COMTool)
|
||||
|
||||
![Comtools.png](./imgs/Comtools.png)
|
After Width: | Height: | Size: 184 KiB |
Before Width: | Height: | Size: 369 KiB After Width: | Height: | Size: 369 KiB |
After Width: | Height: | Size: 225 KiB |
After Width: | Height: | Size: 50 KiB |
After Width: | Height: | Size: 64 KiB |
After Width: | Height: | Size: 77 KiB |
|
@ -0,0 +1,107 @@
|
|||
## 产品参数
|
||||
|
||||
<table>
|
||||
<tr>
|
||||
<td width="20%">尺寸</td>
|
||||
<td>1040*700*430mm</td>
|
||||
<td>驱动形式</td>
|
||||
<td>双轮独立驱动</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>轴距</td>
|
||||
<td>650mm</td>
|
||||
<td>转向形式</td>
|
||||
<td>阿卡曼转向</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>轮距</td>
|
||||
<td>600mm</td>
|
||||
<td>悬挂形式</td>
|
||||
<td>四轮双叉臂式独立悬挂</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>最大速度</td>
|
||||
<td>10km/h</td>
|
||||
<td>电池参数</td>
|
||||
<td>铅酸蓄电池 40AH 24V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>总质量</td>
|
||||
<td>80kg</td>
|
||||
<td>续航时间</td>
|
||||
<td>8小时</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>最小转弯半径</td>
|
||||
<td>1.2m</td>
|
||||
<td>续航里程</td>
|
||||
<td>80公里</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>最大爬坡度</td>
|
||||
<td>30°</td>
|
||||
<td>编码器</td>
|
||||
<td>4096线</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>离地高度</td>
|
||||
<td>110mm</td>
|
||||
<td>对外通信接口</td>
|
||||
<td>RS232</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>驻车</td>
|
||||
<td>电子驻车</td>
|
||||
<td>防护等级</td>
|
||||
<td> IP54</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>驱动电机</td>
|
||||
<td>500W</td>
|
||||
<td>对外供电</td>
|
||||
<td>24V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>转向电机</td>
|
||||
<td>250W</td>
|
||||
<td>遥控距离</td>
|
||||
<td>50M</td>
|
||||
</tr>
|
||||
</table>
|
||||
|
||||
## 产品尺寸
|
||||
|
||||
<div style="width:80%;">
|
||||
|
||||
![1.png](imgs/1.png)
|
||||
</div>
|
||||
|
||||
## 控制手柄参数
|
||||
|
||||
该手柄有自动休眠功能,长时间不操作,省电模块被激活后自动进入休眠模式,按下开机键即可唤醒手柄。
|
||||
|
||||
| 参数名称 | 参数内容 |
|
||||
|:----:|:------:|
|
||||
| 使用时间 | 约10小时 |
|
||||
| 无线频率 | 2.4GHz |
|
||||
| 接收范围 | 50m |
|
||||
|
||||
* * *
|
||||
|
||||
## 控制面板
|
||||
|
||||
控制面板清单:
|
||||
|
||||
| 名称 | 个数 | 说明 |
|
||||
|:--------:|:--:|:---------------------:|
|
||||
| 紧急停止 | 1 | 在紧急情况下请按下该紧急停止按钮 |
|
||||
| 电源 | 1 | 电源开启关闭按钮 |
|
||||
| 充电接口(IN) | 1 | 为内置电池充电 |
|
||||
| 电量显示 | 1 | 以百分比的形式显示AP1电池电量 |
|
||||
| 手柄接收 | 1 | 手柄接收器插口 |
|
||||
| RS232串口 | 1 | 使用串口数据线连接下位机与上位机,进行通信 |
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,58 @@
|
|||
## 产品概述
|
||||
|
||||
Autolabor
|
||||
M2采用前转向的阿克曼结构,四轮双叉臂式独立悬挂,具有100公斤强大负载能力。80公里续航里程。轻松应对各种复杂路况。车规级零部件,稳定可靠,防护等级IP54。配合高精度编码器可以实现高速运动和精准转向,有效提升稳定性和精度。
|
||||
|
||||
* * *
|
||||
|
||||
## 主要特性
|
||||
|
||||
* 可靠耐用,操作简单,无需组装,开机直接使用
|
||||
* 高通过性,爬坡能力十足,续航能力强
|
||||
* 高精度工业级编码器,定位精准
|
||||
* 高负载,负重可达100KG
|
||||
* 适应场景广泛,轻松应对各种复杂路况
|
||||
* 兼容多个系统,支持多种开发平台、控制方式
|
||||
* 支持ROS开发,提供ROS驱动包与运动模型
|
||||
* 雷达、摄像头、惯导等多种传感器随意组合搭配,拆装方便
|
||||
* 使用文档齐全,配备后续用户支持,并不断更新开发教程
|
||||
|
||||
* * *
|
||||
|
||||
## 产品清单
|
||||
|
||||
| 名称 | 数量 | 备注 |
|
||||
|:------:|:--:|----|
|
||||
| M2移动平台 | 1辆 | |
|
||||
| M2充电器 | 1个 | |
|
||||
| M2控制手柄 | 1套 | |
|
||||
| 串口数据线 | 1根 | |
|
||||
| 配套工具 | 1套 | |
|
||||
|
||||
* * *
|
||||
|
||||
## 使用提醒
|
||||
|
||||
* 产品边缘锋利,请小心接触,避免划伤
|
||||
* 产品表面为金属材质,请勿与电路板直接接触
|
||||
* 操控平台时避免速度过快,引起碰撞
|
||||
* 搬运时以及设置作业时,请勿落下或倒置
|
||||
* 非专业人员,请不要私自拆卸
|
||||
* 不使用非原厂标配的电池、电源、充电座
|
||||
* 运行时请勿用手触碰
|
||||
* 不要在有水的地方,存在腐蚀性、易燃性气体的环境内和靠近可燃性物质的地方使用
|
||||
* 不要放置在加热器或者大型卷线电阻器等发热体周围
|
||||
* 切勿将电机直接与商用电源连接
|
||||
|
||||
* * *
|
||||
|
||||
## 电池安全
|
||||
|
||||
* 请在有人看护的状态下充电,若人员离开请拔掉充电插头
|
||||
* 充电器在充电工作时,会向外界散发一定的热量,充电器与产品应放在通风干燥的环境中使用
|
||||
* 正常充电时,充电指示灯为红色,当转为绿色时为充满
|
||||
* 停止充电时,应先拔下插头,然后取下电池端插头
|
||||
* 产品长期不用,需三个月至半年补充一次电
|
||||
* 产品电池不可将电完全用完,否则会严重受损,容易造成不可修复
|
||||
|
||||
* * *
|
|
@ -0,0 +1,114 @@
|
|||
# 控制方式
|
||||
|
||||
M2可以使用手柄控制和上位机控制两种方式来控制,手柄控制权限高于上位机控制,下面将分别概述这两种控制方式。
|
||||
|
||||
## 手柄控制
|
||||
|
||||
### 概述
|
||||
|
||||
我们配送一个控制手柄用于控制M2移动。
|
||||
|
||||
![2.png](imgs/2.png)
|
||||
|
||||
### 使用说明
|
||||
|
||||
#### 手柄操作步骤
|
||||
|
||||
1. 长按手柄HOME键,灯光亮起,自动匹配。
|
||||
2. 匹配成功后,手柄会震动一下,跑马灯最左侧与最右侧灯常亮。
|
||||
3. 同时按下顶部L、LZ、R、RZ四键,手柄解锁。
|
||||
4. 在遥控底盘运动、调整线速度、调整角速度的时候需要长按L、LZ、R、RZ四键中任意一键。
|
||||
|
||||
#### 手柄按键说明
|
||||
|
||||
我们对于M2的手柄控制设计有几种速度档位,如下表。
|
||||
|
||||
<table>
|
||||
<tr align="center">
|
||||
<th>档位</th>
|
||||
<td>0档</td>
|
||||
<td>1档</td>
|
||||
<td>2档</td>
|
||||
<td>3档</td>
|
||||
<td>4档</td>
|
||||
<td>5档</td>
|
||||
</tr>
|
||||
<tr align="center">
|
||||
<th>速度</th>
|
||||
<td>16%</td>
|
||||
<td>33%</td>
|
||||
<td>50%</td>
|
||||
<td>66%</td>
|
||||
<td>83%</td>
|
||||
<td>100%</td>
|
||||
</tr>
|
||||
</table>
|
||||
|
||||
<table>
|
||||
<tr>
|
||||
<th>按键</th>
|
||||
<th>功能</th>
|
||||
<th width="50%">备注</th>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>左侧摇杆键</td>
|
||||
<td>控制M2前进与后退</td>
|
||||
<td>控制摇杆推动的力度控制速度,轻推低速移动,推到底为当前档位最高速</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>右侧摇杆键</td>
|
||||
<td>控制M2左右转向</td>
|
||||
<td>控制摇杆推动的力度控制角度,轻推小角度转向,推到底为最大角转向,松开自动回正</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>中区“—”键</td>
|
||||
<td>速度减档</td>
|
||||
<td>每按一下,速度降低一档,最低不得高于最底档,如0档</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>中区“+”键</td>
|
||||
<td>速度加档</td>
|
||||
<td>每按一下,速度提高一档,最高不得高于最高档,如5档</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>左区4控制键</td>
|
||||
<td>前/后/左/右控制运动方向</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>右区4控制键</td>
|
||||
<td>前/后/左/右控制运动方向</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>HOME键</td>
|
||||
<td>开机/急停</td>
|
||||
<td>紧急情况下,可按HOME键,M2会紧急刹车</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>顶部4控制键</td>
|
||||
<td>解锁/防误触</td>
|
||||
<td>手柄连接成功后,需同时按下4键解锁,控制时需长按任意一键,行驶过程中松开,M2会缓刹</td>
|
||||
</tr>
|
||||
</table>
|
||||
|
||||
* * *
|
||||
|
||||
## 上位机控制
|
||||
|
||||
### 概述
|
||||
|
||||
使用M2配送的串口数据线与上位机相连,按照预定义的**协议规则**,向下位机(底层硬件平台)发送指令,控制移动平台。
|
||||
|
||||
### 使用说明
|
||||
|
||||
使用接口线将下位机与上位机连接起来,向下位机发送指令。
|
||||
|
||||
### 指令发送方式
|
||||
|
||||
用户可按照自己的开发场景,选择不同的方式发送指令:
|
||||
|
||||
* 使用**串口调试助手**直接向下位机发送指令
|
||||
* 基于ROS开发可使用我们提供的**ROS驱动包**与下位机通信发送接收指令
|
||||
|
||||
|
|
@ -0,0 +1,27 @@
|
|||
## 手柄控制
|
||||
|
||||
### 使用手柄控制机器人运动
|
||||
|
||||
<iframe src="http://www.autolabor.com.cn/lib/video/docplay/26" frameborder="0" width="640" height="360" allowfullscreen></iframe>
|
||||
|
||||
更多详情,请查看[此处](http://www.autolabor.com.cn/usedoc/m2/chassis/use)
|
||||
|
||||
## ROS驱动安装与使用
|
||||
|
||||
### ROS驱动安装
|
||||
|
||||
<iframe src="http://www.autolabor.com.cn/lib/video/docplay/27" frameborder="0" width="640" height="360" allowfullscreen></iframe>
|
||||
|
||||
### ROS驱动使用
|
||||
|
||||
<iframe src="http://www.autolabor.com.cn/lib/video/docplay/28" frameborder="0" width="640" height="360" allowfullscreen></iframe>
|
||||
|
||||
更多详情,请查看[此处](http://www.autolabor.com.cn/usedoc/m2/chassis/chassis-m2)
|
||||
|
||||
## 串口协议
|
||||
|
||||
### 串口协议使用与说明
|
||||
|
||||
<iframe src="http://www.autolabor.com.cn/lib/video/docplay/29" frameborder="0" width="640" height="360" allowfullscreen></iframe>
|
||||
|
||||
更多详情,请查看[此处](http://www.autolabor.com.cn/usedoc/m2/chassis/custom-autocan)
|
44
conf.json
|
@ -7,7 +7,7 @@
|
|||
"uri 格式 3 - 绝对地址:https://www.baidu.com",
|
||||
"_readme 本身并没有什么用"
|
||||
],
|
||||
"index": "car/delivery",
|
||||
"index": "navigationKit/delivery",
|
||||
"rewrite": {
|
||||
},
|
||||
"plugin": {
|
||||
|
@ -24,28 +24,58 @@
|
|||
},
|
||||
"items": [
|
||||
{
|
||||
"name": "Autolabor M2底盘",
|
||||
"name": "Autolabor M2",
|
||||
"isOpen": true,
|
||||
"items": [
|
||||
{
|
||||
"name": "收货指南",
|
||||
"uri": "car/delivery"
|
||||
"uri": "navigationKit/delivery"
|
||||
},
|
||||
{
|
||||
"name": "组装教程",
|
||||
"uri": "car/assemble"
|
||||
"uri": "navigationKit/assemble"
|
||||
},
|
||||
{
|
||||
"name": "手柄控制",
|
||||
"uri": "car/use"
|
||||
"uri": "navigationKit/handle"
|
||||
},
|
||||
{
|
||||
"name": "软件介绍",
|
||||
"uri": "car/software"
|
||||
"uri": "navigationKit/software"
|
||||
},
|
||||
{
|
||||
"name": "规格参数",
|
||||
"uri": "car/parameter"
|
||||
"uri": "navigationKit/parameter"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Autolabor M2底盘",
|
||||
"isOpen": false,
|
||||
"items": [
|
||||
{
|
||||
"name": "产品概述",
|
||||
"uri": "chassis/overview"
|
||||
},
|
||||
{
|
||||
"name": "产品参数",
|
||||
"uri": "chassis/intro"
|
||||
},
|
||||
{
|
||||
"name": "控制方式",
|
||||
"uri": "chassis/use"
|
||||
},
|
||||
{
|
||||
"name": "串口协议",
|
||||
"uri": "chassis/custom-autocan"
|
||||
},
|
||||
{
|
||||
"name": "ROS驱动",
|
||||
"uri": "chassis/chassis-m2"
|
||||
},
|
||||
{
|
||||
"name": "视频教程",
|
||||
"uri": "chassis/video-lib"
|
||||
}
|
||||
]
|
||||
}
|
||||
|
|
After Width: | Height: | Size: 369 KiB |
Before Width: | Height: | Size: 238 KiB After Width: | Height: | Size: 238 KiB |
Before Width: | Height: | Size: 66 KiB After Width: | Height: | Size: 66 KiB |
Before Width: | Height: | Size: 185 KiB After Width: | Height: | Size: 185 KiB |
Before Width: | Height: | Size: 171 KiB After Width: | Height: | Size: 171 KiB |