This commit is contained in:
userName
2025-12-15 09:19:47 +08:00
commit 5e2dfc8ac8
16 changed files with 3555 additions and 0 deletions

5
.gitignore vendored Normal file
View File

@@ -0,0 +1,5 @@
.pio
.vscode/.browse.c_cpp.db*
.vscode/c_cpp_properties.json
.vscode/launch.json
.vscode/ipch

10
.vscode/extensions.json vendored Normal file
View File

@@ -0,0 +1,10 @@
{
// See http://go.microsoft.com/fwlink/?LinkId=827846
// for the documentation about the extensions.json format
"recommendations": [
"platformio.platformio-ide"
],
"unwantedRecommendations": [
"ms-vscode.cpptools-extension-pack"
]
}

9
.vscode/settings.json vendored Normal file
View File

@@ -0,0 +1,9 @@
{
"files.associations": {
"cmath": "cpp",
"array": "cpp",
"string": "cpp",
"string_view": "cpp"
},
"C_Cpp.errorSquiggles": "disabled"
}

0
LVEDO.cpp Normal file
View File

View File

@@ -0,0 +1,92 @@
# 数据格式说明
## 1. 雷达数据格式 (HBR01)
### 格式特征
-`HBR01:` 开头
- 后跟8个用逗号分隔的数值字段
- 每行一条数据记录
### 数据字段说明
```
HBR01:presence,heart_rate,breath_rate,motion,rssi,heartbeat_waveform,breathing_waveform,raw_signal
```
### 字段含义
1. `presence` - 人员存在状态 (0=无人, 1=有人)
2. `heart_rate` - 心率 (bpm)
3. `breath_rate` - 呼吸率 (bpm)
4. `motion` - 运动状态 (0=静止, 1=运动)
5. `rssi` - 信号强度
6. `heartbeat_waveform` - 心跳波形数据
7. `breathing_waveform` - 呼吸波形数据
8. `raw_signal` - 原始信号数据
### 示例数据
```
HBR01:1,72,16,0,-45,120,45,-25
HBR01:0,0,0,0,-50,0,0,10
```
### 处理方式
在ESP32代码中通过 `parseSensorLine()` 函数处理,按行读取并解析逗号分隔的数值。
## 2. JSON数据格式
### 格式特征
- 以花括号 `{` 开始,`}` 结束
- 符合标准JSON格式
- 可能因长度超过BLE MTU而需要分包传输
### 示例数据
```json
{
"type": "radarData",
"deviceId": 1001,
"timestamp": 1640995200000,
"presence": 1,
"heartRate": 72.5,
"breathRate": 16.2,
"motion": 0,
"rssi": -45,
"heartbeatWaveform": 120,
"breathingWaveform": 45,
"rawSignal": -25
}
```
### 分包传输特点
- 每包最大20字节BLE限制
- 需要通过匹配花括号来重组完整JSON
- 可能出现一个完整JSON被分成多个BLE包的情况
### 接收处理方式
使用JavaScript代码中的 `processChunk()` 函数处理:
1. 将接收到的数据片段追加到缓冲区
2. 通过计数花括号来识别完整的JSON对象
3. 提取完整JSON并解析
4. 清理缓冲区中已处理的部分
## 3. 两种格式的主要区别
| 特性 | 雷达数据 (HBR01) | JSON数据 |
|------|------------------|----------|
| 格式标识 | HBR01:开头 | 花括号{}包围 |
| 数据结构 | 固定8个数值字段 | 灵活的键值对 |
| 分隔符 | 逗号分隔 | JSON标准格式 |
| 分包处理 | 按行处理 | 按花括号匹配 |
| 解析方式 | 数值转换 | JSON解析 |
## 4. 处理建议
### 雷达数据处理
- 按行读取处理
- 验证以"HBR01:"开头
- 按逗号分割提取8个字段
- 进行数值有效性检查
### JSON数据处理
- 使用缓冲区累积数据
- 通过花括号匹配识别完整对象
- 使用JSON解析库处理
- 注意缓冲区大小限制和清理

44
generate_radar_data.py Normal file
View File

@@ -0,0 +1,44 @@
import random
import time
def generate_radar_data_lines(count=100):
"""生成模拟雷达数据行"""
lines = []
for i in range(count):
# 生成8个随机数值字段
# 字段含义参考代码: presence, heart_rate, breath_rate, motion, rssi, heartbeat_waveform, breathing_waveform, raw_signal
presence = random.choice([0, 1]) # 0=无人, 1=有人
heart_rate = random.uniform(0, 200) if presence else 0 # 心率 (bpm)
breath_rate = random.uniform(0, 60) if presence else 0 # 呼吸率 (bpm)
motion = random.choice([0, 1]) if presence else 0 # 运动状态
rssi = random.randint(-100, -30) # 信号强度
heartbeat_waveform = random.randint(-1000, 1000) # 心跳波形
breathing_waveform = random.randint(-1000, 1000) # 呼吸波形
raw_signal = random.randint(-100, 100) # 原始信号
# 格式化为HBR01数据行
line = f"HBR01:{presence},{heart_rate:.0f},{breath_rate:.0f},{motion},{rssi},{heartbeat_waveform},{breathing_waveform},{raw_signal}"
lines.append(line)
return lines
def save_to_file(lines, filename="generated_sensor_data.txt"):
"""保存数据到文件"""
with open(filename, "w", encoding="utf-8") as f:
for line in lines:
f.write(line + "\n")
print(f"已生成 {len(lines)} 行雷达数据并保存到 {filename}")
def main():
# 生成1000行测试数据
lines = generate_radar_data_lines(1000)
save_to_file(lines, "generated_sensor_data.txt")
# 显示前10行作为示例
print("\n前10行数据示例:")
for i, line in enumerate(lines[:10]):
print(f"{i+1:2d}: {line}")
if __name__ == "__main__":
main()

37
include/README Normal file
View File

@@ -0,0 +1,37 @@
This directory is intended for project header files.
A header file is a file containing C declarations and macro definitions
to be shared between several project source files. You request the use of a
header file in your project source file (C, C++, etc) located in `src` folder
by including it, with the C preprocessing directive `#include'.
```src/main.c
#include "header.h"
int main (void)
{
...
}
```
Including a header file produces the same results as copying the header file
into each source file that needs it. Such copying would be time-consuming
and error-prone. With a header file, the related declarations appear
in only one place. If they need to be changed, they can be changed in one
place, and programs that include the header file will automatically use the
new version when next recompiled. The header file eliminates the labor of
finding and changing all the copies as well as the risk that a failure to
find one copy will result in inconsistencies within a program.
In C, the convention is to give header files names that end with `.h'.
Read more about using header files in official GCC documentation:
* Include Syntax
* Include Operation
* Once-Only Headers
* Computed Includes
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html

46
lib/README Normal file
View File

@@ -0,0 +1,46 @@
This directory is intended for project specific (private) libraries.
PlatformIO will compile them to static libraries and link into the executable file.
The source code of each library should be placed in a separate directory
("lib/your_library_name/[Code]").
For example, see the structure of the following example libraries `Foo` and `Bar`:
|--lib
| |
| |--Bar
| | |--docs
| | |--examples
| | |--src
| | |- Bar.c
| | |- Bar.h
| | |- library.json (optional. for custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
| |
| |--Foo
| | |- Foo.c
| | |- Foo.h
| |
| |- README --> THIS FILE
|
|- platformio.ini
|--src
|- main.c
Example contents of `src/main.c` using Foo and Bar:
```
#include <Foo.h>
#include <Bar.h>
int main (void)
{
...
}
```
The PlatformIO Library Dependency Finder will find automatically dependent
libraries by scanning project source files.
More information about PlatformIO Library Dependency Finder
- https://docs.platformio.org/page/librarymanager/ldf.html

17
platformio.ini Normal file
View File

@@ -0,0 +1,17 @@
; PlatformIO Project Configuration File
;
; Build options: build flags, source filter
; Upload options: custom upload port, speed and extra flags
; Library options: dependencies, extra library storages
; Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html
[env:freenove_esp32_s3_wroom]
platform = espressif32
board = freenove_esp32_s3_wroom
framework = arduino
lib_deps =
bblanchon/ArduinoJson@^7.4.2
emelianov/modbus-esp8266@^4.1.0

1316
src/main.cpp Normal file

File diff suppressed because it is too large Load Diff

243
tcp-output(5).py Normal file
View File

@@ -0,0 +1,243 @@
import time
import random
import requests
from datetime import datetime
# 添加InfluxDB配置
INFLUXDB_URL = 'http://8.134.11.76:8086'
INFLUXDB_TOKEN = 'KuTa5ZsqoHIhi2IglOO06zExUYw1_mJ6K0mcA9X1y6O6CJDog3_Cgr8mUw1SwpuCCKRElqxa6wAhrrhsYPytkg=='
INFLUXDB_ORG = 'gzlg'
INFLUXDB_BUCKET = 'gzlg'
# 配置设备ID设置为0则自动注册设置为1000~1999则固定使用该ID
CONFIG_DEVICE_ID = 1002
# 分配的设备ID初始为None注册后更新
assigned_device_id = None
# 相位计数器
phase_counter = 0
def get_next_device_id():
"""从InfluxDB查询已注册的设备ID并返回下一个可用的ID"""
try:
# 查询InfluxDB中已存在的设备ID
query = '''
from(bucket: "{}")
|> range(start: -365d)
|> filter(fn: (r) => r["_measurement"] == "device_data")
|> keep(columns: ["deviceId"])
|> distinct(column: "deviceId")
|> sort()
'''.format(INFLUXDB_BUCKET)
url = f"{INFLUXDB_URL}/api/v2/query?org={INFLUXDB_ORG}"
headers = {
"Authorization": f"Token {INFLUXDB_TOKEN}",
"Content-Type": "application/json"
}
data = {
"query": query
}
response = requests.post(url, headers=headers, json=data)
print(f"🔍 InfluxDB查询响应状态: {response.status_code}")
if response.status_code == 200:
print(f"🔍 InfluxDB查询响应内容: {response.text}")
# 解析响应数据
device_ids = []
lines = response.text.strip().split('\n')
for line in lines:
if line and not line.startswith('#') and 'deviceId' not in line:
try:
# 解析CSV格式的响应数据
# 格式类似于: ,_result,0,1001,1001
parts = line.split(',')
if len(parts) >= 5:
# deviceId在第4个位置索引3
device_id_str = parts[3].strip()
if device_id_str:
device_id = int(device_id_str)
if 1000 <= device_id <= 1999: # 只考虑1000-1999范围内的设备ID
device_ids.append(device_id)
print(f"📱 发现设备ID: {device_id}")
except (ValueError, IndexError) as e:
# 忽略解析错误的行
print(f"⚠️ 忽略无法解析的行: {line}")
continue
# 对设备ID进行排序
device_ids.sort()
# 找到下一个可用的ID
next_id = 1001
for device_id in device_ids:
if device_id == next_id:
next_id += 1
elif device_id > next_id:
break
# 确保ID在有效范围内
if next_id > 1999:
next_id = 1001 # 如果超出范围,从头开始
print(f"📊 查询到已注册设备: {device_ids}")
print(f"🆕 分配新设备ID: {next_id}")
return next_id
else:
print(f"❌ 查询InfluxDB失败: {response.status_code} - {response.text}")
# 如果查询失败返回默认ID
return 1001
except Exception as e:
print(f"❌ 查询设备ID时出错: {e}")
import traceback
traceback.print_exc()
# 如果查询失败返回默认ID
return 1001
def register_device():
"""注册设备并获取设备ID"""
global assigned_device_id
# 检查配置的设备ID
if CONFIG_DEVICE_ID == 0:
# 自动注册模式
try:
# 获取下一个可用的设备ID
next_device_id = get_next_device_id()
assigned_device_id = next_device_id
print(f"✅ 设备注册成功! 设备ID: {assigned_device_id} (0x{assigned_device_id:04X})")
return True
except Exception as e:
print(f"❌ 注册过程中发生错误: {e}")
return False
elif 1000 <= CONFIG_DEVICE_ID <= 1999:
# 固定设备ID模式
assigned_device_id = CONFIG_DEVICE_ID
print(f"✅ 使用固定设备ID: {assigned_device_id} (0x{assigned_device_id:04X})")
return True
else:
# 配置的设备ID无效
print(f"❌ 配置的设备ID {CONFIG_DEVICE_ID} 无效请设置为0自动注册或1000~1999之间的值")
return False
def save_data_to_influxdb(protocol_id, data_value):
"""保存数据到InfluxDB"""
try:
# 创建数据点
data_point = {
"measurement": "device_data",
"tags": {
"deviceId": assigned_device_id
},
"time": datetime.utcnow().isoformat() + "Z",
"fields": {}
}
# 根据协议ID确定字段名
field_mapping = {
1: "heartRate",
2: "breathingRate",
3: "heartPhase",
4: "breathingPhase",
13: "personDetected",
14: "humanActivity"
}
if protocol_id in field_mapping:
field_name = field_mapping[protocol_id]
# 对特定字段进行数值处理
if protocol_id in [1, 2]: # 心率和呼吸频率需要除以10
data_point["fields"][field_name] = float(data_value) / 10.0
elif protocol_id in [3, 4]: # 相位数据需要除以1000
data_point["fields"][field_name] = float(data_value) / 1000.0
elif protocol_id in [13, 14]: # 人检/活动数据确保是整数0或1
# 强制转换为整数确保只有0或1
data_point["fields"][field_name] = int(data_value)
if data_point["fields"][field_name] not in [0, 1]:
print(f"⚠️ 警告: 人检/活动数据值异常: {data_value}, 强制转换为: {data_point['fields'][field_name]}")
else:
data_point["fields"][field_name] = data_value
print(f"📊 准备保存数据: 协议ID={protocol_id}, 字段={field_name}, 值={data_point['fields'][field_name]}, 原始值={data_value}")
# 发送数据到InfluxDB
url = f"{INFLUXDB_URL}/api/v2/write?org={INFLUXDB_ORG}&bucket={INFLUXDB_BUCKET}"
headers = {
"Authorization": f"Token {INFLUXDB_TOKEN}",
"Content-Type": "text/plain; charset=utf-8"
}
# 构造行协议格式的数据,明确指定数据类型
if protocol_id in [13, 14]:
# 对于人检/活动数据,使用整数格式
line_protocol = f"device_data,deviceId={assigned_device_id} {field_name}={int(data_point['fields'][field_name])}i"
else:
# 对于其他数据,使用浮点数格式
line_protocol = f"device_data,deviceId={assigned_device_id} {field_name}={data_point['fields'][field_name]}"
response = requests.post(url, headers=headers, data=line_protocol)
if response.status_code == 204:
print(f"✅ 数据已保存到InfluxDB设备{assigned_device_id}上: {field_name}={data_point['fields'][field_name]}")
else:
print(f"❌ 保存数据到InfluxDB失败: {response.status_code} - {response.text}")
else:
print(f"⚠️ 未知的协议ID: {protocol_id}")
except Exception as e:
print(f"❌ 保存数据到InfluxDB时出错: {e}")
import traceback
traceback.print_exc()
def main():
global assigned_device_id, phase_counter
try:
# 第一步注册设备获取设备ID
if not register_device():
print("❌ 设备注册失败,程序退出")
return
print(f"🎯 开始使用设备ID {assigned_device_id} 发送数据...")
# 第二步:开始发送数据
while True:
# 初始化数据值
data_value = 0
# 每发送100个相位数据后发送其他数据
if phase_counter < 2:
# 发送相位数据 (心率相位或呼吸相位)
protocol_id = random.choice([3, 4]) # 3=心率相位, 4=呼吸相位
data_value = random.randint(-10000, 10000)
phase_counter += 1
else:
# 重置计数器
phase_counter = 0
# 发送其他数据
protocol_id = random.choice([1, 2, 13, 14]) # 1=心跳, 2=呼吸, 13=检测到人, 14=人体活动
if protocol_id == 1: # 心跳
data_value = random.randint(600, 1000)
elif protocol_id == 2: # 呼吸
data_value = random.randint(120, 200)
elif protocol_id == 13: # 检测到人1检测到0未检测到
data_value = random.choice([0, 1])
elif protocol_id == 14: # 人体活动1活动0静止
data_value = random.choice([0, 1])
# 直接发送数据到InfluxDB
save_data_to_influxdb(protocol_id, data_value)
# 设置发送间隔
time.sleep(0.1) # 每100ms发送一次数据
except KeyboardInterrupt:
print(f"\n🛑 设备 {assigned_device_id} 发送端已停止")
except Exception as e:
print(f"❌ 发生错误: {e}")
if __name__ == "__main__":
main()

11
test/README Normal file
View File

@@ -0,0 +1,11 @@
This directory is intended for PlatformIO Test Runner and project tests.
Unit Testing is a software testing method by which individual units of
source code, sets of one or more MCU program modules together with associated
control data, usage procedures, and operating procedures, are tested to
determine whether they are fit for use. Unit testing finds problems early
in the development cycle.
More information about PlatformIO Unit Testing:
- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html

1177
test/app.cpp Normal file

File diff suppressed because it is too large Load Diff

72
test_json_chunk_sender.py Normal file
View File

@@ -0,0 +1,72 @@
import json
import time
def simulate_json_chunk_sending(data, chunk_size=15):
"""
模拟JSON数据分包发送
"""
json_string = json.dumps(data)
print(f"原始JSON数据: {json_string}")
print(f"数据总长度: {len(json_string)} 字符")
chunks = []
# 分包
for i in range(0, len(json_string), chunk_size):
chunk = json_string[i:i+chunk_size]
chunks.append(chunk)
print(f"\n分包结果 ({len(chunks)} 个包):")
for i, chunk in enumerate(chunks):
print(f"{i+1}: {chunk}")
return chunks
def create_sample_json_data():
"""
创建示例JSON数据
"""
return {
"type": "radarData",
"deviceId": 1001,
"timestamp": int(time.time() * 1000),
"presence": 1,
"heartRate": 72.5,
"breathRate": 16.2,
"motion": 0,
"rssi": -45,
"heartbeatWaveform": 120,
"breathingWaveform": 45,
"rawSignal": -25
}
def create_status_json_data():
"""
创建状态JSON数据
"""
return {
"type": "status",
"wifiConfigured": True,
"wifiConnected": True,
"ipAddress": "192.168.1.100",
"deviceId": 1001
}
def main():
print("=== JSON分包发送模拟测试 ===\n")
# 测试雷达数据
print("1. 雷达数据分包测试:")
radar_data = create_sample_json_data()
simulate_json_chunk_sending(radar_data, 15)
print("\n" + "="*50 + "\n")
# 测试状态数据
print("2. 状态数据分包测试:")
status_data = create_status_json_data()
simulate_json_chunk_sending(status_data, 15)
print("\n=== 测试完成 ===")
if __name__ == "__main__":
main()

82
test_json_parser.js Normal file
View File

@@ -0,0 +1,82 @@
// JSON分包接收处理函数
let streamBuffer = ""
function addLog(message) {
console.log(message);
}
function handleParsedJson(obj) {
console.log("处理解析后的JSON对象:", obj);
}
function processChunk(fragment){
addLog('进入processChunk')
streamBuffer += fragment
let braceCount = 0
let jsonStart = -1
for(let i = 0; i < streamBuffer.length; i++){
const ch = streamBuffer[i]
if(ch === "{"){
if(braceCount === 0){
jsonStart = i
}
braceCount++
}else if(ch === "}"){
braceCount--
if(braceCount === 0 && jsonStart !== -1){
const jsonStr = streamBuffer.substring(jsonStart, i + 1)
addLog("收到完整JSON:" + jsonStr)
try{
const obj = JSON.parse(jsonStr)
handleParsedJson(obj)
}catch(e){
addLog("JSON解析失败:" + e)
}
streamBuffer = streamBuffer.substring(i + 1)
i = -1
jsonStart = -1
}
}
}
//缓冲区过大时清理防越界
if (streamBuffer.length > 20000) {
addLog("⚠ 清空超大缓冲区(异常保护)")
streamBuffer = ""
braceCount = 0
jsonStart = -1
}
}
// 模拟分包发送JSON数据
function simulateJSONSending() {
const jsonData = {
type: "radarData",
deviceId: 1001,
timestamp: Date.now(),
presence: 1,
heartRate: 72.5,
breathRate: 16.2,
motion: 0,
rssi: -45,
heartbeatWaveform: 120,
breathingWaveform: 45,
rawSignal: -25
};
const jsonString = JSON.stringify(jsonData);
console.log("原始JSON数据:", jsonString);
// 模拟分包发送
const packetSize = 15; // 每包15个字符
for (let i = 0; i < jsonString.length; i += packetSize) {
const packet = jsonString.substring(i, Math.min(i + packetSize, jsonString.length));
console.log(`发送分包 ${Math.floor(i/packetSize)+1}:`, packet);
processChunk(packet);
}
}
// 测试函数
console.log("=== 开始测试JSON分包接收处理 ===");
simulateJSONSending();
console.log("=== 测试完成 ===");

394
传感器数据.txt Normal file
View File

@@ -0,0 +1,394 @@
HBR01:0,0,0,0,9,0,0,-30
HBR01:0,0,0,0,9,0,0,-20
HBR01:0,0,0,0,9,0,0,-21
HBR01:0,0,0,0,9,0,0,-19
HBR01:0,0,0,0,9,0,0,-22
HBR01:0,0,0,0,9,0,0,-36
HBR01:0,0,0,0,9,0,0,-35
HBR01:0,0,0,0,9,0,0,-39
HBR01:0,0,0,0,9,0,0,-40
HBR01:0,0,0,0,9,0,0,-40
HBR01:0,0,0,0,9,0,0,-40
HBR01:0,0,0,0,9,0,0,-40
HBR01:0,0,0,0,9,0,0,-23
HBR01:0,0,0,0,9,0,0,0
HBR01:0,0,0,0,9,0,0,0
HBR01:0,0,0,0,9,0,0,-11
HBR01:0,0,0,0,9,0,0,-19
HBR01:0,0,0,0,9,0,0,-29
HBR01:0,0,0,0,9,0,0,-34
HBR01:0,0,0,0,9,0,0,-19
HBR01:0,0,0,0,9,0,0,-22
HBR01:0,0,0,0,9,0,0,-10
HBR01:0,0,0,0,9,0,0,-9
HBR01:0,0,0,0,9,0,0,-12
HBR01:0,0,0,0,9,0,0,-13
HBR01:0,0,0,0,9,0,0,-19
HBR01:0,0,0,0,9,0,0,-23
HBR01:0,0,0,0,9,0,0,-33
HBR01:0,0,0,0,9,0,0,-33
HBR01:0,0,0,0,9,0,0,-19
HBR01:0,0,0,0,9,0,0,-3
HBR01:0,0,0,0,9,0,0,-22
HBR01:0,0,0,0,9,0,0,-13
HBR01:0,0,0,0,9,0,0,-18
HBR01:0,0,0,0,9,0,0,-12
HBR01:0,0,0,0,9,0,0,0
HBR01:0,0,0,0,9,0,0,-16
HBR01:0,0,0,0,9,0,0,-27
HBR01:0,0,0,0,9,0,0,-14
HBR01:0,0,0,0,9,0,0,-23
HBR01:0,0,0,0,9,0,0,-16
HBR01:0,0,0,0,10,0,0,-40
HBR01:0,0,0,0,10,0,0,-42
HBR01:0,0,0,0,10,0,0,-38
HBR01:0,0,0,0,10,0,0,-40
HBR01:0,0,0,0,10,0,0,-43
HBR01:0,0,0,0,10,0,0,0
HBR01:0,0,0,0,10,0,0,0
HBR01:0,0,0,0,10,0,0,0
HBR01:0,0,0,0,10,0,0,1
HBR01:0,0,0,0,10,0,0,0
HBR01:0,0,0,0,10,0,0,0
HBR01:0,0,0,0,10,0,0,0
HBR01:0,0,0,0,10,0,0,-4
HBR01:0,0,0,0,10,0,0,-22
HBR01:0,0,0,0,10,0,0,-40
HBR01:0,0,0,0,11,0,0,-57
HBR01:0,0,0,0,11,0,0,-29
HBR01:0,0,0,0,11,0,0,-22
HBR01:0,0,0,0,11,0,0,-10
HBR01:0,0,0,0,11,0,0,-11
HBR01:0,0,0,0,11,0,0,-11
HBR01:0,0,0,0,11,0,0,-10
HBR01:0,0,0,0,11,0,0,4
HBR01:0,0,0,0,11,0,0,-16
HBR01:0,0,0,0,11,0,0,-59
HBR01:0,0,0,0,11,0,0,-9
HBR01:0,0,0,0,11,0,0,-15
HBR01:0,0,0,0,11,0,0,-21
HBR01:0,0,0,0,11,0,0,-26
HBR01:0,0,0,0,11,0,0,-28
HBR01:0,0,0,0,11,0,0,-26
HBR01:0,0,0,0,11,0,0,-26
HBR01:0,0,0,0,11,0,0,-26
HBR01:0,0,0,0,11,0,0,-24
HBR01:0,0,0,0,11,0,0,-24
HBR01:0,0,0,0,11,0,0,-14
HBR01:0,0,0,0,11,0,0,-28
HBR01:0,0,0,0,11,0,0,-30
HBR01:0,0,0,0,11,0,0,-9
HBR01:0,0,0,0,11,0,0,-25
HBR01:0,0,0,0,11,0,0,-29
HBR01:0,0,0,0,11,0,0,-24
HBR01:0,0,0,0,11,0,0,-23
HBR01:0,0,0,0,11,0,0,-31
HBR01:0,0,0,0,11,0,0,-26
HBR01:0,0,0,0,11,0,0,-25
HBR01:0,0,0,0,11,0,0,-21
HBR01:0,0,0,0,11,0,0,-36
HBR01:0,0,0,0,11,0,0,-25
HBR01:0,0,0,0,11,0,0,-26
HBR01:0,0,0,0,11,0,0,-39
HBR01:0,0,0,0,11,0,0,-27
HBR01:0,0,0,0,11,0,0,-24
HBR01:0,0,0,0,11,0,0,-24
HBR01:0,0,0,0,11,0,0,-27
HBR01:0,0,0,0,11,0,0,-27
HBR01:0,0,0,0,11,0,0,-26
HBR01:0,0,0,0,11,0,0,-36
HBR01:0,0,0,0,11,0,0,-40
HBR01:0,0,0,0,11,0,0,-40
HBR01:0,0,0,0,11,0,0,-40
HBR01:0,0,0,0,11,0,0,-40
HBR01:0,0,0,0,11,0,0,-40
HBR01:0,0,0,0,11,0,0,-59
HBR01:0,0,0,0,11,0,0,-41
HBR01:0,0,0,0,11,0,0,-52
HBR01:0,0,0,0,11,0,0,-39
HBR01:0,0,0,0,11,0,0,-35
HBR01:0,0,0,0,11,0,0,-43
HBR01:0,0,0,0,11,0,0,-30
HBR01:0,0,0,0,11,0,0,-17
HBR01:0,0,0,0,11,0,0,-11
HBR01:0,0,0,0,11,0,0,-20
HBR01:0,0,0,0,11,0,0,-11
HBR01:0,0,0,0,11,0,0,-16
HBR01:0,0,0,0,11,0,0,-11
HBR01:0,0,0,0,11,0,0,-12
HBR01:0,0,0,0,11,0,0,-7
HBR01:0,0,0,0,11,0,0,-9
HBR01:0,0,0,0,11,0,0,-11
HBR01:0,0,0,0,11,0,0,-10
HBR01:0,0,0,0,11,0,0,-14
HBR01:0,0,0,0,11,0,0,-24
HBR01:0,0,0,0,11,0,0,-15
HBR01:0,0,0,0,11,0,0,-20
HBR01:0,0,0,0,11,0,0,-16
HBR01:0,0,0,0,11,0,0,-11
HBR01:0,0,0,0,11,0,0,-12
HBR01:0,0,0,0,12,0,0,9
HBR01:0,0,0,0,12,0,0,-11
HBR01:0,0,0,0,12,0,0,-11
HBR01:0,0,0,0,12,0,0,-16
HBR01:0,0,0,0,12,0,0,11
HBR01:0,0,0,0,12,0,0,11
HBR01:0,0,0,0,12,0,0,1
HBR01:0,0,0,0,12,0,0,-4
HBR01:0,0,0,0,12,0,0,-13
HBR01:0,0,0,0,12,0,0,-3
HBR01:0,0,0,0,12,0,0,-6
HBR01:0,0,0,0,12,0,0,3
HBR01:0,0,0,0,12,0,0,-12
HBR01:0,0,0,0,12,0,0,-23
HBR01:0,0,0,0,12,0,0,-40
HBR01:0,0,0,0,12,0,0,-22
HBR01:0,0,0,0,12,0,0,-40
HBR01:0,0,0,0,12,0,0,-20
HBR01:0,0,0,0,12,0,0,-21
HBR01:0,0,0,0,12,0,0,-42
HBR01:0,0,0,0,12,0,0,-40
HBR01:0,0,0,0,13,0,0,-51
HBR01:0,0,0,0,13,0,0,-40
HBR01:0,0,0,0,13,0,0,-40
HBR01:0,0,0,0,13,0,0,-40
HBR01:0,0,0,0,13,0,0,-45
HBR01:0,0,0,0,13,0,0,-48
HBR01:0,0,0,0,13,0,0,-35
HBR01:0,0,0,0,13,0,0,-38
HBR01:0,0,0,0,13,0,0,-48
HBR01:0,0,0,0,13,0,0,-19
HBR01:0,0,0,0,13,0,0,-12
HBR01:0,0,0,0,13,0,0,-26
HBR01:0,0,0,0,13,0,0,-23
HBR01:0,0,0,0,13,0,0,-9
HBR01:0,0,0,0,13,0,0,4
HBR01:0,0,0,0,13,0,0,-1
HBR01:0,0,0,0,13,0,0,0
HBR01:0,0,0,0,13,0,0,0
HBR01:0,0,0,0,13,0,0,-1
HBR01:0,0,0,0,13,0,0,1
HBR01:0,0,0,0,13,0,0,0
HBR01:0,0,0,0,13,0,0,-1
HBR01:0,0,0,0,13,0,0,0
HBR01:0,0,0,0,13,0,0,21
HBR01:0,0,0,0,13,0,0,15
HBR01:0,0,0,0,13,0,0,0
HBR01:0,0,0,0,13,0,0,21
HBR01:0,0,0,0,14,0,0,18
HBR01:0,0,0,0,14,0,0,0
HBR01:0,0,0,0,14,0,0,2
HBR01:0,0,0,0,14,0,0,4
HBR01:0,0,0,0,14,0,0,-3
HBR01:0,0,0,0,14,0,0,5
HBR01:0,0,0,0,14,0,0,-1
HBR01:0,0,0,0,14,0,0,-22
HBR01:0,0,0,0,14,0,0,4
HBR01:0,0,0,0,14,0,0,3
HBR01:0,0,0,0,14,0,0,-18
HBR01:0,0,0,0,14,0,0,-16
HBR01:0,0,0,0,14,0,0,-6
HBR01:0,0,0,0,14,0,0,-23
HBR01:0,0,0,0,14,0,0,-28
HBR01:0,0,0,0,14,0,0,-24
HBR01:0,0,0,0,14,0,0,-24
HBR01:0,0,0,0,14,0,0,-39
HBR01:0,0,0,0,14,0,0,-24
HBR01:0,0,0,0,14,0,0,-38
HBR01:0,0,0,0,14,0,0,-40
HBR01:0,0,0,0,14,0,0,-37
HBR01:0,0,0,0,14,0,0,-40
HBR01:0,0,0,0,14,0,0,-40
HBR01:0,0,0,0,14,0,0,-40
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,15,0,0,-45
HBR01:0,0,0,0,15,0,0,-36
HBR01:0,0,0,0,15,0,0,-29
HBR01:0,0,0,0,15,0,0,-10
HBR01:0,0,0,0,15,0,0,-43
HBR01:0,0,0,0,15,0,0,-12
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,15,0,0,-33
HBR01:0,0,0,0,15,0,0,-37
HBR01:0,0,0,0,15,0,0,-30
HBR01:0,0,0,0,15,0,0,-35
HBR01:0,0,0,0,15,0,0,-26
HBR01:0,0,0,0,15,0,0,2
HBR01:0,0,0,0,15,0,0,-30
HBR01:0,0,0,0,15,0,0,0
HBR01:0,0,0,0,15,0,0,-22
HBR01:0,0,0,0,15,0,0,-23
HBR01:0,0,0,0,15,0,0,-30
HBR01:0,0,0,0,15,0,0,-33
HBR01:0,0,0,0,15,0,0,-15
HBR01:0,0,0,0,15,0,0,0
HBR01:0,0,0,0,15,0,0,-12
HBR01:0,0,0,0,15,0,0,-20
HBR01:0,0,0,0,15,0,0,-20
HBR01:0,0,0,0,15,0,0,-10
HBR01:0,0,0,0,15,0,0,-25
HBR01:0,0,0,0,15,0,0,-35
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,15,0,0,-62
HBR01:0,0,0,0,15,0,0,-33
HBR01:0,0,0,0,15,0,0,-24
HBR01:0,0,0,0,15,0,0,-30
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,15,0,0,-45
HBR01:0,0,0,0,15,0,0,-29
HBR01:0,0,0,0,15,0,0,-31
HBR01:0,0,0,0,15,0,0,-37
HBR01:0,0,0,0,15,0,0,-43
HBR01:0,0,0,0,15,0,0,-23
HBR01:0,0,0,0,15,0,0,-18
HBR01:0,0,0,0,15,0,0,-7
HBR01:0,0,0,0,15,0,0,-21
HBR01:0,0,0,0,15,0,0,0
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,16,0,0,-69
HBR01:0,0,0,0,16,0,0,-30
HBR01:0,0,0,0,16,0,0,-34
HBR01:0,0,0,0,16,0,0,-1
HBR01:0,0,0,0,16,0,0,-1
HBR01:0,0,0,0,16,0,0,-8
HBR01:0,0,0,0,16,0,0,-26
HBR01:0,0,0,0,16,0,0,-15
HBR01:0,0,0,0,16,0,0,-16
HBR01:0,0,0,0,16,0,0,-17
HBR01:0,0,0,0,16,0,0,-26
HBR01:0,0,0,0,16,0,0,-14
HBR01:0,0,0,0,16,0,0,-16
HBR01:0,0,0,0,16,0,0,-18
HBR01:0,0,0,0,16,0,0,-14
HBR01:0,0,0,0,16,0,0,-9
HBR01:0,0,0,0,16,0,0,-9
HBR01:0,0,0,0,16,0,0,-14
HBR01:0,0,0,0,16,0,0,-16
HBR01:0,0,0,0,16,0,0,-30
HBR01:0,0,0,0,16,0,0,-40
HBR01:0,0,0,0,15,0,0,-23
HBR01:0,0,0,0,15,0,0,-27
HBR01:0,0,0,0,15,0,0,-23
HBR01:0,0,0,0,15,0,0,-11
HBR01:0,0,0,0,15,0,0,-21
HBR01:0,0,0,0,15,0,0,-22
HBR01:0,0,0,0,15,0,0,-12
HBR01:0,0,0,0,15,0,0,-16
HBR01:0,0,0,0,15,0,0,-35
HBR01:0,0,0,0,15,0,0,-18
HBR01:0,0,0,0,15,0,0,-18
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,15,0,0,-25
HBR01:0,0,0,0,16,0,0,-1
HBR01:0,0,0,0,16,0,0,0
HBR01:0,0,0,0,16,0,0,0
HBR01:0,0,0,0,16,0,0,-24
HBR01:0,0,0,0,16,0,0,-16
HBR01:0,0,0,0,16,0,0,-24
HBR01:0,0,0,0,16,0,0,-22
HBR01:0,0,0,0,16,0,0,-38
HBR01:0,0,0,0,16,0,0,-32
HBR01:0,0,0,0,16,0,0,-20
HBR01:0,0,0,0,16,0,0,-21
HBR01:0,0,0,0,16,0,0,-9
HBR01:0,0,0,0,16,0,0,-19
HBR01:0,0,0,0,16,0,0,-31
HBR01:0,0,0,0,16,0,0,-34
HBR01:0,0,0,0,15,0,0,-22
HBR01:0,0,0,0,15,0,0,-34
HBR01:0,0,0,0,15,0,0,-21
HBR01:0,0,0,0,15,0,0,-26
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,15,0,0,-46
HBR01:0,0,0,0,15,0,0,-7
HBR01:0,0,0,0,15,0,0,-4
HBR01:0,0,0,0,15,0,0,-26
HBR01:0,0,0,0,15,0,0,-30
HBR01:0,0,0,0,15,0,0,-14
HBR01:0,0,0,0,15,0,0,-19
HBR01:0,0,0,0,15,0,0,-28
HBR01:0,0,0,0,15,0,0,0
HBR01:0,0,0,0,15,0,0,-9
HBR01:0,0,0,0,15,0,0,-13
HBR01:0,0,0,0,15,0,0,-27
HBR01:0,0,0,0,15,0,0,-13
HBR01:0,0,0,0,15,0,0,0
HBR01:0,0,0,0,15,0,0,-29
HBR01:0,0,0,0,15,0,0,-13
HBR01:0,0,0,0,15,0,0,-25
HBR01:0,0,0,0,15,0,0,-32
HBR01:0,0,0,0,15,0,0,-25
HBR01:0,0,0,0,15,0,0,-18
HBR01:0,0,0,0,15,0,0,-18
HBR01:0,0,0,0,15,0,0,-14
HBR01:0,0,0,0,15,0,0,-17
HBR01:0,0,0,0,15,0,0,-29
HBR01:0,0,0,0,15,0,0,-31
HBR01:0,0,0,0,15,0,0,-39
HBR01:0,0,0,0,15,0,0,-11
HBR01:0,0,0,0,15,0,0,-24
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,15,0,0,-33
HBR01:0,0,0,0,15,0,0,-41
HBR01:0,0,0,0,15,0,0,-32
HBR01:0,0,0,0,15,0,0,-32
HBR01:0,0,0,0,15,0,0,-32
HBR01:0,0,0,0,15,0,0,-18
HBR01:0,0,0,0,15,0,0,-28
HBR01:0,0,0,0,15,0,0,-21
HBR01:0,0,0,0,15,0,0,-18
HBR01:0,0,0,0,15,0,0,-7
HBR01:0,0,0,0,15,0,0,0
HBR01:0,0,0,0,15,0,0,-14
HBR01:0,0,0,0,15,0,0,-11
HBR01:0,0,0,0,15,0,0,-23
HBR01:0,0,0,0,15,0,0,-22
HBR01:0,0,0,0,15,0,0,-14
HBR01:0,0,0,0,15,0,0,-25
HBR01:0,0,0,0,15,0,0,-15
HBR01:0,0,0,0,15,0,0,-28
HBR01:0,0,0,0,15,0,0,1
HBR01:0,0,0,0,15,0,0,1
HBR01:0,0,0,0,15,0,0,-20
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,15,0,0,-25
HBR01:0,0,0,0,15,0,0,0
HBR01:0,0,0,0,15,0,0,0
HBR01:0,0,0,0,15,0,0,-28
HBR01:0,0,0,0,15,0,0,-20
HBR01:0,0,0,0,15,0,0,-10
HBR01:0,0,0,0,15,0,0,-16
HBR01:0,0,0,0,15,0,0,-12
HBR01:0,0,0,0,15,0,0,-26
HBR01:0,0,0,0,15,0,0,-33
HBR01:0,0,0,0,15,0,0,-21
HBR01:0,0,0,0,15,0,0,-22
HBR01:0,0,0,0,15,0,0,-29
HBR01:0,0,0,0,15,0,0,-40
HBR01:0,0,0,0,15,0,0,-33
HBR01:0,0,0,0,15,0,0,-28
HBR01:0,0,0,0,15,0,0,-19
HBR01:0,0,0,0,15,0,0,-26
HBR01:0,0,0,0,15,0,0,-30
HBR01:0,0,0,0,15,0,0,-20
HBR01:0,0,0,0,15,0,0,-29
HBR01:0,0,0,0,15,0,0,-35
HBR01:0,0,0,0,15,0,0,-25
HBR01:0,0,0,0,15,0,0,-27
HBR01:0,0,0,0,15,0,0,-38
HBR01:0,0,0,0,15,0,0,-27
HBR01:0,0,0,0,15,0,0,-27
HBR01:0,0,0,0,15,0,0,-48
HBR01:0,0,0,0,15,0,0,-31
HBR01:0,0,0,0,15,0,0,-26
HBR01:0,0,0,0,15,0,0,-16
HBR01:0,0,0,0,15,0,0,-6
HBR01:0,0,0,0,15,0,0,-13
HBR01:0,0,0,0,15,0,0,-11
HBR01:0,0,0,0,14,0,0,-20
HBR01:0,0,0,0,14,0,0,-58
HBR01:0,0,0,0,14,0,0,-25
HBR01:0,0,0,0,14,0,0,-11