init commit

main
詹力 2024-04-27 17:13:37 +08:00
commit 218d1c92d6
120 changed files with 59961 additions and 0 deletions

11686
UWBAnimationShow/12.14.19.csv Normal file

File diff suppressed because it is too large Load Diff

11668
UWBAnimationShow/12.14.22.csv Normal file

File diff suppressed because it is too large Load Diff

111
UWBAnimationShow/AHRS.m Normal file
View File

@ -0,0 +1,111 @@
classdef AHRS < handle
%% Public properties
properties (Access = public)
SamplePeriod = 1/256;
Quaternion = [1 0 0 0]; % output quaternion describing the sensor relative to the Earth
Kp = 2; % proportional gain
Ki = 0; % integral gain
KpInit = 200; % proportional gain used during initialisation
InitPeriod = 5; % initialisation period in seconds
end
%% Private properties
properties (Access = private)
q = [1 0 0 0]; % internal quaternion describing the Earth relative to the sensor
IntError = [0 0 0]'; % integral error
KpRamped; % internal proportional gain used to ramp during initialisation
end
%% Public methods
methods (Access = public)
function obj = AHRS(varargin)
for i = 1:2:nargin
if strcmp(varargin{i}, 'SamplePeriod'), obj.SamplePeriod = varargin{i+1};
elseif strcmp(varargin{i}, 'Quaternion')
obj.Quaternion = varargin{i+1};
obj.q = quaternConj(obj.Quaternion);
elseif strcmp(varargin{i}, 'Kp'), obj.Kp = varargin{i+1};
elseif strcmp(varargin{i}, 'Ki'), obj.Ki = varargin{i+1};
elseif strcmp(varargin{i}, 'KpInit'), obj.KpInit = varargin{i+1};
elseif strcmp(varargin{i}, 'InitPeriod'), obj.InitPeriod = varargin{i+1};
else error('Invalid argument');
end
obj.KpRamped = obj.KpInit;
end;
end
function obj = Update(obj, Gyroscope, Accelerometer, Magnetometer)
error('This method is unimplemented');
end
function obj = UpdateIMU(obj, Gyroscope, Accelerometer)
% Normalise accelerometer measurement
if(norm(Accelerometer) == 0) % handle NaN
warning(0, 'Accelerometer magnitude is zero. Algorithm update aborted.');
return;
else
Accelerometer = Accelerometer / norm(Accelerometer); % normalise measurement
end
% Compute error between estimated and measured direction of gravity
v = [2*(obj.q(2)*obj.q(4) - obj.q(1)*obj.q(3))
2*(obj.q(1)*obj.q(2) + obj.q(3)*obj.q(4))
obj.q(1)^2 - obj.q(2)^2 - obj.q(3)^2 + obj.q(4)^2]; % estimated direction of gravity
error = cross(v, Accelerometer');
% % Compute ramped Kp value used during init period
% if(obj.KpRamped > obj.Kp)
% obj.IntError = [0 0 0]';
% obj.KpRamped = obj.KpRamped - (obj.KpInit - obj.Kp) / (obj.InitPeriod / obj.SamplePeriod);
% else % init period complete
% obj.KpRamped = obj.Kp;
obj.IntError = obj.IntError + error; % compute integral feedback terms (only outside of init period)
% end
% Apply feedback terms
Ref = Gyroscope - (obj.Kp*error + obj.Ki*obj.IntError)';
% Compute rate of change of quaternion
pDot = 0.5 * obj.quaternProd(obj.q, [0 Ref(1) Ref(2) Ref(3)]); % compute rate of change of quaternion
obj.q = obj.q + pDot * obj.SamplePeriod; % integrate rate of change of quaternion
obj.q = obj.q / norm(obj.q); % normalise quaternion
% Store conjugate
obj.Quaternion = obj.quaternConj(obj.q);
end
function obj = Reset(obj)
obj.KpRamped = obj.KpInit; % start Kp ramp-down
obj.IntError = [0 0 0]'; % reset integral terms
obj.q = [1 0 0 0]; % set quaternion to alignment
end
% function obj = StepDownKp(obj, Kp)
% obj.KpRamped = Kp;
% obj.Kp = Kp;
% end
end
%% Get/set methods
methods
function obj = set.Quaternion(obj, value)
if(norm(value) == 0)
error('Quaternion magnitude cannot be zero.');
end
value = value / norm(value);
obj.Quaternion = value;
obj.q = obj.quaternConj(value);
end
end
%% Private methods
methods (Access = private)
function ab = quaternProd(obj, a, b)
ab(:,1) = a(:,1).*b(:,1)-a(:,2).*b(:,2)-a(:,3).*b(:,3)-a(:,4).*b(:,4);
ab(:,2) = a(:,1).*b(:,2)+a(:,2).*b(:,1)+a(:,3).*b(:,4)-a(:,4).*b(:,3);
ab(:,3) = a(:,1).*b(:,3)-a(:,2).*b(:,4)+a(:,3).*b(:,1)+a(:,4).*b(:,2);
ab(:,4) = a(:,1).*b(:,4)+a(:,2).*b(:,3)-a(:,3).*b(:,2)+a(:,4).*b(:,1);
end
function qConj = quaternConj(obj, q)
qConj = [q(:,1) -q(:,2) -q(:,3) -q(:,4)];
end
end
end

View File

@ -0,0 +1,169 @@
#################
## Eclipse
#################
*.pydevproject
.project
.metadata
bin/
tmp/
*.tmp
*.bak
*.swp
*~.nib
local.properties
.classpath
.settings/
.loadpath
# External tool builders
.externalToolBuilders/
# Locally stored "Eclipse launch configurations"
*.launch
# CDT-specific
.cproject
# PDT-specific
.buildpath
#################
## Visual Studio
#################
## Ignore Visual Studio temporary files, build results, and
## files generated by popular Visual Studio add-ons.
# User-specific files
*.suo
*.user
*.sln.docstates
# Build results
[Dd]ebug/
[Rr]elease/
*_i.c
*_p.c
*.ilk
*.meta
*.obj
*.pch
*.pdb
*.pgc
*.pgd
*.rsp
*.sbr
*.tlb
*.tli
*.tlh
*.tmp
*.vspscc
.builds
*.dotCover
## TODO: If you have NuGet Package Restore enabled, uncomment this
#packages/
# Visual C++ cache files
ipch/
*.aps
*.ncb
*.opensdf
*.sdf
# Visual Studio profiler
*.psess
*.vsp
# ReSharper is a .NET coding add-in
_ReSharper*
# Installshield output folder
[Ee]xpress
# DocProject is a documentation generator add-in
DocProject/buildhelp/
DocProject/Help/*.HxT
DocProject/Help/*.HxC
DocProject/Help/*.hhc
DocProject/Help/*.hhk
DocProject/Help/*.hhp
DocProject/Help/Html2
DocProject/Help/html
# Click-Once directory
publish
# Others
[Bb]in
[Oo]bj
sql
TestResults
*.Cache
ClientBin
stylecop.*
~$*
*.dbmdl
Generated_Code #added for RIA/Silverlight projects
# Backup & report files from converting an old project file to a newer
# Visual Studio version. Backup files are not needed, because we have git ;-)
_UpgradeReport_Files/
Backup*/
UpgradeLog*.XML
############
## Windows
############
# Windows image file caches
Thumbs.db
# Folder config file
Desktop.ini
#############
## Python
#############
*.py[co]
# Packages
*.egg
*.egg-info
dist
build
eggs
parts
bin
var
sdist
develop-eggs
.installed.cfg
# Installer logs
pip-log.txt
# Unit test / coverage reports
.coverage
.tox
#Translations
*.mo
#Mr Developer
.mr.developer.cfg
# Mac crap
.DS_Store
##################
# Binary archive
##################
bin-archive/

View File

@ -0,0 +1,14 @@
# Gait-Tracking-With-x-IMU
> [!WARNING]
> This repository is no longer maintained and has been superseded by [Gait-Tracking](https://github.com/xioTechnologies/Gait-Tracking).
This is the source code for the foot tracking algorithm demonstrated in Seb Madgwick's "[3D Tracking with IMU"](http://www.youtube.com/watch?v=6ijArKE8vKU) video, originally uploaded to YouTube in March 2011. An [x-IMU](http://www.x-io.co.uk/x-imu) attached to a foot is be used to track position through [dead reckoning](http://en.wikipedia.org/wiki/Dead_reckoning) and integral drift corrected for each time the foot hit the ground.
See the [original post](http://www.x-io.co.uk/gait-tracking-with-x-imu/) for more information.
<img src="https://raw.github.com/xioTechnologies/Gait-Tracking-With-x-IMU/master/Screenshot%20-%20x-IMU%20Attached%20To%20Foot.png"/>
<img src="https://raw.github.com/xioTechnologies/Gait-Tracking-With-x-IMU/master/Screenshot%20-%20MATLAB%20Animation%20Close-Up.png"/>
<img src="https://raw.github.com/xioTechnologies/Gait-Tracking-With-x-IMU/master/Screenshot%20-%20MATLAB%20Animation%20Spiral%20Stairs.png"/>

Binary file not shown.

After

Width:  |  Height:  |  Size: 481 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 980 KiB

View File

@ -0,0 +1,73 @@
%% TestScript.m
close all; % close all figures
clear; % clear all variables
clc; % clear the command terminal
%% Axis-angle to rotation matrix
axis = [1 2 3];
axis = axis / norm(axis);
angle = pi/2;
R = axisAngle2rotMat(axis, angle);
num = ' % 1.5f';
a = sprintf('\rAxis-angle to rotation matrix:');
b = sprintf(strcat('\r', num, '\t', num, '\t', num), R(1,:));
c = sprintf(strcat('\r', num, '\t', num, '\t', num), R(2,:));
d = sprintf(strcat('\r', num, '\t', num, '\t', num), R(3,:));
disp(strcat(a,b,c,d));
%% Axis-angle to quaternion
q = axisAngle2quatern(axis, angle);
num = ' % 1.5f';
a = sprintf('\rAxis-angle to quaternion:');
b = sprintf(strcat('\r', num, '\t', num, '\t', num, '\t', num), q);
disp(strcat(a,b));
%% Quaternion to rotation matrix
R = quatern2rotMat(q);
num = ' % 1.5f';
a = sprintf('\rQuaternion to rotation matrix:');
b = sprintf(strcat('\r', num, '\t', num, '\t', num), R(1,:));
c = sprintf(strcat('\r', num, '\t', num, '\t', num), R(2,:));
d = sprintf(strcat('\r', num, '\t', num, '\t', num), R(3,:));
disp(strcat(a,b,c,d));
%% Rotation matrix to quaternion
q = rotMat2quatern(R);
num = ' % 1.5f';
a = sprintf('\rRotation matrix to quaternion:');
b = sprintf(strcat('\r', num, '\t', num, '\t', num, '\t', num), q);
disp(strcat(a,b));
%% Rotation matrix to ZYX Euler angles
euler = rotMat2euler(R);
num = ' % 1.5f';
a = sprintf('\rRotation matrix to ZYX Euler angles:');
b = sprintf(strcat('\r', num, '\t', num, '\t', num), euler);
disp(strcat(a,b));
%% Quaternion to ZYX Euler angles
euler = quatern2euler(q);
num = ' % 1.5f';
a = sprintf('\rQuaternion to ZYX Euler angles:');
b = sprintf(strcat('\r', num, '\t', num, '\t', num), euler);
disp(strcat(a,b));
%% ZYX Euler angles to rotation matrix
R = euler2rotMat(euler(1), euler(2), euler(3));
num = ' % 1.5f';
a = sprintf('\rZYX Euler angles to rotation matrix:');
b = sprintf(strcat('\r', num, '\t', num, '\t', num), R(1,:));
c = sprintf(strcat('\r', num, '\t', num, '\t', num), R(2,:));
d = sprintf(strcat('\r', num, '\t', num, '\t', num), R(3,:));
disp(strcat(a,b,c,d));
%% End of file

View File

@ -0,0 +1,8 @@
function q = axisAngle2quatern(axis, angle)
q0 = cos(angle./2);
q1 = -axis(:,1)*sin(angle./2);
q2 = -axis(:,2)*sin(angle./2);
q3 = -axis(:,3)*sin(angle./2);
q = [q0 q1 q2 q3];
end

View File

@ -0,0 +1,21 @@
function R = axisAngle2rotMat(axis, angle)
kx = axis(:,1);
ky = axis(:,2);
kz = axis(:,3);
cT = cos(angle);
sT = sin(angle);
vT = 1 - cos(angle);
R(1,1,:) = kx.*kx.*vT + cT;
R(1,2,:) = kx.*ky.*vT - kz.*sT;
R(1,3,:) = kx.*kz.*vT + ky.*sT;
R(2,1,:) = kx.*ky.*vT + kz.*sT;
R(2,2,:) = ky.*ky.*vT + cT;
R(2,3,:) = ky.*kz.*vT - kx.*sT;
R(3,1,:) = kx.*kz.*vT - ky.*sT;
R(3,2,:) = ky.*kz.*vT + kx.*sT;
R(3,3,:) = kz.*kz.*vT + cT;
end

View File

@ -0,0 +1,14 @@
function R = euler2rotMat(phi, theta, psi)
R(1,1,:) = cos(psi).*cos(theta);
R(1,2,:) = -sin(psi).*cos(phi) + cos(psi).*sin(theta).*sin(phi);
R(1,3,:) = sin(psi).*sin(phi) + cos(psi).*sin(theta).*cos(phi);
R(2,1,:) = sin(psi).*cos(theta);
R(2,2,:) = cos(psi).*cos(phi) + sin(psi).*sin(theta).*sin(phi);
R(2,3,:) = -cos(psi).*sin(phi) + sin(psi).*sin(theta).*cos(phi);
R(3,1,:) = -sin(theta);
R(3,2,:) = cos(theta).*sin(phi);
R(3,3,:) = cos(theta).*cos(phi);
end

View File

@ -0,0 +1,17 @@
function euler = quatern2euler(q)
% from paper: "Adaptive Filter for a Miniature MEMS Based Attitude and
% Heading Reference System" by Wang et al, IEEE.
R(1,1,:) = 2.*q(:,1).^2-1+2.*q(:,2).^2;
R(2,1,:) = 2.*(q(:,2).*q(:,3)-q(:,1).*q(:,4));
R(3,1,:) = 2.*(q(:,2).*q(:,4)+q(:,1).*q(:,3));
R(3,2,:) = 2.*(q(:,3).*q(:,4)-q(:,1).*q(:,2));
R(3,3,:) = 2.*q(:,1).^2-1+2.*q(:,4).^2;
phi = atan2(R(3,2,:), R(3,3,:) );
theta = -atan(R(3,1,:) ./ sqrt(1-R(3,1,:).^2) );
psi = atan2(R(2,1,:), R(1,1,:) );
euler = [phi(1,:)' theta(1,:)' psi(1,:)'];
end

View File

@ -0,0 +1,14 @@
function R = quatern2rotMat(q)
[rows cols] = size(q);
R = zeros(3,3, rows);
R(1,1,:) = 2.*q(:,1).^2-1+2.*q(:,2).^2;
R(1,2,:) = 2.*(q(:,2).*q(:,3)+q(:,1).*q(:,4));
R(1,3,:) = 2.*(q(:,2).*q(:,4)-q(:,1).*q(:,3));
R(2,1,:) = 2.*(q(:,2).*q(:,3)-q(:,1).*q(:,4));
R(2,2,:) = 2.*q(:,1).^2-1+2.*q(:,3).^2;
R(2,3,:) = 2.*(q(:,3).*q(:,4)+q(:,1).*q(:,2));
R(3,1,:) = 2.*(q(:,2).*q(:,4)+q(:,1).*q(:,3));
R(3,2,:) = 2.*(q(:,3).*q(:,4)-q(:,1).*q(:,2));
R(3,3,:) = 2.*q(:,1).^2-1+2.*q(:,4).^2;
end

View File

@ -0,0 +1,3 @@
function qConj = quaternConj(q)
qConj = [q(:,1) -q(:,2) -q(:,3) -q(:,4)];
end

View File

@ -0,0 +1,7 @@
function ab = quaternProd(a, b)
ab(:,1) = a(:,1).*b(:,1)-a(:,2).*b(:,2)-a(:,3).*b(:,3)-a(:,4).*b(:,4);
ab(:,2) = a(:,1).*b(:,2)+a(:,2).*b(:,1)+a(:,3).*b(:,4)-a(:,4).*b(:,3);
ab(:,3) = a(:,1).*b(:,3)-a(:,2).*b(:,4)+a(:,3).*b(:,1)+a(:,4).*b(:,2);
ab(:,4) = a(:,1).*b(:,4)+a(:,2).*b(:,3)-a(:,3).*b(:,2)+a(:,4).*b(:,1);
end

View File

@ -0,0 +1,6 @@
function v = quaternRotate(v, q)
[row col] = size(v);
v0XYZ = quaternProd(quaternProd(q, [zeros(row, 1) v]), quaternConj(q));
v = v0XYZ(:, 2:4);
end

View File

@ -0,0 +1,11 @@
function euler = rotMat2euler(R)
% from paper: "Adaptive Filter for a Miniature MEMS Based Attitude and
% Heading Reference System" by Wang et al, IEEE.
phi = atan2(R(3,2,:), R(3,3,:) );
theta = -atan(R(3,1,:) ./ sqrt(1-R(3,1,:).^2) );
psi = atan2(R(2,1,:), R(1,1,:) );
euler = [phi(1,:)' theta(1,:)' psi(1,:)'];
end

View File

@ -0,0 +1,30 @@
function q = rotMat2quatern(R)
% wiki URL: http://en.wikipeRia.org/wiki/Quaternions_anR_spatial_rotation#Fitting_quaternions
% paper URL: http://www.aiaa.org/content.cfm?pageiR=406&gTable=japaperimport&gIR=4654
[row col numR] = size(R);
q = zeros(numR, 4);
K = zeros(4,4);
for i = 1:numR
K(1,1) = (1/3) * (R(1,1,i) - R(2,2,i) - R(3,3,i));
K(1,2) = (1/3) * (R(2,1,i) + R(1,2,i));
K(1,3) = (1/3) * (R(3,1,i) + R(1,3,i));
K(1,4) = (1/3) * (R(2,3,i) - R(3,2,i));
K(2,1) = (1/3) * (R(2,1,i) + R(1,2,i));
K(2,2) = (1/3) * (R(2,2,i) - R(1,1,i) - R(3,3,i));
K(2,3) = (1/3) * (R(3,2,i) + R(2,3,i));
K(2,4) = (1/3) * (R(3,1,i) - R(1,3,i));
K(3,1) = (1/3) * (R(3,1,i) + R(1,3,i));
K(3,2) = (1/3) * (R(3,2,i) + R(2,3,i));
K(3,3) = (1/3) * (R(3,3,i) - R(1,1,i) - R(2,2,i));
K(3,4) = (1/3) * (R(1,2,i) - R(2,1,i));
K(4,1) = (1/3) * (R(2,3,i) - R(3,2,i));
K(4,2) = (1/3) * (R(3,1,i) - R(1,3,i));
K(4,3) = (1/3) * (R(1,2,i) - R(2,1,i));
K(4,4) = (1/3) * (R(1,1,i) + R(2,2,i) + R(3,3,i));
[V,D] = eig(K);
%p = find(max(D));
%q = V(:,p)';
q(i,:) = V(:,4)';
q(i,:) = [q(i,4) q(i,1) q(i,2) q(i,3)];
end
end

234
UWBAnimationShow/Script.m Normal file
View File

@ -0,0 +1,234 @@
clear;
close all;
clc;
addpath('Quaternions');
addpath('ximu_matlab_library');
% -------------------------------------------------------------------------
% Select dataset (comment in/out)
filePath = 'Datasets/straightLine';
startTime = 6;
stopTime = 26;
% filePath = 'Datasets/stairsAndCorridor';
% startTime = 5;
% stopTime = 53;
% filePath = 'Datasets/spiralStairs';
% startTime = 4;
% stopTime = 47;
% -------------------------------------------------------------------------
% Import data
samplePeriod = 1/256;
xIMUdata = xIMUdataClass(filePath, 'InertialMagneticSampleRate', 1/samplePeriod);
time = xIMUdata.CalInertialAndMagneticData.Time;
gyrX = xIMUdata.CalInertialAndMagneticData.Gyroscope.X;
gyrY = xIMUdata.CalInertialAndMagneticData.Gyroscope.Y;
gyrZ = xIMUdata.CalInertialAndMagneticData.Gyroscope.Z;
accX = xIMUdata.CalInertialAndMagneticData.Accelerometer.X;
accY = xIMUdata.CalInertialAndMagneticData.Accelerometer.Y;
accZ = xIMUdata.CalInertialAndMagneticData.Accelerometer.Z;
clear('xIMUdata');
% -------------------------------------------------------------------------
% Manually frame data
% startTime = 0;
% stopTime = 10;
indexSel = find(sign(time-startTime)+1, 1) : find(sign(time-stopTime)+1, 1);
time = time(indexSel);
gyrX = gyrX(indexSel, :);
gyrY = gyrY(indexSel, :);
gyrZ = gyrZ(indexSel, :);
accX = accX(indexSel, :);
accY = accY(indexSel, :);
accZ = accZ(indexSel, :);
% -------------------------------------------------------------------------
% Detect stationary periods
% Compute accelerometer magnitude
acc_mag = sqrt(accX.*accX + accY.*accY + accZ.*accZ);
% HP filter accelerometer data
filtCutOff = 0.001;
[b, a] = butter(1, (2*filtCutOff)/(1/samplePeriod), 'high');
acc_magFilt = filtfilt(b, a, acc_mag);
% Compute absolute value
acc_magFilt = abs(acc_magFilt);
% LP filter accelerometer data
filtCutOff = 5;
[b, a] = butter(1, (2*filtCutOff)/(1/samplePeriod), 'low');
acc_magFilt = filtfilt(b, a, acc_magFilt);
% Threshold detection
stationary = acc_magFilt < 0.05;
% -------------------------------------------------------------------------
% Plot data raw sensor data and stationary periods
figure('Position', [9 39 900 600], 'NumberTitle', 'off', 'Name', 'Sensor Data');
ax(1) = subplot(2,1,1);
hold on;
plot(time, gyrX, 'r');
plot(time, gyrY, 'g');
plot(time, gyrZ, 'b');
title('Gyroscope');
xlabel('Time (s)');
ylabel('Angular velocity (^\circ/s)');
legend('X', 'Y', 'Z');
hold off;
ax(2) = subplot(2,1,2);
hold on;
plot(time, accX, 'r');
plot(time, accY, 'g');
plot(time, accZ, 'b');
plot(time, acc_magFilt, ':k');
plot(time, stationary, 'k', 'LineWidth', 2);
title('Accelerometer');
xlabel('Time (s)');
ylabel('Acceleration (g)');
legend('X', 'Y', 'Z', 'Filtered', 'Stationary');
hold off;
linkaxes(ax,'x');
% -------------------------------------------------------------------------
% Compute orientation
quat = zeros(length(time), 4);
AHRSalgorithm = AHRS('SamplePeriod', 1/256, 'Kp', 1, 'KpInit', 1);
% Initial convergence
initPeriod = 2;
indexSel = 1 : find(sign(time-(time(1)+initPeriod))+1, 1);
for i = 1:2000
AHRSalgorithm.UpdateIMU([0 0 0], [mean(accX(indexSel)) mean(accY(indexSel)) mean(accZ(indexSel))]);
end
% For all data
for t = 1:length(time)
if(stationary(t))
AHRSalgorithm.Kp = 0.5;
else
AHRSalgorithm.Kp = 0;
end
AHRSalgorithm.UpdateIMU(deg2rad([gyrX(t) gyrY(t) gyrZ(t)]), [accX(t) accY(t) accZ(t)]);
quat(t,:) = AHRSalgorithm.Quaternion;
end
% -------------------------------------------------------------------------
% Compute translational accelerations
% Rotate body accelerations to Earth frame
acc = quaternRotate([accX accY accZ], quaternConj(quat));
% % Remove gravity from measurements
% acc = acc - [zeros(length(time), 2) ones(length(time), 1)]; % unnecessary due to velocity integral drift compensation
% Convert acceleration measurements to m/s/s
acc = acc * 9.81;
% Plot translational accelerations
figure('Position', [9 39 900 300], 'NumberTitle', 'off', 'Name', 'Accelerations');
hold on;
plot(time, acc(:,1), 'r');
plot(time, acc(:,2), 'g');
plot(time, acc(:,3), 'b');
title('Acceleration');
xlabel('Time (s)');
ylabel('Acceleration (m/s/s)');
legend('X', 'Y', 'Z');
hold off;
% -------------------------------------------------------------------------
% Compute translational velocities
acc(:,3) = acc(:,3) - 9.81;
% Integrate acceleration to yield velocity
vel = zeros(size(acc));
for t = 2:length(vel)
vel(t,:) = vel(t-1,:) + acc(t,:) * samplePeriod;
if(stationary(t) == 1)
vel(t,:) = [0 0 0]; % force zero velocity when foot stationary
end
end
% Compute integral drift during non-stationary periods
velDrift = zeros(size(vel));
stationaryStart = find([0; diff(stationary)] == -1);
stationaryEnd = find([0; diff(stationary)] == 1);
for i = 1:numel(stationaryEnd)
driftRate = vel(stationaryEnd(i)-1, :) / (stationaryEnd(i) - stationaryStart(i));
enum = 1:(stationaryEnd(i) - stationaryStart(i));
drift = [enum'*driftRate(1) enum'*driftRate(2) enum'*driftRate(3)];
velDrift(stationaryStart(i):stationaryEnd(i)-1, :) = drift;
end
% Remove integral drift
vel = vel - velDrift;
% Plot translational velocity
figure('Position', [9 39 900 300], 'NumberTitle', 'off', 'Name', 'Velocity');
hold on;
plot(time, vel(:,1), 'r');
plot(time, vel(:,2), 'g');
plot(time, vel(:,3), 'b');
title('Velocity');
xlabel('Time (s)');
ylabel('Velocity (m/s)');
legend('X', 'Y', 'Z');
hold off;
% -------------------------------------------------------------------------
% Compute translational position
% Integrate velocity to yield position
pos = zeros(size(vel));
for t = 2:length(pos)
pos(t,:) = pos(t-1,:) + vel(t,:) * samplePeriod; % integrate velocity to yield position
end
% Plot translational position
figure('Position', [9 39 900 600], 'NumberTitle', 'off', 'Name', 'Position');
hold on;
plot(time, pos(:,1), 'r');
plot(time, pos(:,2), 'g');
plot(time, pos(:,3), 'b');
title('Position');
xlabel('Time (s)');
ylabel('Position (m)');
legend('X', 'Y', 'Z');
hold off;
% -------------------------------------------------------------------------
% Plot 3D foot trajectory
% % Remove stationary periods from data to plot
% posPlot = pos(find(~stationary), :);
% quatPlot = quat(find(~stationary), :);
posPlot = pos;
quatPlot = quat;
% Extend final sample to delay end of animation
extraTime = 20;
onesVector = ones(extraTime*(1/samplePeriod), 1);
posPlot = [posPlot; [posPlot(end, 1)*onesVector, posPlot(end, 2)*onesVector, posPlot(end, 3)*onesVector]];
quatPlot = [quatPlot; [quatPlot(end, 1)*onesVector, quatPlot(end, 2)*onesVector, quatPlot(end, 3)*onesVector, quatPlot(end, 4)*onesVector]];
% Create 6 DOF animation
SamplePlotFreq = 4;
Spin = 120;
SixDofAnimation(posPlot, quatern2rotMat(quatPlot), ...
'SamplePlotFreq', SamplePlotFreq, 'Trail', 'All', ...
'Position', [9 39 1280 768], 'View', [(100:(Spin/(length(posPlot)-1)):(100+Spin))', 10*ones(length(posPlot), 1)], ...
'AxisLength', 0.1, 'ShowArrowHead', false, ...
'Xlabel', 'X (m)', 'Ylabel', 'Y (m)', 'Zlabel', 'Z (m)', 'ShowLegend', false, ...
'CreateAVI', false, 'AVIfileNameEnum', false, 'AVIfps', ((1/samplePeriod) / SamplePlotFreq));

View File

@ -0,0 +1,255 @@
function fig = SixDOFanimation(varargin)
%% Create local variables
% Required arguments
p = varargin{1}; % position of body
R = varargin{2}; % rotation matrix of body
[numSamples dummy] = size(p);
% Default values of optional arguments
SamplePlotFreq = 1;
Trail = 'Off';
LimitRatio = 1;
Position = [];
FullScreen = false;
View = [30 20];
AxisLength = 1;
ShowArrowHead = 'on';
Xlabel = 'X';
Ylabel = 'Y';
Zlabel = 'Z';
Title = '6DOF Animation';
ShowLegend = true;
CreateAVI = false;
AVIfileName = '6DOF Animation';
AVIfileNameEnum = true;
AVIfps = 30;
for i = 3:2:nargin
if strcmp(varargin{i}, 'SamplePlotFreq'), SamplePlotFreq = varargin{i+1};
elseif strcmp(varargin{i}, 'Trail')
Trail = varargin{i+1};
if(~strcmp(Trail, 'Off') && ~strcmp(Trail, 'DotsOnly') && ~strcmp(Trail, 'All'))
error('Invalid argument. Trail must be ''Off'', ''DotsOnly'' or ''All''.');
end
elseif strcmp(varargin{i}, 'LimitRatio'), LimitRatio = varargin{i+1};
elseif strcmp(varargin{i}, 'Position'), Position = varargin{i+1};
elseif strcmp(varargin{i}, 'FullScreen'), FullScreen = varargin{i+1};
elseif strcmp(varargin{i}, 'View'), View = varargin{i+1};
elseif strcmp(varargin{i}, 'AxisLength'), AxisLength = varargin{i+1};
elseif strcmp(varargin{i}, 'ShowArrowHead'), ShowArrowHead = varargin{i+1};
elseif strcmp(varargin{i}, 'Xlabel'), Xlabel = varargin{i+1};
elseif strcmp(varargin{i}, 'Ylabel'), Ylabel = varargin{i+1};
elseif strcmp(varargin{i}, 'Zlabel'), Zlabel = varargin{i+1};
elseif strcmp(varargin{i}, 'Title'), Title = varargin{i+1};
elseif strcmp(varargin{i}, 'ShowLegend'), ShowLegend = varargin{i+1};
elseif strcmp(varargin{i}, 'CreateAVI'), CreateAVI = varargin{i+1};
elseif strcmp(varargin{i}, 'AVIfileName'), AVIfileName = varargin{i+1};
elseif strcmp(varargin{i}, 'AVIfileNameEnum'), AVIfileNameEnum = varargin{i+1};
elseif strcmp(varargin{i}, 'AVIfps'), AVIfps = varargin{i+1};
else error('Invalid argument.');
end
end;
%% Reduce data to samples to plot only
p = p(1:SamplePlotFreq:numSamples, :);
R = R(:, :, 1:SamplePlotFreq:numSamples) * AxisLength;
if(numel(View) > 2)
View = View(1:SamplePlotFreq:numSamples, :);
end
[numPlotSamples dummy] = size(p);
%% Setup AVI file
aviobj = []; % create null object
if(CreateAVI)
fileName = strcat(AVIfileName, '.avi');
if(exist(fileName, 'file'))
if(AVIfileNameEnum) % if file name exists and enum enabled
i = 0;
while(exist(fileName, 'file')) % find un-used file name by appending enum
fileName = strcat(AVIfileName, sprintf('%i', i), '.avi');
i = i + 1;
end
else % else file name exists and enum disabled
fileName = []; % file will not be created
end
end
if(isempty(fileName))
sprintf('AVI file not created as file already exists.')
else
aviobj = avifile(fileName, 'fps', AVIfps, 'compression', 'Cinepak', 'quality', 100);
end
end
%% Setup figure and plot
% Create figure
fig = figure('NumberTitle', 'off', 'Name', '6DOF Animation');
if(FullScreen)
screenSize = get(0, 'ScreenSize');
set(fig, 'Position', [0 0 screenSize(3) screenSize(4)]);
elseif(~isempty(Position))
set(fig, 'Position', Position);
end
set(gca, 'drawmode', 'fast');
lighting phong;
set(gcf, 'Renderer', 'zbuffer');
hold on;
axis equal;
grid on;
view(View(1, 1), View(1, 2));
title(i);
xlabel(Xlabel);
ylabel(Ylabel);
zlabel(Zlabel);
% Create plot data arrays
if(strcmp(Trail, 'DotsOnly') || strcmp(Trail, 'All'))
x = zeros(numPlotSamples, 1);
y = zeros(numPlotSamples, 1);
z = zeros(numPlotSamples, 1);
end
if(strcmp(Trail, 'All'))
ox = zeros(numPlotSamples, 1);
oy = zeros(numPlotSamples, 1);
oz = zeros(numPlotSamples, 1);
ux = zeros(numPlotSamples, 1);
vx = zeros(numPlotSamples, 1);
wx = zeros(numPlotSamples, 1);
uy = zeros(numPlotSamples, 1);
vy = zeros(numPlotSamples, 1);
wy = zeros(numPlotSamples, 1);
uz = zeros(numPlotSamples, 1);
vz = zeros(numPlotSamples, 1);
wz = zeros(numPlotSamples, 1);
end
x(1) = p(1,1);
y(1) = p(1,2);
z(1) = p(1,3);
ox(1) = x(1);
oy(1) = y(1);
oz(1) = z(1);
ux(1) = R(1,1,1:1);
vx(1) = R(2,1,1:1);
wx(1) = R(3,1,1:1);
uy(1) = R(1,2,1:1);
vy(1) = R(2,2,1:1);
wy(1) = R(3,2,1:1);
uz(1) = R(1,3,1:1);
vz(1) = R(2,3,1:1);
wz(1) = R(3,3,1:1);
% Create graphics handles
orgHandle = plot3(x, y, z, 'k.');
if(ShowArrowHead)
ShowArrowHeadStr = 'on';
else
ShowArrowHeadStr = 'off';
end
quivXhandle = quiver3(ox, oy, oz, ux, vx, wx, 'r', 'ShowArrowHead', ShowArrowHeadStr, 'MaxHeadSize', 0.999999, 'AutoScale', 'off');
quivYhandle = quiver3(ox, oy, oz, uy, vy, wy, 'g', 'ShowArrowHead', ShowArrowHeadStr, 'MaxHeadSize', 0.999999, 'AutoScale', 'off');
quivZhandle = quiver3(ox, ox, oz, uz, vz, wz, 'b', 'ShowArrowHead', ShowArrowHeadStr, 'MaxHeadSize', 0.999999, 'AutoScale', 'off');
% Create legend
if(ShowLegend)
legend('Origin', 'X', 'Y', 'Z');
end
% Set initial limits
Xlim = [x(1)-AxisLength x(1)+AxisLength] * LimitRatio;
Ylim = [y(1)-AxisLength y(1)+AxisLength] * LimitRatio;
Zlim = [z(1)-AxisLength z(1)+AxisLength] * LimitRatio;
set(gca, 'Xlim', Xlim, 'Ylim', Ylim, 'Zlim', Zlim);
% Set initial view
view(View(1, :));
%% Plot one sample at a time
for i = 1:numPlotSamples
% Update graph title
if(strcmp(Title, ''))
titleText = sprintf('Sample %i of %i', 1+((i-1)*SamplePlotFreq), numSamples);
else
titleText = strcat(Title, ' (', sprintf('Sample %i of %i', 1+((i-1)*SamplePlotFreq), numSamples), ')');
end
title(titleText);
% Plot body x y z axes
if(strcmp(Trail, 'DotsOnly') || strcmp(Trail, 'All'))
x(1:i) = p(1:i,1);
y(1:i) = p(1:i,2);
z(1:i) = p(1:i,3);
else
x = p(i,1);
y = p(i,2);
z = p(i,3);
end
if(strcmp(Trail, 'All'))
ox(1:i) = p(1:i,1);
oy(1:i) = p(1:i,2);
oz(1:i) = p(1:i,3);
ux(1:i) = R(1,1,1:i);
vx(1:i) = R(2,1,1:i);
wx(1:i) = R(3,1,1:i);
uy(1:i) = R(1,2,1:i);
vy(1:i) = R(2,2,1:i);
wy(1:i) = R(3,2,1:i);
uz(1:i) = R(1,3,1:i);
vz(1:i) = R(2,3,1:i);
wz(1:i) = R(3,3,1:i);
else
ox = p(i,1);
oy = p(i,2);
oz = p(i,3);
ux = R(1,1,i);
vx = R(2,1,i);
wx = R(3,1,i);
uy = R(1,2,i);
vy = R(2,2,i);
wy = R(3,2,i);
uz = R(1,3,i);
vz = R(2,3,i);
wz = R(3,3,i);
end
set(orgHandle, 'xdata', x, 'ydata', y, 'zdata', z);
set(quivXhandle, 'xdata', ox, 'ydata', oy, 'zdata', oz,'udata', ux, 'vdata', vx, 'wdata', wx);
set(quivYhandle, 'xdata', ox, 'ydata', oy, 'zdata', oz,'udata', uy, 'vdata', vy, 'wdata', wy);
set(quivZhandle, 'xdata', ox, 'ydata', oy, 'zdata', oz,'udata', uz, 'vdata', vz, 'wdata', wz);
% Adjust axes for snug fit and draw
axisLimChanged = false;
if((p(i,1) - AxisLength) < Xlim(1)), Xlim(1) = p(i,1) - LimitRatio*AxisLength; axisLimChanged = true; end
if((p(i,2) - AxisLength) < Ylim(1)), Ylim(1) = p(i,2) - LimitRatio*AxisLength; axisLimChanged = true; end
if((p(i,3) - AxisLength) < Zlim(1)), Zlim(1) = p(i,3) - LimitRatio*AxisLength; axisLimChanged = true; end
if((p(i,1) + AxisLength) > Xlim(2)), Xlim(2) = p(i,1) + LimitRatio*AxisLength; axisLimChanged = true; end
if((p(i,2) + AxisLength) > Ylim(2)), Ylim(2) = p(i,2) + LimitRatio*AxisLength; axisLimChanged = true; end
if((p(i,3) + AxisLength) > Zlim(2)), Zlim(2) = p(i,3) + LimitRatio*AxisLength; axisLimChanged = true; end
if(axisLimChanged), set(gca, 'Xlim', Xlim, 'Ylim', Ylim, 'Zlim', Zlim); end
drawnow;
% Adjust view
if(numel(View) > 2)
view(View(i, :));
end
% Add frame to AVI object
if(~isempty(aviobj))
frame = getframe(fig);
aviobj = addframe(aviobj, frame);
end
end
hold off;
% Close AVI file
if(~isempty(aviobj))
aviobj = close(aviobj);
end
end

BIN
UWBAnimationShow/UWBIns.mat Normal file

Binary file not shown.

Binary file not shown.

View File

@ -0,0 +1,28 @@
clc;
clear;
load UWBIns.mat
x = lightHousePosX * 100;
y = -lightHousePosZ * 100;
theta = -1 / pi;
% Ðýת×ø±ê
xt = x * cos(theta) - y * sin(theta);
yt = x * sin(theta) + y * cos(theta);
x0 = xt(1) - imuPosX(1);
y0 = yt(1) - imuPosY(1);
xt = xt - x0 + 20;
yt = yt - y0 - 10;
plot(xt,yt);
hold on;
plot(imuPosX,imuPosY);
hold on;
plot(uwbPosX,uwbPosY,'.');
hold on;
plot(syncPosX,syncPosY,'.');

View File

@ -0,0 +1,60 @@
clc;
clear;
load UWBIns2.mat
x = lightHousePosX * 100;
y = -lightHousePosZ * 100;
theta = -1 / pi;
% 旋转坐标
xt = x * cos(theta) - y * sin(theta);
yt = x * sin(theta) + y * cos(theta);
x0 = xt(1) - imuPosX(1);
y0 = yt(1) - imuPosY(1);
xt = xt - x0;
yt = yt - y0;
% plot(xt,yt,'r');
% hold on;
% plot(imuPosX,imuPosY,'g');
% plot(uwbPosX,uwbPosY,'b.');
% plot(syncPosX,syncPosY,'k.');
% --------------------- 水平显示 ---------------------------
% %
for i = 1:10:length(xt)
plot(xt(1:i),yt(1:i),'r');
%set(gcf,'Position',[100 100 260 220]);
hold on;
%plot(imuPosX(1:i),imuPosY(1:i),'g');
plot(uwbPosX(1:i),uwbPosY(1:i),'b.');
plot(syncPosX(1:i),syncPosY(1:i),'k.');
legend('参考系统', '原始UWB定位','多传感器融合定位');
pause(0.05);
clf;
end
% posPlot = [xt, yt, zeros(1,length(xt))'];
% quatPlot = [ones(1,length(xt))',zeros(1,length(xt))',zeros(1,length(xt))',zeros(1,length(xt))'];
% samplePeriod = 1/256;
% SamplePlotFreq = 4;
% Spin = 120;
% SixDofAnimation(posPlot, quatern2rotMat(quatPlot), ...
% 'SamplePlotFreq', SamplePlotFreq, 'Trail', 'All', ...
% 'Position', [9 39 1280 768], 'View', [(100:(Spin/(length(posPlot)-1)):(100+Spin))', 10*ones(length(posPlot), 1)], ...
% 'AxisLength', 0.1, 'ShowArrowHead', false, ...
% 'Xlabel', 'X (m)', 'Ylabel', 'Y (m)', 'Zlabel', 'Z (m)', 'ShowLegend', false, ...
% 'CreateAVI', false, 'AVIfileNameEnum', false, 'AVIfps', ((1/samplePeriod) / SamplePlotFreq));
% ----------------- 单独显示X轴情况 -------------------------
% plot(xt);
% hold on;
% plot(imuPosX);
%plot(uwbPosX,'.');

View File

@ -0,0 +1,97 @@
classdef ADXL345busDataBaseClass < TimeSeriesDataBaseClass
%% Abstract public 'read-only' properties
properties (Abstract, SetAccess = private)
FileNameAppendage;
end
%% Public 'read-only' properties
properties (SetAccess = private)
ADXL345A = struct('X', [], 'Y', [], 'Z', []);
ADXL345B = struct('X', [], 'Y', [], 'Z', []);
ADXL345C = struct('X', [], 'Y', [], 'Z', []);
ADXL345D = struct('X', [], 'Y', [], 'Z', []);
end
%% Abstract protected properties
properties (Access = protected)
AccelerometerUnits;
end
%% Protected methods
methods (Access = protected)
function obj = Import(obj, fileNamePrefix)
data = obj.ImportCSVnumeric(fileNamePrefix);
obj.ADXL345A.X = data(:,2);
obj.ADXL345A.Y = data(:,3);
obj.ADXL345A.Z = data(:,4);
obj.ADXL345B.X = data(:,5);
obj.ADXL345B.Y = data(:,6);
obj.ADXL345B.Z = data(:,7);
obj.ADXL345C.X = data(:,8);
obj.ADXL345C.Y = data(:,9);
obj.ADXL345C.Z = data(:,10);
obj.ADXL345D.X = data(:,11);
obj.ADXL345D.Y = data(:,12);
obj.ADXL345D.Z = data(:,13);
obj.SampleRate = obj.SampleRate; % call set method to create time vector
end
end
%% Public methods
methods (Access = public)
function fig = Plot(obj)
if(obj.NumPackets == 0)
error('No data to plot.');
else
if(isempty(obj.Time))
time = 1:obj.NumPackets;
else
time = obj.Time;
end
fig = figure('Name', obj.CreateFigName());
ax(1) = subplot(4,1,1);
hold on;
plot(time, obj.ADXL345A.X, 'r');
plot(time, obj.ADXL345A.Y, 'g');
plot(time, obj.ADXL345A.Z, 'b');
legend('X', 'Y', 'Z');
xlabel(obj.TimeAxis);
ylabel(strcat('Acceleration (', obj.AccelerometerUnits, ')'));
title('ADXL345 A');
hold off;
ax(2) = subplot(4,1,2);
hold on;
plot(time, obj.ADXL345B.X, 'r');
plot(time, obj.ADXL345B.Y, 'g');
plot(time, obj.ADXL345B.Z, 'b');
legend('X', 'Y', 'Z');
xlabel(obj.TimeAxis);
ylabel(strcat('Acceleration (', obj.AccelerometerUnits, ')'));
title('ADXL345 B');
hold off;
ax(3) = subplot(4,1,3);
hold on;
plot(time, obj.ADXL345C.X, 'r');
plot(time, obj.ADXL345C.Y, 'g');
plot(time, obj.ADXL345C.Z, 'b');
legend('X', 'Y', 'Z');
xlabel(obj.TimeAxis);
ylabel(strcat('Acceleration (', obj.AccelerometerUnits, ')'));
title('ADXL345 C');
hold off;
ax(4) = subplot(4,1,4);
hold on;
plot(time, obj.ADXL345D.X, 'r');
plot(time, obj.ADXL345D.Y, 'g');
plot(time, obj.ADXL345D.Z, 'b');
legend('X', 'Y', 'Z');
xlabel(obj.TimeAxis);
ylabel(strcat('Acceleration (', obj.AccelerometerUnits, ')'));
title('ADXL345 D');
hold off;
linkaxes(ax,'x');
end
end
end
end

View File

@ -0,0 +1,69 @@
classdef AnalogueInputDataBaseClass < TimeSeriesDataBaseClass
%% Abstract public 'read-only' properties
properties (Abstract, SetAccess = private)
FileNameAppendage;
end
%% Public 'read-only' properties
properties (SetAccess = private)
AX0 = [];
AX1 = [];
AX2 = [];
AX3 = [];
AX4 = [];
AX5 = [];
AX6 = [];
AX7 = [];
end
%% Abstract protected properties
properties (Access = protected)
ADCunits;
end
%% Protected methods
methods (Access = protected)
function obj = Import(obj, fileNamePrefix)
data = obj.ImportCSVnumeric(fileNamePrefix);
obj.AX0 = data(:,2);
obj.AX1 = data(:,3);
obj.AX2 = data(:,4);
obj.AX3 = data(:,5);
obj.AX4 = data(:,6);
obj.AX5 = data(:,7);
obj.AX6 = data(:,8);
obj.AX7 = data(:,9);
obj.SampleRate = obj.SampleRate; % call set method to create time vector
end
end
%% Public methods
methods (Access = public)
function fig = Plot(obj)
if(obj.NumPackets == 0)
error('No data to plot.');
else
if(isempty(obj.Time))
time = 1:obj.NumPackets;
else
time = obj.Time;
end
fig = figure('Name', obj.CreateFigName());
hold on;
plot(time, obj.AX0, 'r');
plot(time, obj.AX1, 'g');
plot(time, obj.AX2, 'b');
plot(time, obj.AX3, 'k');
plot(time, obj.AX4, ':r');
plot(time, obj.AX5, ':g');
plot(time, obj.AX6, ':b');
plot(time, obj.AX7, ':k');
xlabel(obj.TimeAxis);
ylabel(strcat('Voltage (', obj.ADCunits, ')'));
title('Analogue Input');
hold off;
end
end
end
end

View File

@ -0,0 +1,60 @@
classdef BatteryAndThermometerDataBaseClass < TimeSeriesDataBaseClass
%% Abstract public 'read-only' properties
properties (Abstract, SetAccess = private)
FileNameAppendage;
end
%% Public 'read-only' properties
properties (SetAccess = private)
Battery = [];
Thermometer = [];
end
%% Abstract protected properties
properties (Access = protected)
ThermometerUnits;
BatteryUnits;
end
%% Protected methods
methods (Access = protected)
function obj = Import(obj, fileNamePrefix)
data = obj.ImportCSVnumeric(fileNamePrefix);
obj.Battery = data(:,2);
obj.Thermometer = data(:,3);
obj.SampleRate = obj.SampleRate; % call set method to create time vector
end
end
%% Public methods
methods (Access = public)
function fig = Plot(obj)
if(obj.NumPackets == 0)
error('No data to plot.');
else
if(isempty(obj.Time))
time = 1:obj.NumPackets;
else
time = obj.Time;
end
fig = figure('Name', obj.CreateFigName());
ax(1) = subplot(2,1,1);
hold on;
plot(time, obj.Battery);
xlabel(obj.TimeAxis);
ylabel(strcat('Voltage (', obj.BatteryUnits, ')'));
title('Battery Voltmeter');
hold off;
ax(2) = subplot(2,1,2);
hold on;
plot(time, obj.Thermometer);
xlabel(obj.TimeAxis);
ylabel(strcat('Temperature (', obj.ThermometerUnits, ')'));
title('Thermometer');
hold off;
linkaxes(ax,'x');
end
end
end
end

View File

@ -0,0 +1,23 @@
classdef CalADXL345busDataClass < ADXL345busDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_CalADXL345bus.csv';
end
%% Public methods
methods (Access = public)
function obj = CalADXL345busDataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
obj.Import(fileNamePrefix);
% Set protected parent class variables
obj.AccelerometerUnits = 'g';
end
end
end

View File

@ -0,0 +1,23 @@
classdef CalAnalogueInputDataClass < AnalogueInputDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_CalAnalogueInput.csv';
end
%% Public methods
methods (Access = public)
function obj = CalAnalogueInputDataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
obj.Import(fileNamePrefix);
% Set protected parent class variables
obj.ADCunits = 'V';
end
end
end

View File

@ -0,0 +1,24 @@
classdef CalBatteryAndThermometerDataClass < BatteryAndThermometerDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_CalBattAndTherm.csv';
end
%% Public methods
methods (Access = public)
function obj = CalBatteryAndThermometerDataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
obj.Import(fileNamePrefix);
% Set protected parent class variables
obj.ThermometerUnits = '^\circC';
obj.BatteryUnits = 'G';
end
end
end

View File

@ -0,0 +1,25 @@
classdef CalInertialAndMagneticDataClass < InertialAndMagneticDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_CalInertialAndMag.csv';
end
%% Public methods
methods (Access = public)
function obj = CalInertialAndMagneticDataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
obj.Import(fileNamePrefix);
% Set protected parent class variables
obj.GyroscopeUnits = '^\circ/s';
obj.AccelerometerUnits = 'g';
obj.MagnetometerUnits = 'G';
end
end
end

View File

@ -0,0 +1,18 @@
classdef CommandDataClass < DataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_Commands.csv';
Code = [];
Message = [];
end
%% Public methods
methods (Access = public)
function obj = CommandDataClass(fileNamePrefix)
data = obj.ImportCSVmixed(fileNamePrefix, '%f %f %s');
obj.Code = data{2};
obj.Message = data{3};
end
end
end

View File

@ -0,0 +1,44 @@
classdef DataBaseClass < handle
%% Abstract public 'read-only' properties
properties (Abstract, SetAccess = private)
FileNameAppendage;
end
%% Public 'read-only' properties
properties (SetAccess = private)
NumPackets = 0;
PacketNumber = [];
end
%% Protected methods
methods (Access = protected)
function data = ImportCSVnumeric(obj, fileNamePrefix)
data = dlmread(obj.CreateFileName(fileNamePrefix), ',', 1, 0);
obj.PacketNumber = data(:,1);
obj.NumPackets = length(obj.PacketNumber);
end
function data = ImportCSVmixed(obj, fileNamePrefix, fieldSpecifier)
fid = fopen(obj.CreateFileName(fileNamePrefix));
fgets(fid); % disregard column headings
data = textscan(fid, fieldSpecifier, 'Delimiter', ',');
fclose(fid);
obj.PacketNumber = data{1};
obj.NumPackets = length(obj.PacketNumber);
end
function figName = CreateFigName(obj)
[pathstr, name , ext, versn] = fileparts(obj.FileNameAppendage);
figName = name(2:end);
end
end
%% Private methods
methods (Access = private)
function fileName = CreateFileName(obj, fileNamePrefix)
fileName = strcat(fileNamePrefix, obj.FileNameAppendage);
if(~exist(fileName, 'file'))
error('File not found. No data was imported.');
end
end
end
end

View File

@ -0,0 +1,30 @@
classdef DateTimeDataClass < TimeSeriesDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_DateTime.csv';
String = [];
Vector = [];
Serial = [];
end
%% Public methods
methods (Access = public)
function obj = DateTimeDataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
data = obj.ImportCSVnumeric(fileNamePrefix);
obj.Vector = data(:,2:7);
obj.String = cellstr(datestr(obj.Vector));
obj.Serial = datenum(obj.Vector);
obj.SampleRate = obj.SampleRate; % call set method to create time vector
end
function obj = Plot(obj)
error('This method is unimplemented.');
end
end
end

View File

@ -0,0 +1,65 @@
classdef DigitalIODataClass < TimeSeriesDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_DigitalIO.csv';
Direction = struct('AX0', [], 'AX1', [], 'AX2', [], 'AX3', [], 'AX4', [], 'AX5', [], 'AX6', [], 'AX7', []);
State = struct('AX0', [], 'AX1', [], 'AX2', [], 'AX3', [], 'AX4', [], 'AX5', [], 'AX6', [], 'AX7', []);
end
%% Public methods
methods (Access = public)
function obj = DigitalIOdataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
data = obj.ImportCSVnumeric(fileNamePrefix);
obj.Direction.AX0 = data(:,2);
obj.Direction.AX1 = data(:,3);
obj.Direction.AX2 = data(:,4);
obj.Direction.AX3 = data(:,5);
obj.Direction.AX4 = data(:,6);
obj.Direction.AX5 = data(:,7);
obj.Direction.AX6 = data(:,8);
obj.Direction.AX7 = data(:,9);
obj.State.AX0 = data(:,10);
obj.State.AX1 = data(:,11);
obj.State.AX2 = data(:,12);
obj.State.AX3 = data(:,13);
obj.State.AX4 = data(:,14);
obj.State.AX5 = data(:,15);
obj.State.AX6 = data(:,16);
obj.State.AX7 = data(:,17);
obj.SampleRate = obj.SampleRate; % call set method to create time vector
end
function fig = Plot(obj)
if(obj.NumPackets == 0)
error('No data to plot.');
else
if(isempty(obj.Time))
time = 1:obj.NumPackets;
else
time = obj.Time;
end
fig = figure('Name', obj.CreateFigName());
hold on;
plot(time, obj.State.AX0, 'r');
plot(time, obj.State.AX1, 'g');
plot(time, obj.State.AX2, 'b');
plot(time, obj.State.AX3, 'k');
plot(time, obj.State.AX4, ':r');
plot(time, obj.State.AX5, ':g');
plot(time, obj.State.AX6, ':b');
plot(time, obj.State.AX7, ':k');
title('Digital I/O');
xlabel(obj.TimeAxis);
ylabel('State (Binary)');
legend('AX0', 'AX1', 'AX2', 'AX3', 'AX4', 'AX5', 'AX6', 'AX7');
hold off;
end
end
end
end

View File

@ -0,0 +1,18 @@
classdef ErrorDataClass < DataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_Errors.csv';
Code = [];
Message = [];
end
%% Public methods
methods (Access = public)
function obj = ErrorDataClass(fileNamePrefix)
data = obj.ImportCSVmixed(fileNamePrefix, '%f %f %s');
obj.Code = data{2};
obj.Message = data{3};
end
end
end

View File

@ -0,0 +1,48 @@
classdef EulerAnglesDataClass < TimeSeriesDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_EulerAngles.csv';
Phi = [];
Theta = [];
Psi = [];
end
%% Public methods
methods (Access = public)
function obj = EulerAnglesDataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
data = obj.ImportCSVnumeric(fileNamePrefix);
obj.Phi = data(:,2);
obj.Theta = data(:,3);
obj.Psi = data(:,4);
obj.SampleRate = obj.SampleRate; % call set method to create time vector
end
function fig = Plot(obj)
if(obj.NumPackets == 0)
error('No data to plot.');
else
if(isempty(obj.Time))
time = 1:obj.NumPackets;
else
time = obj.Time;
end
fig = figure('Name', obj.CreateFigName());
hold on;
plot(time, obj.Phi, 'r');
plot(time, obj.Theta, 'g');
plot(time, obj.Psi, 'b');
title('Euler angles');
xlabel(obj.TimeAxis);
ylabel('Angle (degrees)');
legend('\phi', '\theta', '\psi');
hold off;
end
end
end
end

View File

@ -0,0 +1,38 @@
function xIMUdataStruct = ImportDirectory(directory)
%IMPORTDIRECTORY Imports all x-IMU data CSV files within directory
%
% xIMUdataStruct = ImportDirectory(directory)
%
% Automatically imports x-IMU CSV files within specified directly.
% Imported data is returned as a structure of xIMUdataClass objects. The
% name of each member will "ID_ABCD" where "ABCD" if the x-IMU device ID
% if available (i.e. if *_Registers.csv file present) or "FILE_00000"
% where "00000" is the file name prefix of the CSV files.
%% Import CSV files
listing = dir(strcat(directory, '\*_*.csv')); % list all *_*.csv files in directory
fileNamePrefixes = unique(strtok({listing.name}, '_')); % list unique file name prefixes (e.g. name_*.csv)
xIMUdataObjs = cell(length(fileNamePrefixes), 1);
for i = 1:length(fileNamePrefixes)
try xIMUdataObjs{i} = xIMUdataClass(strcat(directory, '\', fileNamePrefixes{i})); catch e, end
end
fileNamePrefixes(cellfun(@isempty,xIMUdataObjs)) = []; % remove failures from lists
xIMUdataObjs(cellfun(@isempty,xIMUdataObjs)) = [];
if(numel(xIMUdataObjs) == 0)
error('No data was imported.');
end
%% Organise data in structure
fieldNames = cell(numel(xIMUdataObjs), 1);
try % try using device IDs as structure field names
for i = 1:numel(xIMUdataObjs)
fieldNames{i} = strcat('ID_', dec2hex(xIMUdataObjs{i}.RegisterData.GetValueAtAddress(2)));
end
xIMUdataStruct = orderfields(cell2struct(xIMUdataObjs, fieldNames, 1));
catch e % otherwise use file name prefix (alpha-numeric characters only)
for i = 1:numel(xIMUdataObjs)
fieldNames{i} = strcat('FILE_', fileNamePrefixes{i}(isstrprop(fileNamePrefixes{i}, 'alphanum')));
end
xIMUdataStruct = orderfields(cell2struct(xIMUdataObjs, fieldNames, 1));
end
end

View File

@ -0,0 +1,85 @@
classdef InertialAndMagneticDataBaseClass < TimeSeriesDataBaseClass
%% Abstract public 'read-only' properties
properties (Abstract, SetAccess = private)
FileNameAppendage;
end
%% Public 'read-only' properties
properties (SetAccess = private)
Gyroscope = struct('X', [], 'Y', [], 'Z', []);
Accelerometer = struct('X', [], 'Y', [], 'Z', []);
Magnetometer = struct('X', [], 'Y', [], 'Z', []);
end
%% Abstract protected properties
properties (Access = protected)
GyroscopeUnits;
AccelerometerUnits;
MagnetometerUnits;
end
%% Protected methods
methods (Access = protected)
function obj = Import(obj, fileNamePrefix)
data = obj.ImportCSVnumeric(fileNamePrefix);
obj.Gyroscope.X = data(:,2);
obj.Gyroscope.Y = data(:,3);
obj.Gyroscope.Z = data(:,4);
obj.Accelerometer.X = data(:,5);
obj.Accelerometer.Y = data(:,6);
obj.Accelerometer.Z = data(:,7);
obj.Magnetometer.X = data(:,8);
obj.Magnetometer.Y = data(:,9);
obj.Magnetometer.Z = data(:,10);
obj.SampleRate = obj.SampleRate; % call set method to create time vector
end
end
%% Public methods
methods (Access = public)
function fig = Plot(obj)
if(obj.NumPackets == 0)
error('No data to plot.');
else
if(isempty(obj.Time))
time = 1:obj.NumPackets;
else
time = obj.Time;
end
fig = figure('Name', obj.CreateFigName());
ax(1) = subplot(3,1,1);
hold on;
plot(time, obj.Gyroscope.X, 'r');
plot(time, obj.Gyroscope.Y, 'g');
plot(time, obj.Gyroscope.Z, 'b');
legend('X', 'Y', 'Z');
xlabel(obj.TimeAxis);
ylabel(strcat('Angular rate (', obj.GyroscopeUnits, ')'));
title('Gyroscope');
hold off;
ax(2) = subplot(3,1,2);
hold on;
plot(time, obj.Accelerometer.X, 'r');
plot(time, obj.Accelerometer.Y, 'g');
plot(time, obj.Accelerometer.Z, 'b');
legend('X', 'Y', 'Z');
xlabel(obj.TimeAxis);
ylabel(strcat('Acceleration (', obj.AccelerometerUnits, ')'));
title('Accelerometer');
hold off;
ax(3) = subplot(3,1,3);
hold on;
plot(time, obj.Magnetometer.X, 'r');
plot(time, obj.Magnetometer.Y, 'g');
plot(time, obj.Magnetometer.Z, 'b');
legend('X', 'Y', 'Z');
xlabel(obj.TimeAxis);
ylabel(strcat('Flux (', obj.MagnetometerUnits, ')'));
title('Magnetometer');
hold off;
linkaxes(ax,'x');
end
end
end
end

View File

@ -0,0 +1,22 @@
classdef PWMoutputDataClass < DataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_PWMoutput.csv';
AX0 = [];
AX2 = [];
AX4 = [];
AX6 = [];
end
%% Public methods
methods (Access = public)
function obj = PWMoutputDataClass(fileNamePrefix)
data = obj.ImportCSVnumeric(fileNamePrefix);
obj.AX0 = data(:,2);
obj.AX2 = data(:,3);
obj.AX4 = data(:,4);
obj.AX6 = data(:,5);
end
end
end

View File

@ -0,0 +1,26 @@
classdef QuaternionDataClass < TimeSeriesDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_Quaternion.csv';
Quaternion = [];
end
%% Public methods
methods (Access = public)
function obj = QuaternionDataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
data = obj.ImportCSVnumeric(fileNamePrefix);
obj.Quaternion = data(:,2:5);
obj.SampleRate = obj.SampleRate; % call set method to create time vector
end
function obj = Plot(obj)
error('This method is unimplemented.');
end
end
end

View File

@ -0,0 +1,23 @@
classdef RawADXL345busDataClass < ADXL345busDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_RawADXL345bus.csv';
end
%% Public methods
methods (Access = public)
function obj = RawADXL345busDataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
obj.Import(fileNamePrefix);
% Set protected parent class variables
obj.AccelerometerUnits = 'g';
end
end
end

View File

@ -0,0 +1,23 @@
classdef RawAnalogueInputDataClass < AnalogueInputDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_RawAnalogueInput.csv';
end
%% Public methods
methods (Access = public)
function obj = RawAnalogueInputDataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
obj.Import(fileNamePrefix);
% Set protected parent class variables
obj.ADCunits = 'lsb';
end
end
end

View File

@ -0,0 +1,24 @@
classdef RawBatteryAndThermometerDataClass < BatteryAndThermometerDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_RawBattAndTherm.csv';
end
%% Public methods
methods (Access = public)
function obj = RawBatteryAndThermometerDataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
obj.Import(fileNamePrefix);
% Set protected parent class variables
obj.ThermometerUnits = 'lsb';
obj.BatteryUnits = 'lsb';
end
end
end

View File

@ -0,0 +1,25 @@
classdef RawInertialAndMagneticDataClass < InertialAndMagneticDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_RawInertialAndMag.csv';
end
%% Public methods
methods (Access = public)
function obj = RawInertialAndMagneticDataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
obj.Import(fileNamePrefix);
% Set protected parent class variables
obj.GyroscopeUnits = 'lsb';
obj.AccelerometerUnits = 'lsb';
obj.MagnetometerUnits = 'lsb';
end
end
end

View File

@ -0,0 +1,62 @@
classdef RegisterDataClass < DataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_Registers.csv';
Address = [];
Value = [];
FloatValue = [];
Name = {};
end
%% Public methods
methods (Access = public)
function obj = RegisterDataClass(fileNamePrefix)
data = obj.ImportCSVmixed(fileNamePrefix, '%f %f %f %f %s');
obj.Address = data{2};
obj.Value = data{3};
obj.FloatValue = data{4};
obj.Name = data{5};
end
function value = GetValueAtAddress(obj, address)
value = obj.ValueAtIndexes(obj.IndexesOfAddress(address));
end
function floatValue = GetFloatValueAtAddress(obj, address)
floatValue = obj.FloatValueAtIndexes(obj.IndexesOfAddress(address));
end
function value = GetValueAtName(obj, name)
value = obj.ValueAtIndexes(obj.IndexesOfName(name));
end
function floatValue = GetFloatValueAtName(obj, name)
floatValue = obj.FloatValueAtIndexes(obj.IndexesOfName(name));
end
end
%% Private methods
methods (Access = private)
function indexes = IndexesOfAddress(obj, address)
indexes = find(obj.Address == address);
if(isempty(indexes))
error('Register address not found.');
end
end
function indexes = IndexesOfName(obj, name)
indexes = find(ismember(obj.Name, name));
if(isempty(indexes))
error('Register name not found.');
end
end
function value = ValueAtIndexes(obj, indexes)
if(numel(unique(obj.Value(indexes))) > 1)
error('Conflicting register values exist.');
end
value = obj.Value(indexes(1));
end
function floatValue = FloatValueAtIndexes(obj, indexes)
if(numel(unique(obj.FloatValue(indexes))) > 1)
error('Conflicting register values exist.');
end
floatValue = obj.FloatValue(indexes(1));
end
end
end

View File

@ -0,0 +1,35 @@
classdef RotationMatrixDataClass < TimeSeriesDataBaseClass
%% Public 'read-only' properties
properties (SetAccess = private)
FileNameAppendage = '_RotationMatrix.csv';
RotationMatrix = [];
end
%% Public methods
methods (Access = public)
function obj = RotationMatrixDataClass(varargin)
fileNamePrefix = varargin{1};
for i = 2:2:nargin
if strcmp(varargin{i}, 'SampleRate'), obj.SampleRate = varargin{i+1};
else error('Invalid argument.');
end
end
data = obj.ImportCSVnumeric(fileNamePrefix);
obj.RotationMatrix = zeros(3, 3, obj.NumPackets);
obj.RotationMatrix(1,1,:) = data(:,2);
obj.RotationMatrix(1,2,:) = data(:,3);
obj.RotationMatrix(1,3,:) = data(:,4);
obj.RotationMatrix(2,1,:) = data(:,5);
obj.RotationMatrix(2,2,:) = data(:,6);
obj.RotationMatrix(2,3,:) = data(:,7);
obj.RotationMatrix(3,1,:) = data(:,8);
obj.RotationMatrix(3,2,:) = data(:,9);
obj.RotationMatrix(3,3,:) = data(:,10);
obj.SampleRate = obj.SampleRate; % call set method to create time vector
end
function obj = Plot(obj)
error('This method is unimplemented.');
end
end
end

View File

@ -0,0 +1,101 @@
function SyncroniseData(varargin)
%SYNCRONISEDATA Syncronises time series data between xIMUdataClass objects
%
% SyncroniseData(xIMUdataStruct, StartEventTimes)
% SyncroniseData(xIMUdataStruct, StartEventTimes, EndEventTimes)
% SyncroniseData(xIMUdataStruct, 'UseAX0fallingEdge')
%
% This fuction syncronises time series data between xIMUdataClass objects
% by adjusting the StartTime and SampleRate properties of each data
% class.
%
% StartEventTimes is vector of values representing the time at which a
% 'start synchronisation event' common to all xIMUdataClass objects is
% known to occur within each xIMUdataClass object's time series data. The
% length of this vector must equal the number of xIMUdataClass objects
% in xIMUdataStruct.
%
% EndEventTimes is vector of values representing the time at which a
% 'end synchronisation event' common to all xIMUdataClass objects is
% known to occur within each xIMUdataClass object's time series data. The
% length of this vector must equal the number of xIMUdataClass objects
% in xIMUdataStruct.
%
% 'UseAX0fallingEdge' should be specified if a falling edge of the
% auxilary port (configured in digital I/O mode) channel AX0 represents
% the 'start synchronisation event' or 'start synchronisation event' and
% 'end synchronisation event'.
%% Apply arguments
xIMUdata = varargin{1};
xIMUdataObjs = struct2cell(xIMUdata);
StartEventTimes = [];
EndEventTimes = [];
UseAX0fallingEdge = false;
if(ischar(varargin{2}))
if strcmp(varargin{2}, 'UseAX0fallingEdge'), UseAX0fallingEdge = true;
else error('Invalid argument.');
end
else
StartEventTimes = varargin{2};
if(nargin == 3)
EndEventTimes = varargin{3};
end
end
%% Use AX0 falling edge of auxiliary port in Digital I/O mode
if(UseAX0fallingEdge)
for i = 1:numel(xIMUdataObjs)
fallingEdgeIndexes = [0; diff(xIMUdataObjs{i}.DigitalIOdata.State.AX0)] == -1;
fallingEdgeTimes = xIMUdataObjs{i}.DigitalIOdata.Time(fallingEdgeIndexes);
StartEventTimes = [StartEventTimes; fallingEdgeTimes(1)];
if(numel(fallingEdgeTimes) > 1)
EndEventTimes = [EndEventTimes; fallingEdgeTimes(end)];
end
end
end
%% Modify start times to synchronise start of window
if(numel(StartEventTimes) ~= numel(xIMUdataObjs))
error('Length of StartEventTimes vector must equal number of xIMUdataClass objects');
end
for i = 1:numel(xIMUdataObjs)
try h = xIMUdataObjs{i}.DateTimeData; h.StartTime = -StartEventTimes(i); catch e, end
try h = xIMUdataObjs{i}.RawBatteryAndThermometerData; h.StartTime = -StartEventTimes(i); catch e, end
try h = xIMUdataObjs{i}.CalBatteryAndThermometerData; h.StartTime = -StartEventTimes(i); catch e, end
try h = xIMUdataObjs{i}.RawInertialAndMagneticData; h.StartTime = -StartEventTimes(i); catch e, end
try h = xIMUdataObjs{i}.CalInertialAndMagneticData; h.StartTime = -StartEventTimes(i); catch e, end
try h = xIMUdataObjs{i}.QuaternionData; h.StartTime = -StartEventTimes(i); catch e, end
try h = xIMUdataObjs{i}.RotationMatrixData; h.StartTime = -StartEventTimes(i); catch e, end
try h = xIMUdataObjs{i}.EulerAnglesData; h.StartTime = -StartEventTimes(i); catch e, end
try h = xIMUdataObjs{i}.DigitalIOdata; h.StartTime = -StartEventTimes(i); catch e, end
try h = xIMUdataObjs{i}.RawAnalogueInputData; h.StartTime = -StartEventTimes(i); catch e, end
try h = xIMUdataObjs{i}.CalAnalogueInputData; h.StartTime = -StartEventTimes(i); catch e, end
try h = xIMUdataObjs{i}.RawADXL345busData; h.StartTime = -StartEventTimes(i); catch e, end
try h = xIMUdataObjs{i}.CalADXL345busData; h.StartTime = -StartEventTimes(i); catch e, end
end
%% Modify sample rate to synchronise end of window
if(numel(EndEventTimes) == 0)
return;
end
if(numel(EndEventTimes) ~= numel(xIMUdataObjs))
error('Length of EndEventTimes vector must equal number of xIMUdataClass objects');
end
scalers = (EndEventTimes - StartEventTimes) * (1/((EndEventTimes(1)-StartEventTimes(1))));
for i = 2:numel(xIMUdataObjs)
try h = xIMUdataObjs{i}.DateTimeData; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = StartEventTimes(i)/scalers(i); catch e, end
try h = xIMUdataObjs{i}.RawBatteryAndThermometerData; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = StartEventTimes(i)/scalers(i); catch e, end
try h = xIMUdataObjs{i}.CalBatteryAndThermometerData; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = StartEventTimes(i)/scalers(i); catch e, end
try h = xIMUdataObjs{i}.RawInertialAndMagneticData; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = StartEventTimes(i)/scalers(i); catch e, end
try h = xIMUdataObjs{i}.CalInertialAndMagneticData; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = -StartEventTimes(i)/scalers(i); catch e, end
try h = xIMUdataObjs{i}.QuaternionData; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = StartEventTimes(i)/scalers(i); catch e, end
try h = xIMUdataObjs{i}.RotationMatrixData; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = StartEventTimes(i)/scalers(i); catch e, end
try h = xIMUdataObjs{i}.EulerAnglesData; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = StartEventTimes(i)/scalers(i); catch e, end
try h = xIMUdataObjs{i}.DigitalIOdata; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = StartEventTimes(i)/scalers(i); catch e, end
try h = xIMUdataObjs{i}.RawAnalogueInputData; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = StartEventTimes(i)/scalers(i); catch e, end
try h = xIMUdataObjs{i}.CalAnalogueInputData; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = StartEventTimes(i)/scalers(i); catch e, end
try h = xIMUdataObjs{i}.RawADXL345busData; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = StartEventTimes(i)/scalers(i); catch e, end
try h = xIMUdataObjs{i}.CalADXL345busData; h.SampleRate = scalers(i)*h.SampleRate; h.StartTime = StartEventTimes(i)/scalers(i); catch e, end
end
end

View File

@ -0,0 +1,54 @@
classdef TimeSeriesDataBaseClass < DataBaseClass
%% Abstract public 'read-only' properties
properties (Abstract, SetAccess = private)
FileNameAppendage;
end
%% Public 'read-only' properties
properties (SetAccess = private)
Time = [];
SamplePeriod = 0;
end
%% Public properties
properties (Access = public)
SampleRate = 0;
StartTime = 0;
end
%% Protected properties
properties (Access = protected)
TimeAxis;
end
%% Abstract public methods
methods (Abstract, Access = public)
Plot(obj);
end
%% Get/set methods
methods
function obj = set.SampleRate(obj, sampleRate)
obj.SampleRate = sampleRate;
if(obj.SampleRate == 0)
obj.Time = [];
obj.TimeAxis = 'Sample';
elseif(obj.NumPackets ~= 0)
obj.Time = (0:obj.NumPackets-1)' * (1/obj.SampleRate) + obj.StartTime;
obj.TimeAxis = 'Time (s)';
end
end
function obj = set.StartTime(obj, startTime)
obj.StartTime = startTime;
obj.SampleRate = obj.SampleRate;
end
function samplePeriod = get.SamplePeriod(obj)
if(obj.SampleRate == 0)
samplePeriod = 0;
else
samplePeriod = 1 / obj.SampleRate;
end
end
end
end

View File

@ -0,0 +1,116 @@
classdef xIMUdataClass < handle
%% Public properties
properties (SetAccess = private)
FileNamePrefix = '';
ErrorData = [];
CommandData = [];
RegisterData = [];
DateTimeData = [];
RawBatteryAndThermometerData = [];
CalBatteryAndThermometerData = [];
RawInertialAndMagneticData = [];
CalInertialAndMagneticData = [];
QuaternionData = [];
RotationMatrixData = [];
EulerAnglesData = [];
DigitalIOdata = [];
RawAnalogueInputData = [];
CalAnalogueInputData = [];
PWMoutputData = [];
RawADXL345busData = [];
CalADXL345busData = [];
end
%% Public methods
methods (Access = public)
function obj = xIMUdataClass(varargin)
% Create data objects from files
obj.FileNamePrefix = varargin{1};
dataImported = false;
try obj.ErrorData = ErrorDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.CommandData = CommandDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.RegisterData = RegisterDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.DateTimeData = DateTimeDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.RawBatteryAndThermometerData = RawBatteryAndThermometerDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.CalBatteryAndThermometerData = CalBatteryAndThermometerDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.RawInertialAndMagneticData = RawInertialAndMagneticDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.CalInertialAndMagneticData = CalInertialAndMagneticDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.QuaternionData = QuaternionDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.EulerAnglesData = EulerAnglesDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.RotationMatrixData = RotationMatrixDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.DigitalIOdata = DigitalIOdataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.RawAnalogueInputData = RawAnalogueInputDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.CalAnalogueInputData = CalAnalogueInputDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.PWMoutputData = PWMoutputDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.RawADXL345busData = RawADXL345busDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
try obj.CalADXL345busData = CalADXL345busDataClass(obj.FileNamePrefix); dataImported = true; catch e, end
if(~dataImported)
error('No data was imported.');
end
% Apply SampleRate from register data
try h = obj.DateTimeData; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(67)); catch e, end
try h = obj.RawBatteryAndThermometerData; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(68)); catch e, end
try h = obj.CalBatteryAndThermometerData; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(68)); catch e, end
try h = obj.RawInertialAndMagneticData; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(69)); catch e, end
try h = obj.CalInertialAndMagneticData; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(69)); catch e, end
try h = obj.QuaternionData; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(70)); catch e, end
try h = obj.RotationMatrixData; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(70)); catch e, end
try h = obj.EulerAnglesData; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(70)); catch e, end
try h = obj.DigitalIOdata; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(78)); catch e, end
try h = obj.RawAnalogueInputData; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(80)); catch e, end
try h = obj.CalAnalogueInputData; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(80)); catch e, end
try h = obj.RawADXL345busData; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(85)); catch e, end
try h = obj.CalADXL345busData; h.SampleRate = obj.SampleRateFromRegValue(obj.RegisterData.GetValueAtAddress(85)); catch e, end
% Apply SampleRate if specified as argument
for i = 2:2:(nargin)
if strcmp(varargin{i}, 'DateTimeSampleRate')
try h = obj.DateTimeData; h.SampleRate = varargin{i+1}; catch e, end
elseif strcmp(varargin{i}, 'BattThermSampleRate')
try h = obj.RawBatteryAndThermometerData; h.SampleRate = varargin{i+1}; catch e, end
try h = obj.CalBatteryAndThermometerData; h.SampleRate = varargin{i+1}; catch e, end
elseif strcmp(varargin{i}, 'InertialMagneticSampleRate')
try h = obj.RawInertialAndMagneticData; h.SampleRate = varargin{i+1}; catch e, end
try h = obj.CalInertialAndMagneticData; h.SampleRate = varargin{i+1}; catch e, end
elseif strcmp(varargin{i}, 'QuaternionSampleRate')
try h = obj.QuaternionData; h.SampleRate = varargin{i+1}; catch e, end
try h = obj.RotationMatrixData.SampleRate; h.SampleRate = varargin{i+1}; catch e, end
try h = obj.EulerAnglesData; h.SampleRate = varargin{i+1}; catch e, end
elseif strcmp(varargin{i}, 'DigitalIOSampleRate')
try h = obj.DigitalIOdata; h.SampleRate = varargin{i+1}; catch e, end
elseif strcmp(varargin{i}, 'AnalogueInputSampleRate')
try h = obj.RawAnalogueInputData; h.SampleRate = varargin{i+1}; catch e, end
try h = obj.CalAnalogueInputData; h.SampleRate = varargin{i+1}; catch e, end
elseif strcmp(varargin{i}, 'ADXL345SampleRate')
try h = obj.RawADXL345busData; h.SampleRate = varargin{i+1}; catch e, end
try h = obj.CalADXL345busData; h.SampleRate = varargin{i+1}; catch e, end
else
error('Invalid argument.');
end
end
end
function obj = Plot(obj)
try obj.RawBatteryAndThermometerData.Plot(); catch e, end
try obj.CalBatteryAndThermometerData.Plot(); catch e, end
try obj.RawInertialAndMagneticData.Plot(); catch e, end
try obj.CalInertialAndMagneticData.Plot(); catch e, end
try obj.QuaternionData.Plot(); catch e, end
try obj.EulerAnglesData.Plot(); catch e, end
try obj.RotationMatrixDataClass.Plot(); catch e, end
try obj.DigitalIOdata.Plot(); catch e, end
try obj.RawAnalogueInputData.Plot(); catch e, end
try obj.CalAnalogueInputData.Plot(); catch e, end
try obj.RawADXL345busData.Plot(); catch e, end
try obj.CalADXL345busData.Plot(); catch e, end
end
end
%% Private methods
methods (Access = private)
function sampleRate = SampleRateFromRegValue(obj, value)
sampleRate = floor(2^(value-1));
end
end
end

View File

@ -0,0 +1,30 @@
#include "UWBFilter.h"
#include "math.h"
UWBFilter::UWBFilter() {
}
void UWBFilter::update(float& x, float& y,float& vo) {
if (initFlag == false) {
lastX = x;
lastY = y;
lastXf = x;
lastYf = y;
initFlag = true;
}
float d2 = (x - lastX) * (x - lastX) + (y - lastY) * (y - lastY);
lastX = x;
lastY = y;
// 判断速度是否有效遇到重复值速度为0
float v = d2 == 0 ? lastV : sqrtf(d2);
// 根据速度参数选择不同滤波器参数
float alpha = v < 50 ? 0.98f : 0.999f;
x = lastXf * alpha + (1 - alpha) * x;
y = lastYf * alpha + (1 - alpha) * y;
// 记录上一次的滤波值
lastXf = x;
lastYf = y;
lastV = v;
vo = v;
;}

View File

@ -0,0 +1,14 @@
#pragma once
class UWBFilter {
public:
UWBFilter();
void update(float& x, float& y, float& vo);
private:
float lastX;
float lastY;
float lastXf;
float lastYf;
float lastV = 0.0f;
int thres = 50;
bool initFlag = false;
};

View File

@ -0,0 +1,46 @@
#include <iostream>
#include <fstream>
#include <sstream>
#include <vector>
#include "UWBFilter.h"
struct Point {
float x;
float y;
};
int main() {
std::ifstream file("a3.txt"); // 假设数据保存在名为 data.txt 的文件中
std::ofstream fileOut("a3_out.txt");
std::vector<Point> points;
UWBFilter filter;
if (file.is_open() && fileOut.is_open()) {
std::string line;
// 逐行读取数据
while (std::getline(file, line)) {
std::stringstream ss(line);
Point p;
char delimiter;
// 从每行中读取 x 和 y 值,并用逗号分隔
if (ss >> p.x >> delimiter >> p.y) {
float xf = p.x;
float yf = p.y;
float v = 0.0f;
filter.update(xf, yf, v);
fileOut << p.x << "," << p.y << "," << xf << "," << yf << "," << v << std::endl;
}
}
file.close();
fileOut.close();
}
else {
std::cerr << "无法打开文件!" << std::endl;
return 1;
}
// 打印读取到的数据
for (const auto& point : points) {
std::cout << "x: " << point.x << ", y: " << point.y << std::endl;
}
return 0;
}

Binary file not shown.

Binary file not shown.

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,614 @@
-6.70312,45.985,-6.70312,45.985,0
-1.90859,39.105,-6.4634,45.641,8.38582
-5.15078,38.15,-6.39777,45.2664,3.37991
-6.19922,47.4588,-6.38784,45.3761,9.36761
-11.4992,51.7188,-6.64341,45.6932,6.79982
-5.29922,49.6,-6.5762,45.8885,6.55203
-1.26875,43.5262,-6.31083,45.7704,7.28938
-4.1125,60.52,-6.20091,46.5079,17.23
-2.78125,55.2163,-6.02993,46.9433,5.46827
-5.80937,54.58,-6.0189,47.3252,3.09425
2.10547,57.64,-5.61268,47.8409,8.48577
0,56.9637,-5.33205,48.297,2.21141
0.291406,56.2337,-5.05087,48.6939,0.786013
-5.625,59.205,-5.07958,49.2194,6.62059
-6.75,60.5187,-5.1631,49.7844,1.72961
-7.01172,59.435,-5.25553,50.2669,1.1149
-7.24609,59.7438,-5.35506,50.7408,0.387632
-6.9,58.375,-5.43231,51.1225,1.41183
-5.71875,50.4362,-5.44663,51.0882,8.02615
-3.50625,52.9412,-5.34961,51.1808,3.34218
-4.95,48.3363,-5.32963,51.0386,4.82602
-7.525,33.245,-5.4394,50.1489,15.3094
-6.62187,38.22,-5.49852,49.5525,5.05631
-6.15,41.3088,-5.5311,49.1403,3.12459
-6.30859,41.2938,-5.56997,48.748,0.159301
-6.075,41.72,-5.59522,48.3966,0.486061
-7.31797,42.595,-5.68136,48.1065,1.52006
-7.27266,43.8363,-5.76092,47.893,1.24208
-8.775,45.845,-5.91163,47.7906,2.50841
-8.39453,49.54,-6.03577,47.878,3.71454
-7.38672,48.635,-6.10332,47.9159,1.35452
-9.04922,50.075,-6.25062,48.0238,2.19943
-8.52734,50.64,-6.36445,48.1547,0.769141
-9.97734,51.2738,-6.5451,48.3106,1.58245
-10.7586,50.5638,-6.75577,48.4233,1.05568
-11.175,53.26,-6.97673,48.6651,2.72821
-7.34766,48.4813,-6.99528,48.6559,6.1225
-9.0625,51.5863,-7.09864,48.8024,3.54707
-13.2312,55.1613,-7.40527,49.1204,5.49173
-4.05234,39.325,-7.23763,48.6306,18.3041
0.560156,37.2438,-6.84774,48.0613,5.06031
-5.09766,44.76,-6.76023,47.8962,9.4077
-5.6875,44.795,-6.7066,47.7411,0.590881
-6.32109,44.865,-6.68732,47.5973,0.637449
-5.425,38.2438,-6.6242,47.1297,6.68161
-5.07812,37.5238,-6.5469,46.6494,0.799202
-2.54922,40.3288,-6.34702,46.3333,3.77669
-3.15,40.9938,-6.18717,46.0663,0.896195
-2.86562,40,-6.02109,45.763,1.03364
-3.175,39.32,-5.87878,45.4409,0.74707
-2.75625,36.55,-5.72266,44.9963,2.80147
-1.5375,34.6,-5.5134,44.4765,2.29953
-1.1625,33.15,-5.29586,43.9102,1.4977
1.62422,26.5212,-4.94985,43.0407,7.1907
-1.43828,31.5763,-4.77427,42.4675,5.91032
-1.01953,27.25,-4.58654,41.7066,4.34647
-1.98438,28.975,-4.45643,41.07,1.9765
-1.2,50.17,-4.29361,41.525,21.2095
-2.82188,49.075,-4.22002,41.9025,1.95691
-1.625,48.925,-4.09027,42.2537,1.20624
0.199219,44.76,-3.87579,42.379,4.54698
-5.46016,43.5612,-3.95501,42.4381,5.78494
-7.03125,42.78,-4.10882,42.4552,1.75462
-6.03047,34.08,-4.20491,42.0364,8.75737
-3.22734,27.9137,-4.15603,41.3303,6.77349
-0.917969,34.5387,-3.99413,40.9907,7.01597
0,31.68,-3.79442,40.5252,3.00252
-0.75625,28.88,-3.64251,39.9429,2.90033
1.32891,27.76,-3.39394,39.3338,2.36691
5.38125,31.0462,-2.95518,38.9194,5.21737
5.21016,32.005,-2.54691,38.5737,0.973898
6.64453,34.6087,-2.08734,38.3754,2.9727
7.08203,37.3787,-1.62887,38.3256,2.80434
9.73047,36.55,-1.0609,38.2368,2.77508
2.42734,39.1413,-0.886492,38.282,7.74921
5.54766,42.0037,-0.564785,38.4681,4.23441
5.91328,39.7088,-0.240882,38.5302,2.32394
-5.15625,40.9263,-0.48665,38.65,11.1363
-2.30859,35.1338,-0.577747,38.4741,6.45463
-2.19141,32.59,-0.65843,38.1799,2.54645
-1.48438,25.12,-0.699727,37.5269,7.50338
-0.909375,28.695,-0.71021,37.0854,3.62094
-2.23125,36.55,-0.786262,37.0586,7.96545
-2.72266,37.9963,-0.883082,37.1055,1.52746
-0.824219,36.2788,-0.880139,37.0641,2.56005
0,36.37,-0.836132,37.0294,0.829254
0.532031,35.2,-0.767723,36.938,1.28528
-0.499219,35.36,-0.754298,36.8591,1.04359
-1.98047,34.3,-0.815607,36.7311,1.82146
-1.69297,36.115,-0.859475,36.7003,1.83763
-0.761719,37.6488,-0.854587,36.7477,1.79433
-1.02266,36.6362,-0.86299,36.7422,1.04558
12.057,36.395,-0.216989,36.7248,13.0819
6.97734,35.32,0.142728,36.6546,5.19219
3.34375,34.65,0.302779,36.5543,3.69485
1.325,37.325,0.35389,36.5929,3.35126
-1.07734,41,0.282328,36.8132,4.39054
0.475781,20.0987,0.292001,35.9775,20.9589
2.33203,23.935,0.394002,35.3754,4.26175
2.78437,25.2738,0.513521,34.8703,1.41311
2.14297,25.97,0.594993,34.4253,0.94666
5.80078,21.875,0.855283,33.7978,5.49078
6.67734,18.9562,1.14639,33.0557,3.04753
7.89453,28.4,1.48379,32.8229,9.52187
3.64375,29.5012,1.59179,32.6568,4.39112
-0.144531,31.5912,1.50497,32.6035,4.32657
-2.51016,35.56,1.30422,32.7514,4.6203
0.414844,32.0563,1.25975,32.7166,4.5642
-0.978906,35.6862,1.14782,32.8651,3.88837
0,28.8787,1.09043,32.6658,6.87752
-1.90313,33.9338,0.940749,32.7292,5.40138
-1.75703,30.9662,0.80586,32.641,2.97109
-1.90313,31.2,0.67041,32.569,0.27565
-0.265625,32.1338,0.623609,32.5472,1.88502
0.652344,33.35,0.625045,32.5874,1.52379
1.91016,31.165,0.689301,32.5162,2.52117
1.67578,29.5187,0.738625,32.3664,1.66285
5.375,19.1637,0.970444,31.7062,10.9959
2.95625,23.9112,1.06973,31.3165,5.32814
-1.50391,33.4062,0.941052,31.421,10.4904
3.73828,26.0088,1.08091,31.1504,9.06662
5.33203,27.7488,1.29347,30.9803,2.35958
4.74141,29.925,1.46587,30.9275,2.25497
-1.97109,36.985,1.29402,31.2304,9.74173
-0.7875,29.8113,1.18994,31.1594,7.27073
-0.65625,29.6012,1.09763,31.0815,0.247643
-0.355469,28.615,1.02498,30.9582,1.0311
-0.355469,30.3388,0.955955,30.9272,1.72375
-1.97109,34.7438,0.809603,31.118,4.69194
-3.62109,37.8138,0.588068,31.4528,3.48531
-3.28125,37.27,0.394602,31.7437,0.641217
-1.90625,37.4813,0.279559,32.0306,1.39113
-1.79609,36.445,0.175777,32.2513,1.04209
-0.321094,33.3737,0.150933,32.3074,3.40708
0.875,31.1338,0.187136,32.2487,2.53934
-6.09375,42.45,-0.126908,32.7588,13.2899
-6.8875,43.2012,-0.464938,33.2809,1.09289
-2.71484,37.825,-0.577433,33.5081,6.80552
-2.39062,43.045,-0.668093,33.985,5.23006
-5.15312,47.2137,-0.892344,34.6464,5.00099
-3.6375,46.0312,-1.0296,35.2156,1.92235
-4.50859,45.4338,-1.20355,35.7265,1.05632
-6.67266,49.7562,-1.47701,36.428,4.83396
-18.4195,62.94,-2.32413,37.7536,17.6579
-5.15625,42.1263,-2.46574,37.9723,24.6805
-4.34688,34.5387,-2.5598,37.8006,7.63055
-7.06563,38.6,-2.78509,37.8406,4.88726
-5.29375,38.63,-2.91052,37.88,1.77213
-10.9375,42.0312,-3.31187,38.0876,6.58942
-6.4,23.6,-3.46628,37.3632,18.9816
-0.384375,40.615,-3.31218,37.5258,18.0471
1.49297,40.66,-3.07192,37.6825,1.87788
-4.43437,40.695,-3.14005,37.8331,5.92745
-4.36562,22.4,-3.20132,37.0615,18.2951
-2.66875,24.6763,-3.1747,36.4422,2.83914
-0.878906,32.38,-3.05991,36.2391,7.90894
-1.59609,33.9437,-2.98672,36.1243,1.72037
-1.23047,34.0387,-2.8989,36.0201,0.377766
0.832031,31.74,-2.71236,35.8061,3.08839
2.33203,28.8,-2.46014,35.4558,3.30055
4.46875,27.9562,-2.11369,35.0808,2.29728
1.46875,27.4562,-1.93457,34.6996,3.04138
0.738281,29.455,-1.80093,34.4373,2.12805
0.61875,31.2812,-1.67994,34.2795,1.83016
-5.175,36.2137,-1.8547,34.3762,7.60901
-0.4875,29.395,-1.78634,34.1272,8.27454
-0.977344,31.165,-1.74589,33.9791,1.83653
0.278906,30.16,-1.64465,33.7881,1.60879
0.6375,39.93,-1.53054,34.0952,9.77658
-0.90625,34.61,-1.49933,34.1209,5.53945
-3.84375,38.5,-1.61655,34.3399,4.87453
-1.63125,39.2912,-1.61728,34.5875,2.34973
-3.45,41.515,-1.70892,34.9338,2.87279
-4.725,36.5,-1.85972,35.0121,5.17454
-5.00547,40,-2.01701,35.2615,3.51122
-2.29766,40.7012,-2.03104,35.5335,2.79714
-5.98828,50.7,-2.2289,36.2918,10.6581
-5.41875,41.74,-2.3884,36.5643,8.97808
-4.05625,45.95,-2.47179,37.0335,4.42499
-5.54609,43.4238,-2.6255,37.3531,2.93284
-7.3625,45.0812,-2.86235,37.7395,2.45899
0.177344,35.16,-2.71037,37.6105,12.4612
-16.9813,60.4712,-3.42391,38.7535,30.579
-2.825,40.8963,-3.39397,38.8607,24.1574
-3.22109,38.8,-3.38532,38.8576,2.13335
-4.2375,39.6862,-3.42793,38.8991,1.34853
-3.57734,42.8237,-3.4354,39.0953,3.2062
-9.80391,51.5913,-3.75383,39.7201,10.7536
-6.26484,40,-3.87938,39.7341,12.1195
-1.56797,33.7,-3.76381,39.4324,7.85816
-5.65,39.35,-3.85812,39.4283,6.97033
-1.02188,32.8988,-3.71631,39.1018,7.93966
-2.18359,31.04,-3.63967,38.6987,2.19193
-4.7125,40.9562,-3.69331,38.8116,10.2336
-6.48125,44.9313,-3.83271,39.1176,4.35076
0,36.55,-3.64107,38.9892,10.5949
2.01953,36.7687,-3.35804,38.8782,2.03134
2.19375,37.1,-3.08045,38.7893,0.37427
-0.175781,37.05,-2.93522,38.7023,2.37006
-1.8125,39.39,-2.87908,38.7367,2.8556
-0.7375,35.8887,-2.772,38.5943,3.66257
-2.69062,37.32,-2.76794,38.5306,2.4214
-1.37266,33.4212,-2.69817,38.2751,4.11549
-0.208594,42.2837,-2.57369,38.4755,8.93862
-1.82109,41.965,-2.53606,38.65,1.6437
-0.39375,40.3162,-2.42895,38.7333,2.18075
0.75,38.185,-2.27,38.7059,2.41876
0.3625,38.5312,-2.13837,38.6972,0.519658
0.178906,38.84,-2.02251,38.7043,0.359212
-0.174219,38.5687,-1.9301,38.6975,0.44528
-0.3375,38.0312,-1.85047,38.6642,0.561752
-2.7,39.7088,-1.89294,38.7164,2.89748
-2.20391,37.9263,-1.90849,38.6769,1.85025
-3.00938,40.575,-1.96353,38.7718,2.76851
-0.99375,38.89,-1.91505,38.7778,2.62716
-1.0875,39.7012,-1.87367,38.8239,0.816648
-1.95078,38.79,-1.87752,38.8222,1.25524
-2.3625,36.37,-1.90177,38.6996,2.45478
-0.925781,39.0812,-1.85297,38.7187,3.06839
-1.4375,38.4813,-1.8322,38.7068,0.788577
-1.07812,39.1037,-1.7945,38.7267,0.718786
-1.79688,39.6987,-1.79461,38.7753,0.933074
-4.5,42.8688,-1.92988,38.98,4.16603
-3.075,43.15,-1.98714,39.1885,1.45249
-3.20078,42.8013,-2.04782,39.3691,0.37074
-1.62422,39.6987,-2.02664,39.3856,3.4801
-1.4,37.9087,-1.99531,39.3117,1.80399
-2.36641,40,-2.01386,39.3462,2.30375
-1.8125,41.4813,-2.0038,39.4529,1.58143
-2.625,41.5563,-2.03486,39.5581,0.815954
-2.325,42.2137,-2.04936,39.6909,0.722705
9.84297,39.6862,-1.45475,39.6906,12.4277
9.25703,39.375,-0.919158,39.6748,0.663475
8.38125,40.3262,-0.454137,39.7074,1.29301
7.70859,40.3312,-0.0460006,39.7386,0.672675
9.90938,40,0.451768,39.7517,2.22557
8.50391,42.025,0.854375,39.8653,2.46495
10.7164,42.025,1.34748,39.9733,2.2125
0.988281,43.2588,1.32952,40.1376,9.80605
-0.186719,42.0387,1.25371,40.2327,1.69382
-1.05,41.9512,1.13852,40.3186,0.867704
-2.95,46.84,0.934094,40.6446,5.24499
4.05234,44.4813,1.09001,40.8365,7.38895
1.21875,46.9,1.09644,41.1397,3.72553
-12.75,59.5938,0.404121,42.0624,18.8748
-15.5867,63.8688,-0.395421,43.1527,5.13056
-9.45,52.1637,-0.84815,43.6032,13.2161
-8.92266,51.7012,-1.25188,44.0081,0.701426
-7.00625,49.4162,-1.53959,44.2785,2.98225
-1.3,40.535,-1.52761,44.0914,10.5564
-0.157031,40.7463,-1.45909,43.9241,1.16233
0.3125,40.49,-1.37051,43.7524,0.534905
-0.3125,40.5,-1.31761,43.5898,0.62508
-0.769531,37.35,-1.2902,43.2778,3.18298
-1.98047,41.02,-1.32472,43.1649,3.86462
-3.29766,45.94,-1.42336,43.3037,5.09327
-2.66953,44.2713,-1.48567,43.352,1.78305
-3.975,46.5938,-1.61014,43.5141,2.66425
-1.72734,43.6937,-1.616,43.5231,3.66906
-0.321875,45.115,-1.55129,43.6027,1.99883
-2.93516,49.2962,-1.62048,43.8874,4.93073
-3.01484,49.785,-1.6902,44.1823,0.495204
-5.8,52.3187,-1.89569,44.5891,3.76523
-3.59375,50.5,-1.9806,44.8846,2.85926
-4.05,47.6488,-2.08407,45.0228,2.88752
-4.96172,46.4688,-2.22795,45.0951,1.49118
-2.54297,39.7088,-2.2437,44.8258,7.17969
-1.03125,37.9613,-2.18308,44.4826,2.31064
-4.08516,44.48,-2.27818,44.4825,7.19864
-3.88438,39.375,-2.35849,44.2271,5.10895
-5.41484,43.84,-2.51131,44.2077,4.72002
-4.79375,39.34,-2.62543,43.9643,4.54266
-2.825,35.1813,-2.63541,43.5252,4.60121
-1.93359,35.2938,-2.60032,43.1136,0.898477
-2.9,36.1,-2.6153,42.7629,1.25856
-1.07812,35.9538,-2.53844,42.4225,1.82774
-0.185156,40,-2.42078,42.3013,4.14361
-0.183594,38.4938,-2.30892,42.111,1.50625
-0.359375,36.975,-2.21144,41.8542,1.52889
-1.76562,42.28,-2.18915,41.8755,5.48822
-1.78125,42.3,-2.16876,41.8967,0.0253803
2,40.9113,-1.96032,41.8474,4.02821
4.09375,38.14,-1.65761,41.6621,3.47327
2.61016,38.76,-1.44423,41.5169,1.60793
0,41.5812,-1.37201,41.5202,3.84348
0.957031,37.1987,-1.25556,41.3041,4.48578
-0.988281,39.6763,-1.2422,41.2227,3.14996
-0.871094,40.2837,-1.22364,41.1758,0.618698
-4.09062,42.2137,-1.36699,41.2277,3.7537
-4.43828,45.67,-1.52056,41.4498,3.47369
-4.7625,49.3,-1.68265,41.8423,3.64445
-3.63672,46.3787,-1.78036,42.0691,3.13067
-1.5125,37.7513,-1.76696,41.8532,8.88516
-3.125,34.36,-1.83487,41.4786,3.75509
-3.05,37.6637,-1.89562,41.2878,3.3046
-5.25234,40.3438,-2.06346,41.2406,3.46882
-5.04141,38.65,-2.21236,41.1111,1.70683
-3.65625,35.31,-2.28455,40.821,3.61583
-3.82266,41.25,-2.36146,40.8425,5.94233
-3.01484,36.16,-2.39413,40.6083,5.1537
-5.625,41.0013,-2.55567,40.628,5.50006
-5.50547,40.3387,-2.70316,40.6135,0.673199
-3.23438,35.7588,-2.72972,40.3708,5.11217
-4.58984,38.005,-2.82273,40.2525,2.62353
-3.88828,38.02,-2.876,40.1409,0.701723
-4.6125,41.6562,-2.96283,40.2166,3.70767
-6.125,44.44,-3.12094,40.4278,3.16811
-3.99297,44.795,-3.16454,40.6462,2.16138
-7.29609,51.0438,-3.37112,41.166,7.06807
-8.02188,56.06,-3.60366,41.9107,5.06848
-8.86875,53.65,-3.86691,42.4977,2.55447
-10.0008,53.1,-4.1736,43.0278,1.25857
-3.16172,41.695,-4.12301,42.9612,13.2984
-1.9875,40.8288,-4.01623,42.8546,1.45917
-1.35703,36.5062,-3.88327,42.5371,4.36824
-0.714844,36.1937,-3.72485,42.22,0.714186
-1.26562,34.12,-3.60189,41.815,2.14565
0.5375,31.415,-3.39492,41.295,3.25089
0.675781,28.34,-3.19139,40.6472,3.07811
-1.1125,30.01,-3.08744,40.1154,2.4468
-0.55,28.345,-2.96057,39.5269,1.75745
-1.1125,35.1312,-2.86817,39.3071,6.80952
0,33.9338,-2.72476,39.0384,1.63452
-2.44922,38.5687,-2.71098,39.0149,5.24232
-4.78828,43.05,-2.81485,39.2167,5.05498
-4.79375,42.54,-2.91379,39.3828,0.510028
-3.59297,39.395,-2.94775,39.3834,3.36644
-3.25078,38.79,-2.9629,39.3538,0.695066
-1.71875,40.57,-2.90069,39.4146,2.34851
-1.0125,37.4012,-2.80628,39.3139,3.2465
0,31.6987,-2.66597,38.9332,5.79169
-1.14297,33.1287,-2.58982,38.6429,1.83065
-2.275,34.2762,-2.57408,38.4246,1.61191
-1.9875,36.46,-2.54475,38.3264,2.20259
-2.675,39.1263,-2.55126,38.3664,2.75346
-2.72266,38.29,-2.55983,38.3625,0.837607
-4.64062,37.9437,-2.66387,38.3416,1.94897
-2.96953,33.84,-2.67915,38.1165,4.43095
-2.53125,34.2513,-2.67176,37.9233,0.601014
-3.61562,38.425,-2.71895,37.9483,4.31231
-1.1125,36.2313,-2.63863,37.8625,3.32839
-1.93984,35.6,-2.60369,37.7494,1.04066
-2.14453,29.47,-2.58073,37.3354,6.13342
-1.18828,20.2563,-2.51111,36.4814,9.26324
-1.14609,27.7938,-2.44286,36.0471,7.53762
-2.40391,27.4,-2.44091,35.6147,1.318
-2.125,31.9,-2.42512,35.429,4.50864
-1.69609,29,-2.38866,35.1075,2.93155
-1.27266,30.48,-2.33286,34.8761,1.53938
-1.15,30.0688,-2.27372,34.6358,0.429151
-2.14453,33.6463,-2.26726,34.5863,3.71317
-3.14453,33.0312,-2.31113,34.5085,1.17398
-1.125,30.565,-2.25182,34.3114,3.18762
-0.5625,27.7987,-2.16735,33.9857,2.82286
-1.20234,35.8138,-2.1191,34.0771,8.0405
-2.125,36.5,-2.1194,34.1983,1.14988
-1.75703,35.1312,-2.10128,34.2449,1.41735
-1.5375,36.4188,-2.07309,34.3536,1.30608
-3.26172,39.515,-2.13252,34.6117,3.54396
-5.00078,40.7762,-2.27593,34.9199,2.14828
-1.77188,31.075,-2.25073,34.7277,10.2245
-2.625,30.565,-2.26945,34.5195,0.993943
-2.07422,39.7588,-2.25968,34.7815,9.21023
-0.8625,40.47,-2.18982,35.0659,1.40504
-0.155469,41.455,-2.08811,35.3854,1.21248
-1.9125,41.8288,-2.07933,35.7075,1.79634
-1.37109,41.2438,-2.04391,35.9844,0.797085
0,41.1813,-1.94172,36.2442,1.37252
-1.67578,43.5812,-1.92842,36.611,2.92715
-2.69609,44.7738,-1.96681,37.0192,1.56943
-2.8125,43.3312,-2.00909,37.3348,1.44719
-1.9125,44.2287,-2.00426,37.6795,1.27102
-0.309375,40.495,-1.91952,37.8203,4.06336
-20.8438,72.0813,-2.86573,39.5333,37.6743
-21.4438,73.0413,-3.79463,41.2087,1.13208
-22.507,72.8313,-4.73025,42.7898,1.08382
-11.6617,56.9,-5.07682,43.4953,19.2724
-6.25234,40.2537,-5.1356,43.3333,17.5031
-2.92891,38.56,-5.02526,43.0946,3.73015
-1.91016,37.15,-4.86951,42.7974,1.73953
-2.68125,32.2,-4.7601,42.2675,5.0097
-5.34766,41.3563,-4.78947,42.2219,9.53659
-3.4875,41.53,-4.72438,42.1873,1.86825
-4.02891,46.8512,-4.6896,42.4205,5.34872
-2.40234,38.0137,-4.57524,42.2002,8.98594
-0.625,40.505,-4.37773,42.1154,3.06028
-0.5875,33.2188,-4.18822,41.6706,7.28635
-0.5875,30.395,-4.00818,41.1068,2.82375
-1.575,23.8438,-3.88652,40.2437,6.62526
-1.6125,26.4287,-3.77282,39.5529,2.58527
-2.125,24.53,-3.69043,38.8018,1.9667
-2.41875,21.6362,-3.62684,37.9435,2.90862
-2.27109,19.045,-3.55906,36.9986,2.59545
-3.22266,42.4613,-3.54224,37.2717,23.4356
-2.92891,38.56,-3.51157,37.3361,3.91229
-3.0375,39.2912,-3.48787,37.4339,0.739266
-2.44922,39.2988,-3.43593,37.5271,0.588329
-4.28672,46.675,-3.47847,37.9845,7.60167
-2.84375,43.9313,-3.44674,38.2819,3.10005
-3.26172,41.6188,-3.43749,38.4487,2.34997
-3.82891,43.8462,-3.45706,38.7186,2.29857
-4.30547,41.455,-3.49948,38.8554,2.43827
-3.85,44.185,-3.517,39.1219,2.76773
-3.82891,40.97,-3.5326,39.2143,3.21507
-4.25,41.7062,-3.56847,39.3389,0.848163
-3.03672,41.6188,-3.54188,39.4529,1.21643
-3.14453,44.45,-3.52201,39.7027,2.8333
-3.96484,41.96,-3.54416,39.8156,2.62164
-3.85,43.1037,-3.55945,39.98,1.1495
-4.25,42.85,-3.59398,40.1235,0.473697
-2.96484,38.7938,-3.56252,40.057,4.25497
-3.22266,39.7612,-3.54553,40.0422,1.00126
-2.96484,39.7637,-3.51649,40.0283,0.257825
-3.87422,40,-3.53438,40.0269,0.939563
-2.56797,40.7088,-3.48606,40.061,1.48614
-3.37891,40.7313,-3.4807,40.0945,0.811249
-4.28672,40.7687,-3.521,40.1282,0.908587
-5.5,42.8187,-3.61995,40.2627,2.38213
-3.14453,41.6712,-3.59618,40.3332,2.62011
-2.83828,41.1813,-3.55828,40.3756,0.57783
-2.6875,42.275,-3.51475,40.4705,1.10409
-3.14453,40.7313,-3.49623,40.4836,1.60998
-4.46016,41.7412,-3.54443,40.5465,1.6586
-5.17422,44.2287,-3.62592,40.7306,2.58796
-5.28984,46.305,-3.70912,41.0093,2.07947
-2.575,27.2763,-3.65241,40.3226,19.2214
2.32578,37.4688,-3.3535,40.1799,11.3095
3.91875,37.86,-2.98989,40.0639,1.64031
0.9,35.41,-2.79539,39.8312,3.88785
5.90625,37.9412,-2.36031,39.7368,5.60979
2.675,38.99,-2.10855,39.6994,3.39718
0.65625,40.7612,-1.97031,39.7525,2.68564
-0.99375,44.2713,-1.92148,39.9784,3.87848
-0.928125,40,-1.87181,39.9795,4.27176
-3.80859,42.8737,-1.96865,40.1242,4.06885
-3.3125,45.3,-2.03584,40.383,2.47645
-0.984375,42.08,-1.98327,40.4679,3.97348
1.02188,41.545,-1.83301,40.5217,2.07636
-1.45,45.995,-1.81386,40.7954,5.09045
-0.578906,46.78,-1.75211,41.0946,1.17262
8.38125,46.8713,-1.24545,41.3835,8.96062
-10.1719,48.2687,-1.69177,41.7277,18.6057
-9.32422,46.3,-2.07339,41.9563,2.14348
-39.6039,95.36,-2.824,43.0244,57.6519
-6.93984,64.48,-3.02979,44.0972,44.9501
-2.15859,57.9437,-2.98623,44.7895,8.09833
-5.03125,64.0512,-3.08848,45.7526,6.74935
2.81328,48.26,-2.79339,45.878,17.6324
-9.07266,49.3162,-3.10736,46.0499,11.9328
-10.1445,51.5062,-3.45922,46.3227,2.43824
5.22891,43.5337,-3.02481,46.1833,17.3177
2.4,43.7537,-2.75357,46.0618,2.83745
-2.85547,45.3,-2.75866,46.0237,5.47822
2.975,44.8213,-2.47198,45.9636,5.85009
-1.67188,44.16,-2.43198,45.8734,4.69369
-2.55,43.12,-2.43788,45.7357,1.36114
-1.57812,43.2337,-2.39489,45.6106,0.978509
-3.98125,44.3563,-2.47421,45.5479,2.65236
-2.48359,41,-2.47468,45.3205,3.67524
-1.75703,39.05,-2.43879,45.007,2.08096
-3.4875,40.52,-2.49123,44.7826,2.27056
-2.16797,40,-2.47507,44.5435,1.4183
-1.55547,40.2388,-2.42909,44.3283,0.657387
-2.14453,40,-2.41486,44.1118,0.635607
-2.325,40,-2.41037,43.9063,0.180469
-2.00078,42.2612,-2.38989,43.824,2.28437
-4.62578,41.8812,-2.50168,43.7269,2.65236
-4.14375,41.9512,-2.58379,43.6381,0.487087
3.78125,40.55,-2.26553,43.4837,8.04793
2.46797,41.9512,-2.02886,43.4071,1.92047
-0.775,43.6,-1.96617,43.4167,3.63802
-2.89453,44.6312,-2.01258,43.4774,2.35709
-3.275,45.85,-2.0757,43.5961,1.27676
-16.9039,54.8462,-2.81711,44.1586,16.3303
-3.01328,39.44,-2.82692,43.9226,20.7437
3.5,44.0788,-2.51058,43.9304,7.9963
-3.71875,40.64,-2.57099,43.7659,7.99596
-2.01953,41.8,-2.54341,43.6676,2.05741
-2.38672,41.5187,-2.53558,43.5602,0.462524
-4.7125,41.89,-2.64442,43.4767,2.35523
6.69375,45.85,-2.17752,43.5953,12.0741
-3.5,56.2562,-2.24364,44.2284,14.5672
-11.5586,43.925,-2.70939,44.2132,14.7309
-21.3461,60.88,-3.64122,45.0466,19.5772
-31.5352,80.7812,-5.03592,46.8333,22.3579
-2.70703,37.46,-4.98934,46.6458,52.0364
-1.95078,39.4,-4.83741,46.2835,2.08219
-0.855469,38.5687,-4.63832,45.8978,1.37502
-2.45,41.4562,-4.5289,45.6757,3.29851
-3.09375,39.4,-4.45714,45.3619,2.15466
-3.53125,40,-4.41085,45.0938,0.742566
-2.16328,37.05,-4.29847,44.6916,3.25174
-3.9875,39.0363,-4.28292,44.4089,2.69684
-2.58125,28.3263,-4.19784,43.6047,10.8019
-2.125,35.6862,-4.0942,43.2088,7.37413
0.796875,26.9538,-3.84964,42.3961,9.20836
0.424219,27.4562,-3.63595,41.6491,0.625602
1.925,28.84,-3.3579,41.0086,2.04135
0.924219,32.5213,-3.1438,40.5843,3.81486
-1.69609,34.7238,-3.07141,40.2912,3.42302
-3.69688,39.475,-3.10268,40.2504,5.15533
-1.98047,36.7,-3.04657,40.0729,3.26292
-8.61328,39.7012,-3.32491,40.0543,7.28023
-4.45,45.98,-3.38116,40.3506,7.53363
-2.45,43.465,-3.3346,40.5063,3.21329
-3.01484,48.2537,-3.31862,40.8937,4.82195
3,44.3988,-3.00269,41.0689,7.14418
3.25,46.105,-2.69005,41.3207,1.72447
0.621094,48.19,-2.52449,41.6642,3.35535
-8.54297,54.4,-2.82542,42.301,11.07
-6.88359,56.605,-3.02833,43.0162,2.75963
-5.82266,53.5563,-3.16804,43.5432,3.22807
-5.775,54.145,-3.29839,44.0733,0.590675
-9.45,53.8138,-3.60597,44.5603,3.6899
-18.5,62.0687,-4.35067,45.4357,12.2494
-10.5273,43.16,-4.65951,45.322,20.5208
-4.68125,37.1763,-4.66059,44.9147,8.36553
10.6117,41.4813,-3.89698,44.743,15.8874
-7.65,51.9437,-4.08463,45.103,21.0465
-19.9875,71.1062,-4.87977,46.4032,22.7907
-5.55625,45.94,-4.9136,46.38,29.0104
-4.29688,39.315,-4.88276,46.0268,6.74364
-3.69609,41.965,-4.82343,45.8237,2.71725
-3.025,40.9562,-4.73351,45.5803,1.21159
-1.79297,40.655,-4.58648,45.3341,1.26833
-1.5375,41.25,-4.43403,45.1299,0.647527
-1.4875,39.6912,-4.2867,44.8579,1.55955
-2.36641,40.61,-4.19069,44.6455,1.27145
-2.31875,35.8,-4.09709,44.2032,4.81024
-3.9,35.695,-4.08724,43.7778,1.58473
0,36.2137,-3.88287,43.3996,3.93435
-1.3875,37.3112,-3.75811,43.0952,1.76909
-1.9125,34.1,-3.66583,42.6455,3.25388
4.25,35.6937,-3.27003,42.2979,6.36525
-1.1,30.4188,-3.16153,41.7039,7.5132
-1.75703,31.9,-3.09131,41.2137,1.62043
-1.5375,34.555,-3.01362,40.8808,2.66406
-1.98047,35.455,-2.96196,40.6095,1.00311
-1.08984,34.0938,-2.86835,40.2837,1.62672
-4.4625,39.2313,-2.94806,40.2311,6.14563
-1.975,36.71,-2.89941,40.055,3.5418
-2.92891,36.5,-2.90088,39.8773,0.976748
-2.77266,37.2363,-2.89447,39.7452,0.752649
-1.63125,35.96,-2.83131,39.556,1.7122
-2.15,36.465,-2.79725,39.4014,0.723967
-2.07422,36.6688,-2.76109,39.2648,0.217387
-3.00234,38.1538,-2.77316,39.2092,1.75118
-2.12188,38.1188,-2.74059,39.1547,0.881164
-3.64766,39.7163,-2.78595,39.1828,2.20908
-2.44922,37.3787,-2.76911,39.0926,2.62682
-8.42813,39.385,-3.05206,39.1072,6.30653
-7.77734,38.185,-3.28832,39.0611,1.3651
-7.7,30.175,-3.50891,38.6168,8.01038
-9.625,52.96,-3.81471,39.3339,22.8662
-8.1,50.01,-4.02898,39.8677,3.32086
-7.125,49.9,-4.18378,40.3694,0.981185
-3.75547,49.4087,-4.16236,40.8213,3.40515
-5.66953,48.55,-4.23772,41.2078,2.09788
-1.6875,44.3,-4.11021,41.3624,5.82401
-0.424219,25.375,-3.92591,40.563,18.9671
0.4875,32.095,-3.70524,40.1396,6.78157
-0.471094,41.96,-3.54353,40.2306,9.91146
-1.8,42.6538,-3.45636,40.3518,1.49909
-4.86797,46.0088,-3.52694,40.6346,4.54626
-2.23125,43.8063,-3.46215,40.7932,3.43559
-2.20391,46.18,-3.39924,41.0625,2.37391
1.44922,48.3013,-3.15682,41.4245,4.22434
-8.96484,53.8138,-3.44722,42.0439,11.7831
-21.9,64.6,-4.36986,43.1717,16.8422
-5.6875,40.3587,-4.43574,43.0311,29.163
-4.95,42.8,-4.46145,43.0195,2.55022
-5.17578,44.17,-4.49717,43.0771,1.38848
-6.14062,43.525,-4.57934,43.0995,1.16058
-6.18516,41.49,-4.65963,43.019,2.03549
-5.2875,42.98,-4.69103,43.017,1.73951
-2.49375,38.2313,-4.58116,42.7777,5.5096
-3.55,43.9738,-4.5296,42.8375,5.83883
-4.17109,43.2738,-4.51168,42.8594,0.93582
-5.3625,48.2163,-4.55422,43.1272,5.08407
-12.375,55.0062,-4.94526,43.7212,9.76111
-7.26562,47.245,-5.06128,43.8974,9.29208
-7.09141,47.6712,-5.16278,44.086,0.46048
-5.99609,44.025,-5.20445,44.083,3.80721
-5.7,42.0187,-5.22923,43.9798,2.02798
-7.38672,43.6787,-5.3371,43.9647,2.36656
-5.87891,40,-5.36419,43.7665,3.97576
-1.39688,43.675,-5.16583,43.7619,5.79605
-4.53125,43.75,-5.1341,43.7613,3.13527
-4.34922,43.775,-5.09485,43.762,0.18374
-1.40547,40,-4.91038,43.5739,4.7871
-4.8375,45.0062,-4.90674,43.6455,6.06971
-4,43.96,-4.8614,43.6612,1.34017
-4.82422,43.9,-4.85954,43.6732,0.8264
-2.96484,42.6,-4.76481,43.6195,2.26876
-6.98672,54.0288,-4.8759,44.14,12.1158
-12.5039,64.4062,-5.2573,45.1533,11.7529
-9.73828,57.55,-5.48135,45.7731,7.39303
-2.01953,42.6662,-5.30826,45.6178,16.7662
-1.875,44.13,-5.1366,45.5434,1.47087
-2.5375,41.5062,-5.00664,45.3415,2.7061
-2.1,41.16,-4.86131,45.1325,0.557938
-3.72422,46.215,-4.80446,45.1866,5.30953
-2.30547,45.995,-4.67951,45.227,1.43571
-2.51562,46.8438,-4.57131,45.3079,0.874382
-0.177344,43.745,-4.35161,45.2297,3.88199
-9.63125,57.8063,-4.6156,45.8585,16.9439
0.925781,41.695,-4.33853,45.6504,19.262
-2.00234,41.4938,-4.22172,45.4425,2.93503
-3.04141,40,-4.1627,45.1704,1.8196
-3.06797,41.815,-4.10797,45.0026,1.81519
0.800781,29.7188,-3.86253,44.2384,12.6999
0.163281,38.6688,-3.66124,43.96,8.97268
-0.6875,40.2788,-3.51255,43.7759,1.82097
-0.878906

View File

@ -0,0 +1,409 @@
480.691,137.965,480.691,137.965,0
465.75,142.071,479.197,138.376,15.4954
455.484,141.104,476.826,138.648,10.3111
464.556,145.236,475.599,139.307,9.96877
467.529,141.725,474.792,139.549,4.6006
467.096,141.44,474.022,139.738,0.518212
463.5,141.104,472.97,139.875,3.61179
467.096,142.7,472.383,140.157,3.93446
677.841,142.375,476.492,140.202,210.745
447.663,140.489,475.915,140.207,230.185
457.849,145.236,474.109,140.71,11.238
460.976,140.489,472.795,140.688,5.68455
458.301,144.855,471.346,141.105,5.12051
490.997,143.025,473.311,141.297,32.7473
452.087,137.65,471.189,140.932,39.2789
454.3,139.855,469.5,140.824,3.12365
455.177,144.61,468.068,141.203,4.83527
454.893,140.171,466.75,141.1,4.44785
452.234,139.54,465.298,140.944,2.73329
459.785,144.28,464.747,141.277,8.91594
456.816,141.725,463.954,141.322,3.91682
469.95,148.941,464.554,142.084,14.9855
459.785,144.28,464.077,142.304,11.1826
446.473,143.654,462.316,142.439,13.3272
456.225,141.426,461.707,142.337,10.0035
459.785,140.485,461.515,142.152,3.68248
453.415,140.16,460.705,141.953,6.37859
466.651,146.195,461.3,142.377,14.5469
462.466,143.654,461.416,142.505,4.89562
461.412,137.016,461.416,141.956,6.72077
464.405,141.44,461.715,141.904,5.34154
463.657,141.749,461.909,141.889,0.809596
457.406,134.456,461.459,141.146,9.60484
498.682,132.869,465.181,140.318,41.3063
487.881,131.406,467.451,139.427,10.8993
477.574,136.38,468.463,139.122,11.4444
485.55,97.2012,470.172,134.93,39.9823
474.547,100.734,470.61,131.51,11.5563
439.425,187.701,469.986,132.634,93.7917
482.357,111.029,470.233,132.202,87.874
470.694,114.62,470.279,130.444,12.2036
463.034,113.351,469.555,128.735,7.76452
450.415,129.92,467.641,128.853,20.8268
458.316,114.88,466.708,127.456,16.9889
418.765,164.4,465.749,128.195,63.3758
418.765,167.256,461.051,132.101,2.85626
412.365,169.216,456.182,135.812,6.69339
436.969,133.041,454.261,135.535,43.7491
424.785,150.625,451.313,137.044,21.3923
452.257,131.74,451.408,136.514,33.3369
448.181,127.881,451.085,135.651,5.61266
446.912,120.616,450.668,134.147,7.37509
435.53,134.15,449.154,134.147,17.6832
426.065,154.881,446.845,136.221,22.79
457.718,159.486,447.932,138.547,31.9863
480.601,169.195,451.199,141.612,24.8573
413.085,167.205,450.437,142.124,67.5449
402.634,181.36,445.657,146.048,17.595
397.055,184.55,440.797,149.898,6.42652
393.525,190.06,436.069,153.914,6.54403
389.212,191.875,431.384,157.71,4.67888
465.125,190.625,432.059,158.368,75.9228
442.84,204.656,433.137,162.997,26.3345
366.163,209.92,431.797,163.936,76.857
315.073,207.434,429.463,164.806,51.1511
307.284,221.74,417.245,170.499,16.2892
291.457,248.32,404.666,178.281,30.935
275.878,255.689,391.787,186.022,17.2337
292.47,231.18,381.855,190.538,29.5965
280,226.739,371.67,194.158,13.2368
239.663,275.756,369.03,195.79,63.4809
104.235,486.214,363.734,201.598,250.266
268.6,207.944,361.831,201.725,323.187
266.663,214.281,352.314,202.981,6.62705
252.515,214.856,342.334,204.168,14.1593
242.263,209.969,332.327,204.748,11.357
223.975,202.976,321.492,204.571,19.5795
294.612,197.481,320.954,204.429,70.8501
266.409,187.964,315.5,202.783,29.765
234,177.115,307.35,200.216,34.1769
218.875,177.69,298.502,197.963,15.1359
227.777,172.356,291.43,195.403,10.3779
228.668,173.331,285.154,193.196,1.32055
235.696,148.03,280.208,188.679,26.2592
233.713,161.44,275.558,185.955,13.5558
196.341,217.719,273.974,186.59,67.5575
201.934,204.531,266.77,188.384,14.3245
192.488,207.469,259.342,190.293,9.8923
188.773,176.744,252.285,188.938,30.9488
206.155,194.08,247.672,189.452,24.5501
224.29,182.57,245.334,188.764,21.4787
239.113,144.65,244.712,184.353,40.7141
263.938,136.22,246.634,179.539,26.2173
259.791,150.2,247.95,176.605,14.5818
261.013,155.83,249.256,174.528,5.76091
266.61,133.72,250.992,170.447,22.8076
263.425,165,252.235,169.902,31.4418
237.025,152.666,250.714,168.179,29.139
223.098,134.484,247.952,164.809,22.9036
217.932,166,244.95,164.928,31.9368
214.282,181.68,241.883,166.603,16.0992
244.243,189.8,242.119,168.923,31.0418
261.013,184.18,244.009,170.449,17.6862
240.587,204.936,243.667,173.898,29.121
260.578,203.2,245.358,176.828,20.0667
234.853,202.435,244.307,179.389,25.7364
212.056,198.71,241.082,181.321,23.0992
240.909,200.65,241.065,183.254,28.9175
249.03,190.671,241.861,183.995,12.8662
256.719,186.52,243.347,184.248,8.73742
225.288,217.375,241.541,187.561,44.0449
249.581,182.076,242.345,187.012,42.8508
224.859,206.8,240.597,188.991,34.9633
224.846,191.42,239.022,189.234,15.38
241.931,165.341,239.312,186.845,31.177
247.816,157.244,240.163,183.884,10.0102
219.552,194.481,238.102,184.944,46.7492
219.193,194.406,236.211,185.89,0.367117
243.262,155.061,236.916,182.807,46.1234
236.409,159.094,236.865,180.436,7.9515
236.955,159.04,236.874,178.296,0.548736
235.862,160.381,236.773,176.505,1.73069
231.621,163.911,236.258,175.246,5.51759
234.295,161.26,236.062,173.847,3.76516
233.655,163.911,235.821,172.853,2.72719
240.426,162.075,236.281,171.776,7.01491
238.213,165.615,236.475,171.16,4.17454
236.538,169.896,236.481,171.033,4.59754
233.363,172.87,236.169,171.217,4.35015
210.176,209.58,233.57,175.053,43.4195
210.4,208.36,231.253,178.384,1.24043
240.825,167.111,231.444,178.158,51.2556
230.523,177.414,231.352,178.084,14.5698
235.77,175.2,231.794,177.796,5.69477
233.812,180.846,231.996,178.101,5.9758
228.39,184.576,231.635,178.748,6.58164
227.5,189.295,231.222,179.803,4.80192
229.125,189.52,231.012,180.775,1.6405
230.306,188.4,230.941,181.537,1.62781
203.702,224.861,228.217,185.87,45.1353
183.181,262.01,223.714,193.484,42.4399
188.025,254.891,220.145,199.624,8.61038
221.295,203.2,220.168,199.696,61.4723
206.787,219.681,218.83,201.694,21.957
196.219,244.076,216.569,205.933,26.5857
236.002,183.19,216.957,205.478,72.7315
241.875,180.065,219.449,202.936,6.65234
250.155,168.27,222.52,199.47,14.4114
249.113,169.03,225.179,196.426,1.29049
252.362,163.97,227.897,193.18,6.0134
249.785,163.48,230.086,190.21,2.62275
249.6,168.389,232.037,188.028,4.91224
245.36,169.785,233.37,186.204,4.46384
245.36,170.174,234.569,184.601,0.388748
245.438,169.159,235.656,183.057,1.01794
132.3,343.559,233.589,186.267,207.883
190.094,255.666,232.719,187.655,105.191
186.637,255.93,228.111,194.482,3.4663
181.453,259.675,223.445,201.001,6.39552
241.035,171.404,223.797,200.409,106.498
240.469,173.11,225.464,197.68,1.79781
247.099,166.116,227.627,194.523,9.63719
245.993,165.93,229.464,191.664,1.12182
249.785,161.125,231.496,188.61,6.12117
250.331,160.251,233.38,185.774,1.03037
242.809,168.891,234.322,184.086,11.456
242.544,172.31,235.145,182.908,3.42899
237.262,176.111,235.356,182.229,6.50701
241.855,167.5,236.006,180.756,9.75956
186.3,254.819,235.012,182.237,103.494
185.962,255.28,230.107,189.541,0.571539
184.934,256.05,225.59,196.192,1.28511
186.993,256.431,221.73,202.216,2.09437
190.781,252.4,218.635,207.234,5.53191
213.832,213.6,218.155,207.871,45.1307
224.159,202.14,218.755,207.298,15.4263
220.681,203.416,218.948,206.91,3.70416
163.127,297.156,217.831,208.715,109.998
219.844,200.681,217.872,208.554,111.911
204,235.075,216.485,211.206,37.8676
178.574,269.901,212.694,217.076,43.12
179.215,272.936,209.346,222.662,3.10188
178.819,273.32,206.293,227.727,0.551503
181.025,268.01,203.766,231.756,5.75009
184.837,268,201.873,235.38,3.81251
184.13,268.76,200.099,238.718,1.03803
181.287,272.936,198.218,242.14,5.05251
226.906,203.416,198.792,241.365,83.1515
229.521,197.566,201.865,236.986,6.40779
232.045,200.429,204.882,233.33,3.81597
228.741,201.624,207.268,230.159,3.51263
227.178,195.44,209.259,226.687,6.37829
234.9,188.574,211.823,222.876,10.3331
174.684,286.826,211.081,224.155,115.237
135.278,350.62,209.565,226.684,74.9829
108.122,391.48,199.42,243.164,49.0612
109.16,390.745,190.394,257.922,1.27212
166.175,308.234,189.91,258.928,100.294
236.393,190.671,190.84,257.563,136.936
238.029,191.225,195.559,250.929,1.72711
193.55,255.35,195.518,251.018,78.0409
135.598,357.72,194.32,253.152,117.635
203.909,234.171,194.512,252.772,141.176
225.544,198.636,197.615,247.359,41.6031
229.716,189.725,200.825,241.595,9.83978
236.25,191.031,204.368,236.539,6.6629
231.927,191.76,207.124,232.061,4.38366
231.194,190.671,209.531,227.922,1.31282
233.716,192.375,211.949,224.367,3.04345
226.145,197.309,213.369,221.661,9.03677
220.281,206.98,214.06,220.193,11.3098
211.301,233.119,213.784,221.486,27.6384
227.443,193.591,215.15,218.696,42.6965
234.675,158.811,217.102,212.708,35.5239
224.538,165.12,217.846,207.949,11.9402
216.056,164.211,217.667,203.575,8.52981
213.775,165.116,217.278,199.729,2.45421
200.8,169.244,215.63,196.681,13.6157
200.226,172.48,214.09,194.261,3.2868
194.337,163.25,212.114,191.16,10.9487
186.532,167.455,209.556,188.789,8.86539
178.37,167.075,206.437,186.618,8.17133
175.503,159.34,203.344,183.89,8.24903
163.078,165.955,199.317,182.096,14.0762
152.191,171.794,194.605,181.066,12.3536
148.141,167.14,189.958,179.674,6.16978
141.334,169.165,185.096,178.623,7.1011
132.281,173.831,179.814,178.144,10.1849
128.381,173.646,174.671,177.694,3.90438
114.04,171.181,168.608,177.043,14.5517
93.9781,168.155,161.145,176.154,20.2887
88.9938,169.236,153.93,175.462,5.1003
77.6156,162.859,146.299,174.202,13.0436
57.8312,168.756,137.452,173.657,20.6447
62.332,168.975,129.94,173.189,4.50609
54.9,162.535,122.436,172.124,9.83406
53.2656,158.429,115.519,170.754,4.41955
38.8477,166.524,107.852,170.331,16.535
30.9742,157.45,100.164,169.043,12.0135
15.9633,161.22,91.7439,168.261,15.4771
10.6531,159.639,83.6348,167.398,5.54059
0.753906,156.494,75.3467,166.308,10.3868
-13.6969,166.069,66.4423,166.284,17.3351
-17.3758,162.92,58.0605,165.948,4.84242
-19.825,162.65,50.272,165.618,2.46406
-43.3289,168.52,40.9119,165.908,24.2258
-49.2938,157.3,31.8913,165.047,12.707
-50.407,149.98,23.6615,163.541,7.40418
-69.7188,158.09,14.3235,162.996,20.9455
-67.793,151.78,6.11181,161.874,6.59733
-79.9969,156.019,-2.49906,161.288,12.9191
-88.0875,159.04,-11.0579,161.064,8.63633
-97.1352,156.61,-19.6656,160.618,9.36829
-106.313,159.156,-28.3304,160.472,9.52477
-122.288,170.556,-37.7262,161.48,19.6255
-121.709,152.519,-46.1245,160.584,18.0468
-126.588,148.439,-54.1708,159.37,6.35945
-224.4,283.54,-57.5754,161.853,166.792
-247.754,293.711,-76.5932,175.039,25.4727
-151.598,135.996,-78.0933,174.258,184.716
-200.996,204.274,-80.5514,174.858,84.2735
-162.041,142.291,-82.1812,174.207,73.2072
-173.145,147.73,-91.2775,171.559,12.3636
-188.895,153.1,-101.039,169.713,16.6403
-200.58,150.719,-110.993,167.814,11.9261
-209.309,156.805,-120.825,166.713,10.6406
-202.546,131.424,-128.997,163.184,26.2667
-206.41,125.856,-136.738,159.451,6.77702
-209.946,123.394,-144.059,155.846,4.30891
-214.062,129.606,-151.059,153.222,7.45251
-220.19,139.044,-157.973,151.804,11.2521
-224.66,145.656,-164.641,151.189,7.98178
-229.943,130.639,-171.171,149.134,15.9196
-231.562,118.859,-177.211,146.107,11.8908
-235.891,103.704,-183.079,141.866,15.7609
-241.96,108.75,-188.967,138.555,7.89328
-244.512,99.375,-194.521,134.637,9.71602
-250.038,108.86,-200.073,132.059,10.9772
-251.96,99.66,-205.262,128.819,9.39875
-328.141,209.32,-207.719,130.429,133.525
-266.165,89.4837,-208.888,129.61,134.914
-358.148,225.436,-211.873,131.527,164.146
-252.968,52.56,-212.695,129.947,202.358
-260.475,51.0863,-217.473,122.061,7.65033
-262.793,38.4087,-222.005,113.696,12.8877
-261.249,28.8787,-225.93,105.214,9.65423
-256.15,14.72,-228.952,96.1648,15.049
-249.938,2.32,-231.05,86.7804,13.8692
-257.4,8.45,-233.685,78.9473,9.65742
-261.176,6.74125,-236.434,71.7267,4.14444
-260.762,-1.145,-238.867,64.4395,7.89711
-249.775,-30.7062,-239.958,54.9249,31.5369
-258.181,-29.63,-241.78,46.4695,8.47487
-261.057,-36.44,-243.708,38.1785,7.39231
-270.69,-22.5462,-246.406,32.106,16.9064
-270.344,-29.0688,-248.8,25.9885,6.53168
-253.116,-61.44,-249.231,17.2457,36.6702
-247.113,-74.8838,-249.02,8.03274,14.7229
-252.928,-75.7962,-249.41,-0.350158,5.88601
-256.554,-72,-250.125,-7.51514,5.24954
-260.537,-80.2812,-251.166,-14.7918,9.18923
-252.541,-96.955,-251.303,-23.0081,18.4919
-242.315,-133.446,-250.405,-34.0519,37.8969
-251.343,-124.671,-250.498,-43.1138,12.59
-250.609,-119.5,-250.51,-50.7525,5.22302
-249.55,-125.62,-250.414,-58.2392,6.21101
-245.616,-135.175,-249.934,-65.9328,10.3333
-235.362,-139.265,-248.477,-73.266,11.0395
-237.25,-149.9,-247.354,-80.9294,10.8013
-240.844,-144.15,-246.703,-87.2515,6.78067
-249.938,-126.14,-247.026,-91.1403,20.1756
-247.145,-126.14,-247.038,-94.6403,2.79297
-246.947,-137.461,-247.029,-98.9224,11.323
-249.965,-142.115,-247.323,-103.242,5.54668
-243.448,-149.359,-246.935,-107.853,9.744
-235.362,-156.54,-245.778,-112.722,10.8145
-229.113,-167.144,-244.111,-118.164,12.3078
-227.297,-169.22,-242.43,-123.27,2.75865
-241.062,-149.39,-242.293,-125.882,24.1396
-238.337,-152,-241.898,-128.494,3.77386
-240.975,-147.346,-241.805,-130.379,5.34957
-223.48,-174.88,-239.973,-134.829,32.6216
-223.847,-176.24,-238.36,-138.97,1.40849
-209.875,-194,-235.512,-144.473,22.5971
-210.104,-201.994,-232.971,-150.225,7.99702
-215.613,-205.094,-231.235,-155.712,6.32097
-220.2,-178.404,-230.132,-157.981,27.0814
-261.087,-130.56,-230.751,-157.433,62.9345
-249.694,-134.69,-232.645,-155.158,12.1185
-246.921,-137.375,-234.073,-153.38,3.85964
-191.35,-218.781,-233.218,-154.688,98.5653
-212.315,-171.106,-232.8,-155.017,52.081
-243.169,-120.25,-233.007,-154.321,59.4838
-235.527,-119.706,-233.259,-150.86,7.66073
-229.188,-131.811,-232.852,-148.955,13.6647
-217.884,-145.491,-231.355,-148.608,17.7455
-192.879,-177.26,-227.508,-151.474,40.4293
-175.409,-197.395,-222.298,-156.066,26.6576
-169.738,-203.074,-217.042,-160.767,8.02555
-167.552,-195.916,-212.093,-164.282,7.48363
-162.062,-191.865,-207.09,-167.04,6.82344
-154.465,-182.915,-201.827,-168.627,11.7395
-148.281,-185.099,-196.473,-170.275,6.55787
-136.125,-180.389,-190.438,-171.286,13.0368
-124.14,-180,-183.808,-172.157,11.9915
-118.523,-174.88,-177.28,-172.43,7.60047
-106.393,-182.025,-170.191,-173.389,14.0777
-95.8258,-194.304,-162.754,-175.481,16.1998
-91.8187,-194.07,-155.661,-177.34,4.01385
-83.8375,-202.73,-148.478,-179.879,11.7769
-78.5383,-212.2,-141.484,-183.111,10.8518
-68.5875,-181.76,-134.195,-182.976,32.0252
-59.8648,-183.2,-126.762,-182.998,8.84072
-41.8086,-201.536,-118.266,-184.852,25.7342
-29.2781,-194.135,-109.368,-185.78,14.5531
-18.4875,-196.749,-100.28,-186.877,11.1027
-8.14453,-197.274,-91.0661,-187.917,10.3563
-9.98438,-190.591,-82.9579,-188.184,6.93114
-1.66172,-190.785,-74.8283,-188.444,8.32491
4.45,-191.54,-66.9005,-188.754,6.15817
14.9555,-180.5,-58.7149,-187.928,15.2396
25.5875,-191.309,-50.2846,-188.266,15.1614
31.3945,-179.905,-42.1167,-187.43,12.7972
51.9,-194.84,-32.715,-188.171,25.3679
64.2586,-190.689,-23.0177,-188.423,13.0372
73.6695,-190.431,-13.3489,-188.624,9.41446
81.6539,-185.72,-3.84866,-188.333,9.27071
86.9,-185.62,5.22621,-188.062,5.24705
96.6602,-190.336,14.3696,-188.29,10.8399
106.301,-189.331,23.5627,-188.394,9.69287
117.7,-194.974,32.9765,-189.052,12.7193
0.6375,39.93,32.3297,-184.472,262.456
137.5,-192.05,34.4331,-184.624,269.344
150.875,-182.08,46.0773,-184.369,16.6821
158.641,-187.04,57.3336,-184.636,9.21447
160.322,-193.406,67.6324,-185.513,6.58451
167.988,-194.411,77.668,-186.403,7.73201
174.598,-194.986,87.361,-187.261,6.63434
183.7,-190.999,96.9949,-187.635,9.93744
191.121,-190.23,106.408,-187.895,7.46081
197.704,-188.375,115.537,-187.943,6.83918
207.645,-188.585,124.748,-188.007,9.94285
217.071,-190.25,133.98,-188.231,9.57247
221.875,-189.889,142.77,-188.397,4.81747
226.712,-189.52,151.164,-188.509,4.85075
232.465,-190.28,159.294,-188.686,5.80311
236.191,-183.48,166.984,-188.166,7.75418
236.109,-181.92,173.896,-187.541,1.56215
243.857,-176.431,180.892,-186.43,9.49487
244.043,-167.589,187.207,-184.546,8.84445
246.1,-162.556,193.097,-182.347,5.43668
247.725,-161.55,198.56,-180.267,1.91132
247.68,-156.814,203.472,-177.922,4.73646
255.071,-154.54,208.632,-175.584,7.73248
253.198,-140.836,213.088,-172.109,13.8312
260.284,-134.6,217.808,-168.358,9.43934
252.5,-119.075,221.277,-163.43,17.3669
271.079,-144.275,226.257,-161.514,31.3084
268.375,-127.366,230.469,-158.1,17.1236
266.838,-116.505,234.106,-153.94,10.9694
259.556,-116.914,236.651,-150.237,7.29351
250.609,-111.2,238.047,-146.334,10.6157
274.219,-103.63,241.664,-142.063,24.7933
277.438,-105.361,245.241,-138.393,3.6548
276.478,-97.6513,248.365,-134.319,7.76946
277.438,-94.0212,251.272,-130.289,3.75485
265.3,-91.07,252.675,-126.367,12.4919
275.271,-79.7,254.935,-121.701,15.1228
275.438,-70.88,256.985,-116.618

View File

@ -0,0 +1,613 @@
-6.70312,45.985,-6.70312,45.985,0
-1.90859,39.105,-6.46339,45.641,8.38582
-5.15078,38.15,-6.39776,45.2664,3.37991
-6.19922,47.4588,-6.38784,45.3761,9.36766
-11.4992,51.7188,-6.6434,45.6932,6.79981
-5.29922,49.6,-6.5762,45.8885,6.55203
-1.26875,43.5262,-6.31082,45.7704,7.28943
-4.1125,60.52,-6.20091,46.5079,17.2301
-2.78125,55.2163,-6.02992,46.9433,5.46822
-5.80937,54.58,-6.0189,47.3252,3.09425
2.10547,57.64,-5.61268,47.8409,8.48577
0,56.9637,-5.33204,48.297,2.21142
0.291406,56.2337,-5.05087,48.6939,0.786013
-5.625,59.205,-5.07958,49.2194,6.62061
-6.75,60.5187,-5.1631,49.7844,1.72957
-7.01172,59.435,-5.25553,50.2669,1.11485
-7.24609,59.7438,-5.35506,50.7408,0.387668
-6.9,58.375,-5.43231,51.1225,1.41188
-5.71875,50.4362,-5.44663,51.0882,8.0262
-3.50625,52.9412,-5.34961,51.1808,3.34218
-4.95,48.3363,-5.32963,51.0386,4.82592
-7.525,33.245,-5.4394,50.1489,15.3094
-6.62187,38.22,-5.49852,49.5525,5.05631
-6.15,41.3088,-5.5311,49.1403,3.12463
-6.30859,41.2938,-5.56997,48.748,0.159298
-6.075,41.72,-5.59522,48.3966,0.486016
-7.31797,42.595,-5.68136,48.1065,1.52007
-7.27266,43.8363,-5.76092,47.893,1.24213
-8.775,45.845,-5.91163,47.7906,2.50837
-8.39453,49.54,-6.03577,47.878,3.71454
-7.38672,48.635,-6.10332,47.9159,1.35452
-9.04922,50.075,-6.25062,48.0238,2.19943
-8.52734,50.64,-6.36445,48.1547,0.769144
-9.97734,51.2738,-6.5451,48.3106,1.58247
-10.7586,50.5638,-6.75577,48.4233,1.05568
-11.175,53.26,-6.97673,48.6651,2.72816
-7.34766,48.4813,-6.99528,48.6559,6.12246
-9.0625,51.5863,-7.09864,48.8024,3.54707
-13.2312,55.1613,-7.40527,49.1204,5.49169
-4.05234,39.325,-7.23762,48.6306,18.3041
0.560156,37.2438,-6.84773,48.0613,5.06029
-5.09766,44.76,-6.76023,47.8962,9.40766
-5.6875,44.795,-6.70659,47.7411,0.590877
-6.32109,44.865,-6.68732,47.5973,0.637446
-5.425,38.2438,-6.6242,47.1297,6.68156
-5.07812,37.5238,-6.5469,46.6494,0.799204
-2.54922,40.3288,-6.34701,46.3333,3.77669
-3.15,40.9938,-6.18716,46.0664,0.896194
-2.86562,40,-6.02109,45.763,1.03369
-3.175,39.32,-5.87878,45.4409,0.747072
-2.75625,36.55,-5.72266,44.9963,2.80147
-1.5375,34.6,-5.5134,44.4765,2.29953
-1.1625,33.15,-5.29585,43.9102,1.4977
1.62422,26.5212,-4.94985,43.0408,7.19074
-1.43828,31.5763,-4.77427,42.4675,5.91041
-1.01953,27.25,-4.58653,41.7066,4.34652
-1.98438,28.975,-4.45643,41.0701,1.9765
-1.2,50.17,-4.2936,41.5251,21.2095
-2.82188,49.075,-4.22002,41.9026,1.95691
-1.625,48.925,-4.09027,42.2537,1.20624
0.199219,44.76,-3.87579,42.379,4.54698
-5.46016,43.5612,-3.95501,42.4381,5.78495
-7.03125,42.78,-4.10882,42.4552,1.75459
-6.03047,34.08,-4.20491,42.0364,8.75737
-3.22734,27.9137,-4.15603,41.3303,6.77354
-0.917969,34.5387,-3.99412,40.9907,7.01597
0,31.68,-3.79442,40.5252,3.00247
-0.75625,28.88,-3.64251,39.9429,2.90033
1.32891,27.76,-3.39394,39.3338,2.36692
5.38125,31.0462,-2.95518,38.9194,5.21733
5.21016,32.005,-2.54691,38.5737,0.973946
6.64453,34.6087,-2.08734,38.3754,2.97265
7.08203,37.3787,-1.62887,38.3256,2.80434
9.73047,36.55,-1.0609,38.2368,2.77506
2.42734,39.1413,-0.886492,38.282,7.74923
5.54766,42.0037,-0.564785,38.4681,4.23435
5.91328,39.7088,-0.240881,38.5302,2.32384
-5.15625,40.9263,-0.48665,38.65,11.1363
-2.30859,35.1338,-0.577747,38.4742,6.45463
-2.19141,32.59,-0.65843,38.1799,2.5465
-1.48438,25.12,-0.699728,37.5269,7.50338
-0.909375,28.695,-0.71021,37.0854,3.62095
-2.23125,36.55,-0.786262,37.0586,7.96545
-2.72266,37.9963,-0.883082,37.1055,1.5275
-0.824219,36.2788,-0.880139,37.0641,2.56005
0,36.37,-0.836132,37.0294,0.829249
0.532031,35.2,-0.767724,36.938,1.28528
-0.499219,35.36,-0.754298,36.8591,1.04359
-1.98047,34.3,-0.815607,36.7311,1.82146
-1.69297,36.115,-0.859475,36.7003,1.83763
-0.761719,37.6488,-0.854587,36.7477,1.79437
-1.02266,36.6362,-0.862991,36.7422,1.04568
12.057,36.395,-0.216991,36.7248,13.0819
6.97734,35.32,0.142725,36.6546,5.19216
3.34375,34.65,0.302777,36.5543,3.69484
1.325,37.325,0.353888,36.5929,3.35126
-1.07734,41,0.282326,36.8132,4.39054
0.475781,20.0987,0.291999,35.9775,20.9589
2.33203,23.935,0.394001,35.3754,4.26179
2.78437,25.2738,0.513519,34.8703,1.41315
2.14297,25.97,0.594992,34.4253,0.946619
5.80078,21.875,0.855281,33.7978,5.49077
6.67734,18.9562,1.14638,33.0557,3.04758
7.89453,28.4,1.48379,32.8229,9.52192
3.64375,29.5012,1.59179,32.6568,4.3911
-0.144531,31.5912,1.50497,32.6035,4.32657
-2.51016,35.56,1.30422,32.7514,4.62034
0.414844,32.0563,1.25975,32.7166,4.56416
-0.978906,35.6862,1.14782,32.8651,3.88828
0,28.8787,1.09042,32.6658,6.87752
-1.90313,33.9338,0.940747,32.7292,5.40148
-1.75703,30.9662,0.805858,32.641,2.97119
-1.90313,31.2,0.670408,32.569,0.275696
-0.265625,32.1338,0.623607,32.5472,1.88505
0.652344,33.35,0.625044,32.5873,1.52375
1.91016,31.165,0.6893,32.5162,2.52117
1.67578,29.5187,0.738624,32.3664,1.6629
5.375,19.1637,0.970442,31.7062,10.9959
2.95625,23.9112,1.06973,31.3165,5.32814
-1.50391,33.4062,0.941051,31.421,10.4904
3.73828,26.0088,1.08091,31.1503,9.06654
5.33203,27.7488,1.29347,30.9803,2.35958
4.74141,29.925,1.46587,30.9275,2.25492
-1.97109,36.985,1.29402,31.2304,9.74173
-0.7875,29.8113,1.18994,31.1594,7.27069
-0.65625,29.6012,1.09763,31.0815,0.247727
-0.355469,28.615,1.02498,30.9582,1.03105
-0.355469,30.3388,0.955955,30.9272,1.7238
-1.97109,34.7438,0.809602,31.118,4.69194
-3.62109,37.8138,0.588068,31.4528,3.48531
-3.28125,37.27,0.394602,31.7437,0.641257
-1.90625,37.4813,0.279559,32.0306,1.39114
-1.79609,36.445,0.175777,32.2513,1.04214
-0.321094,33.3737,0.150933,32.3074,3.40712
0.875,31.1338,0.187136,32.2487,2.53925
-6.09375,42.45,-0.126908,32.7588,13.2898
-6.8875,43.2012,-0.464938,33.2809,1.09286
-2.71484,37.825,-0.577433,33.5081,6.80548
-2.39062,43.045,-0.668092,33.985,5.23006
-5.15312,47.2137,-0.892344,34.6464,5.00095
-3.6375,46.0312,-1.0296,35.2156,1.92234
-4.50859,45.4338,-1.20355,35.7266,1.05626
-6.67266,49.7562,-1.47701,36.428,4.83387
-18.4195,62.94,-2.32413,37.7536,17.6579
-5.15625,42.1263,-2.46574,37.9723,24.6804
-4.34688,34.5387,-2.55979,37.8006,7.63065
-7.06563,38.6,-2.78509,37.8406,4.8873
-5.29375,38.63,-2.91052,37.88,1.77213
-10.9375,42.0312,-3.31187,38.0876,6.58939
-6.4,23.6,-3.46628,37.3632,18.9815
-0.384375,40.615,-3.31218,37.5258,18.0471
1.49297,40.66,-3.07192,37.6825,1.87788
-4.43437,40.695,-3.14004,37.8331,5.92744
-4.36562,22.4,-3.20132,37.0615,18.2951
-2.66875,24.6763,-3.1747,36.4422,2.83917
-0.878906,32.38,-3.05991,36.2391,7.90889
-1.59609,33.9437,-2.98671,36.1243,1.72032
-1.23047,34.0387,-2.8989,36.0201,0.377761
0.832031,31.74,-2.71236,35.806,3.08835
2.33203,28.8,-2.46014,35.4557,3.30055
4.46875,27.9562,-2.11369,35.0808,2.2973
1.46875,27.4562,-1.93457,34.6995,3.04138
0.738281,29.455,-1.80093,34.4373,2.12809
0.61875,31.2812,-1.67994,34.2795,1.83011
-5.175,36.2137,-1.8547,34.3762,7.60901
-0.4875,29.395,-1.78634,34.1272,8.2745
-0.977344,31.165,-1.74589,33.979,1.83653
0.278906,30.16,-1.64465,33.7881,1.60879
0.6375,39.93,-1.53054,34.0952,9.77658
-0.90625,34.61,-1.49933,34.1209,5.53945
-3.84375,38.5,-1.61655,34.3399,4.87453
-1.63125,39.2912,-1.61728,34.5874,2.34971
-3.45,41.515,-1.70892,34.9338,2.87283
-4.725,36.5,-1.85972,35.0121,5.17454
-5.00547,40,-2.01701,35.2615,3.51122
-2.29766,40.7012,-2.03104,35.5335,2.79713
-5.98828,50.7,-2.2289,36.2918,10.6582
-5.41875,41.74,-2.3884,36.5642,8.97808
-4.05625,45.95,-2.47179,37.0335,4.42499
-5.54609,43.4238,-2.6255,37.353,2.9328
-7.3625,45.0812,-2.86235,37.7395,2.45893
0.177344,35.16,-2.71037,37.6105,12.4611
-16.9813,60.4712,-3.42392,38.7535,30.579
-2.825,40.8963,-3.39397,38.8607,24.1573
-3.22109,38.8,-3.38533,38.8576,2.13339
-4.2375,39.6862,-3.42793,38.899,1.3485
-3.57734,42.8237,-3.43541,39.0953,3.2062
-9.80391,51.5913,-3.75383,39.7201,10.7537
-6.26484,40,-3.87938,39.7341,12.1195
-1.56797,33.7,-3.76381,39.4324,7.85815
-5.65,39.35,-3.85812,39.4283,6.97033
-1.02188,32.8988,-3.71631,39.1018,7.93961
-2.18359,31.04,-3.63967,38.6987,2.19196
-4.7125,40.9562,-3.69331,38.8116,10.2336
-6.48125,44.9313,-3.83271,39.1176,4.35085
0,36.55,-3.64107,38.9892,10.5949
2.01953,36.7687,-3.35804,38.8782,2.03134
2.19375,37.1,-3.08045,38.7892,0.374315
-0.175781,37.05,-2.93522,38.7023,2.37006
-1.8125,39.39,-2.87909,38.7367,2.8556
-0.7375,35.8887,-2.77201,38.5943,3.66261
-2.69062,37.32,-2.76794,38.5306,2.42143
-1.37266,33.4212,-2.69817,38.2751,4.11554
-0.208594,42.2837,-2.57369,38.4755,8.93862
-1.82109,41.965,-2.53606,38.65,1.64369
-0.39375,40.3162,-2.42895,38.7333,2.18079
0.75,38.185,-2.27,38.7059,2.41871
0.3625,38.5312,-2.13838,38.6972,0.519625
0.178906,38.84,-2.02251,38.7043,0.359255
-0.174219,38.5687,-1.9301,38.6975,0.445311
-0.3375,38.0312,-1.85047,38.6642,0.561752
-2.7,39.7088,-1.89294,38.7164,2.89754
-2.20391,37.9263,-1.90849,38.6769,1.85025
-3.00938,40.575,-1.96354,38.7718,2.76846
-0.99375,38.89,-1.91505,38.7777,2.62716
-1.0875,39.7012,-1.87367,38.8239,0.816599
-1.95078,38.79,-1.87753,38.8222,1.2552
-2.3625,36.37,-1.90177,38.6996,2.45478
-0.925781,39.0812,-1.85297,38.7187,3.06835
-1.4375,38.4813,-1.8322,38.7068,0.788502
-1.07812,39.1037,-1.7945,38.7267,0.718703
-1.79688,39.6987,-1.79462,38.7753,0.933082
-4.5,42.8688,-1.92988,38.9799,4.1661
-3.075,43.15,-1.98714,39.1884,1.45248
-3.20078,42.8013,-2.04782,39.3691,0.370693
-1.62422,39.6987,-2.02664,39.3856,3.48018
-1.4,37.9087,-1.99531,39.3117,1.80399
-2.36641,40,-2.01387,39.3461,2.3038
-1.8125,41.4813,-2.0038,39.4529,1.58148
-2.625,41.5563,-2.03486,39.5581,0.815954
-2.325,42.2137,-2.04936,39.6908,0.722615
9.84297,39.6862,-1.45475,39.6906,12.4277
9.25703,39.375,-0.919158,39.6748,0.663454
8.38125,40.3262,-0.454138,39.7074,1.29297
7.70859,40.3312,-0.046001,39.7386,0.672679
9.90938,40,0.451768,39.7517,2.22557
8.50391,42.025,0.854375,39.8653,2.46495
10.7164,42.025,1.34748,39.9733,2.21249
0.988281,43.2588,1.32952,40.1376,9.80605
-0.186719,42.0387,1.25371,40.2326,1.69389
-1.05,41.9512,1.13852,40.3186,0.867704
-2.95,46.84,0.934094,40.6446,5.24503
4.05234,44.4813,1.09001,40.8365,7.38893
1.21875,46.9,1.09644,41.1396,3.7255
-12.75,59.5938,0.404121,42.0624,18.8748
-15.5867,63.8688,-0.39542,43.1527,5.13055
-9.45,52.1637,-0.848149,43.6032,13.2162
-8.92266,51.7012,-1.25188,44.0081,0.701424
-7.00625,49.4162,-1.53959,44.2785,2.98226
-1.3,40.535,-1.52761,44.0913,10.5564
-0.157031,40.7463,-1.45908,43.9241,1.16234
0.3125,40.49,-1.37051,43.7524,0.534928
-0.3125,40.5,-1.31761,43.5898,0.62508
-0.769531,37.35,-1.2902,43.2778,3.18298
-1.98047,41.02,-1.32472,43.1649,3.86462
-3.29766,45.94,-1.42336,43.3036,5.09327
-2.66953,44.2713,-1.48567,43.352,1.783
-3.975,46.5938,-1.61014,43.5141,2.66425
-1.72734,43.6937,-1.616,43.5231,3.66914
-0.321875,45.115,-1.55129,43.6027,1.99886
-2.93516,49.2962,-1.62048,43.8874,4.93069
-3.01484,49.785,-1.6902,44.1822,0.495252
-5.8,52.3187,-1.89569,44.5891,3.7652
-3.59375,50.5,-1.9806,44.8846,2.85923
-4.05,47.6488,-2.08407,45.0228,2.88747
-4.96172,46.4688,-2.22795,45.0951,1.49119
-2.54297,39.7088,-2.2437,44.8258,7.17969
-1.03125,37.9613,-2.18308,44.4826,2.31064
-4.08516,44.48,-2.27818,44.4825,7.1986
-3.88438,39.375,-2.35849,44.2271,5.10895
-5.41484,43.84,-2.51131,44.2077,4.72001
-4.79375,39.34,-2.62543,43.9643,4.54266
-2.825,35.1813,-2.63541,43.5252,4.60117
-1.93359,35.2938,-2.60032,43.1136,0.898481
-2.9,36.1,-2.6153,42.7629,1.25853
-1.07812,35.9538,-2.53844,42.4225,1.82774
-0.185156,40,-2.42078,42.3014,4.14356
-0.183594,38.4938,-2.30892,42.111,1.5062
-0.359375,36.975,-2.21144,41.8542,1.52894
-1.76562,42.28,-2.18915,41.8755,5.48822
-1.78125,42.3,-2.16876,41.8967,0.0253834
2,40.9113,-1.96032,41.8474,4.02819
4.09375,38.14,-1.65761,41.6621,3.47331
2.61016,38.76,-1.44423,41.517,1.60793
0,41.5812,-1.37201,41.5202,3.84345
0.957031,37.1987,-1.25556,41.3041,4.48578
-0.988281,39.6763,-1.2422,41.2227,3.15004
-0.871094,40.2837,-1.22364,41.1758,0.6186
-4.09062,42.2137,-1.36699,41.2277,3.7537
-4.43828,45.67,-1.52056,41.4498,3.47374
-4.7625,49.3,-1.68265,41.8423,3.64445
-3.63672,46.3787,-1.78036,42.0691,3.13071
-1.5125,37.7513,-1.76696,41.8532,8.88506
-3.125,34.36,-1.83487,41.4786,3.75514
-3.05,37.6637,-1.89562,41.2878,3.30455
-5.25234,40.3438,-2.06346,41.2406,3.4689
-5.04141,38.65,-2.21236,41.1111,1.70688
-3.65625,35.31,-2.28455,40.821,3.61584
-3.82266,41.25,-2.36146,40.8425,5.94233
-3.01484,36.16,-2.39412,40.6083,5.15371
-5.625,41.0013,-2.55567,40.628,5.5001
-5.50547,40.3387,-2.70316,40.6135,0.673297
-3.23438,35.7588,-2.72972,40.3708,5.11208
-4.58984,38.005,-2.82273,40.2525,2.62349
-3.88828,38.02,-2.876,40.1409,0.70172
-4.6125,41.6562,-2.96283,40.2166,3.70762
-6.125,44.44,-3.12094,40.4278,3.16815
-3.99297,44.795,-3.16454,40.6462,2.16138
-7.29609,51.0438,-3.37112,41.166,7.06811
-8.02188,56.06,-3.60365,41.9107,5.06844
-8.86875,53.65,-3.86691,42.4977,2.55446
-10.0008,53.1,-4.1736,43.0278,1.25859
-3.16172,41.695,-4.12301,42.9612,13.2984
-1.9875,40.8288,-4.01623,42.8546,1.45914
-1.35703,36.5062,-3.88327,42.5371,4.36834
-0.714844,36.1937,-3.72485,42.22,0.714184
-1.26562,34.12,-3.60189,41.815,2.1456
0.5375,31.415,-3.39492,41.295,3.25089
0.675781,28.34,-3.19139,40.6472,3.07811
-1.1125,30.01,-3.08744,40.1154,2.4468
-0.55,28.345,-2.96057,39.5268,1.75745
-1.1125,35.1312,-2.86817,39.3071,6.80947
0,33.9338,-2.72476,39.0384,1.63445
-2.44922,38.5687,-2.71098,39.0149,5.24223
-4.78828,43.05,-2.81485,39.2167,5.05502
-4.79375,42.54,-2.91379,39.3828,0.510028
-3.59297,39.395,-2.94775,39.3834,3.36644
-3.25078,38.79,-2.9629,39.3538,0.695067
-1.71875,40.57,-2.90069,39.4146,2.34851
-1.0125,37.4012,-2.80628,39.3139,3.24655
0,31.6987,-2.66597,38.9331,5.79169
-1.14297,33.1287,-2.58982,38.6429,1.83065
-2.275,34.2762,-2.57408,38.4246,1.61191
-1.9875,36.46,-2.54475,38.3264,2.20264
-2.675,39.1263,-2.55126,38.3664,2.75351
-2.72266,38.29,-2.55983,38.3625,0.837657
-4.64062,37.9437,-2.66387,38.3416,1.94897
-2.96953,33.84,-2.67915,38.1165,4.4309
-2.53125,34.2513,-2.67176,37.9233,0.601047
-3.61562,38.425,-2.71895,37.9483,4.31226
-1.1125,36.2313,-2.63863,37.8625,3.32835
-1.93984,35.6,-2.60369,37.7494,1.04069
-2.14453,29.47,-2.58073,37.3354,6.13342
-1.18828,20.2563,-2.51111,36.4814,9.26319
-1.14609,27.7938,-2.44286,36.0471,7.53762
-2.40391,27.4,-2.44091,35.6147,1.31802
-2.125,31.9,-2.42512,35.429,4.50864
-1.69609,29,-2.38866,35.1075,2.93155
-1.27266,30.48,-2.33286,34.8761,1.53938
-1.15,30.0688,-2.27372,34.6358,0.429104
-2.14453,33.6463,-2.26726,34.5863,3.71317
-3.14453,33.0312,-2.31113,34.5085,1.17403
-1.125,30.565,-2.25182,34.3114,3.18758
-0.5625,27.7987,-2.16735,33.9857,2.82291
-1.20234,35.8138,-2.1191,34.0771,8.0406
-2.125,36.5,-2.1194,34.1983,1.14986
-1.75703,35.1312,-2.10128,34.2449,1.4174
-1.5375,36.4188,-2.07309,34.3536,1.30618
-3.26172,39.515,-2.13252,34.6117,3.54392
-5.00078,40.7762,-2.27593,34.9199,2.14824
-1.77188,31.075,-2.25073,34.7277,10.2244
-2.625,30.565,-2.26944,34.5195,0.993939
-2.07422,39.7588,-2.25968,34.7815,9.21028
-0.8625,40.47,-2.18982,35.0659,1.40502
-0.155469,41.455,-2.08811,35.3854,1.21248
-1.9125,41.8288,-2.07933,35.7076,1.79635
-1.37109,41.2438,-2.04391,35.9844,0.797088
0,41.1813,-1.94172,36.2442,1.37251
-1.67578,43.5812,-1.92842,36.6111,2.92707
-2.69609,44.7738,-1.9668,37.0192,1.5695
-2.8125,43.3312,-2.00909,37.3348,1.44729
-1.9125,44.2287,-2.00426,37.6795,1.27102
-0.309375,40.495,-1.91952,37.8203,4.06331
-20.8438,72.0813,-2.86573,39.5333,37.6744
-21.4438,73.0413,-3.79463,41.2087,1.13208
-22.507,72.8313,-4.73025,42.7899,1.08374
-11.6617,56.9,-5.07682,43.4954,19.2724
-6.25234,40.2537,-5.1356,43.3333,17.5032
-2.92891,38.56,-5.02527,43.0946,3.73012
-1.91016,37.15,-4.86951,42.7974,1.73953
-2.68125,32.2,-4.7601,42.2675,5.0097
-5.34766,41.3563,-4.78948,42.222,9.53664
-3.4875,41.53,-4.72438,42.1874,1.86825
-4.02891,46.8512,-4.6896,42.4205,5.34867
-2.40234,38.0137,-4.57524,42.2002,8.98594
-0.625,40.505,-4.37773,42.1154,3.06031
-0.5875,33.2188,-4.18822,41.6706,7.2863
-0.5875,30.395,-4.00818,41.1068,2.8238
-1.575,23.8438,-3.88652,40.2437,6.62521
-1.6125,26.4287,-3.77282,39.5529,2.58517
-2.125,24.53,-3.69043,38.8018,1.96665
-2.41875,21.6362,-3.62685,37.9435,2.90867
-2.27109,19.045,-3.55906,36.9986,2.5954
-3.22266,42.4613,-3.54224,37.2717,23.4356
-2.92891,38.56,-3.51157,37.3361,3.91234
-3.0375,39.2912,-3.48787,37.4339,0.739217
-2.44922,39.2988,-3.43594,37.5271,0.588329
-4.28672,46.675,-3.47848,37.9845,7.60162
-2.84375,43.9313,-3.44674,38.2819,3.10001
-3.26172,41.6188,-3.43749,38.4487,2.34997
-3.82891,43.8462,-3.45706,38.7186,2.29848
-4.30547,41.455,-3.49948,38.8554,2.43822
-3.85,44.185,-3.51701,39.1219,2.76773
-3.82891,40.97,-3.5326,39.2143,3.21507
-4.25,41.7062,-3.56847,39.3389,0.848118
-3.03672,41.6188,-3.54188,39.4529,1.21642
-3.14453,44.45,-3.52202,39.7027,2.83325
-3.96484,41.96,-3.54416,39.8156,2.62164
-3.85,43.1037,-3.55945,39.98,1.14945
-4.25,42.85,-3.59398,40.1235,0.473671
-2.96484,38.7938,-3.56252,40.057,4.25492
-3.22266,39.7612,-3.54553,40.0422,1.00117
-2.96484,39.7637,-3.51649,40.0283,0.257832
-3.87422,40,-3.53438,40.0269,0.93958
-2.56797,40.7088,-3.48606,40.061,1.48617
-3.37891,40.7313,-3.4807,40.0945,0.811252
-4.28672,40.7687,-3.521,40.1282,0.90858
-5.5,42.8187,-3.61995,40.2627,2.38213
-3.14453,41.6712,-3.59618,40.3332,2.62011
-2.83828,41.1813,-3.55829,40.3756,0.577745
-2.6875,42.275,-3.51475,40.4705,1.10404
-3.14453,40.7313,-3.49624,40.4836,1.60993
-4.46016,41.7412,-3.54443,40.5465,1.65855
-5.17422,44.2287,-3.62592,40.7306,2.58796
-5.28984,46.305,-3.70912,41.0093,2.07952
-2.575,27.2763,-3.65241,40.3226,19.2214
2.32578,37.4688,-3.3535,40.1799,11.3095
3.91875,37.86,-2.98989,40.0639,1.6403
0.9,35.41,-2.79539,39.8312,3.88785
5.90625,37.9412,-2.36031,39.7367,5.60977
2.675,38.99,-2.10855,39.6994,3.3972
0.65625,40.7612,-1.97031,39.7525,2.68561
-0.99375,44.2713,-1.92148,39.9784,3.87857
-0.928125,40,-1.87181,39.9795,4.27181
-3.80859,42.8737,-1.96865,40.1242,4.06881
-3.3125,45.3,-2.03584,40.383,2.4765
-0.984375,42.08,-1.98327,40.4679,3.97348
1.02188,41.545,-1.83301,40.5217,2.07636
-1.45,45.995,-1.81386,40.7954,5.09045
-0.578906,46.78,-1.75211,41.0946,1.17262
8.38125,46.8713,-1.24545,41.3835,8.96062
-10.1719,48.2687,-1.69177,41.7277,18.6057
-9.32422,46.3,-2.07339,41.9563,2.14344
-39.6039,95.36,-2.824,43.0244,57.6519
-6.93984,64.48,-3.02979,44.0972,44.9501
-2.15859,57.9437,-2.98623,44.7895,8.09837
-5.03125,64.0512,-3.08848,45.7526,6.74935
2.81328,48.26,-2.79339,45.878,17.6323
-9.07266,49.3162,-3.10736,46.0499,11.9328
-10.1445,51.5062,-3.45922,46.3227,2.43822
5.22891,43.5337,-3.02481,46.1832,17.3177
2.4,43.7537,-2.75357,46.0618,2.83745
-2.85547,45.3,-2.75866,46.0237,5.47823
2.975,44.8213,-2.47198,45.9636,5.85009
-1.67188,44.16,-2.43198,45.8734,4.6937
-2.55,43.12,-2.43788,45.7357,1.36114
-1.57812,43.2337,-2.39489,45.6106,0.978508
-3.98125,44.3563,-2.47421,45.5479,2.65241
-2.48359,41,-2.47468,45.3205,3.67529
-1.75703,39.05,-2.43879,45.007,2.08096
-3.4875,40.52,-2.49123,44.7826,2.27056
-2.16797,40,-2.47507,44.5435,1.41829
-1.55547,40.2388,-2.42909,44.3283,0.657405
-2.14453,40,-2.41486,44.1118,0.635624
-2.325,40,-2.41037,43.9062,0.18047
-2.00078,42.2612,-2.38989,43.824,2.28433
-4.62578,41.8812,-2.50168,43.7269,2.65236
-4.14375,41.9512,-2.58378,43.6381,0.487086
3.78125,40.55,-2.26553,43.4837,8.04792
2.46797,41.9512,-2.02886,43.407,1.92043
-0.775,43.6,-1.96616,43.4167,3.63805
-2.89453,44.6312,-2.01258,43.4774,2.35707
-3.275,45.85,-2.0757,43.5961,1.2768
-16.9039,54.8462,-2.81711,44.1586,16.3303
-3.01328,39.44,-2.82692,43.9226,20.7437
3.5,44.0788,-2.51058,43.9304,7.99633
-3.71875,40.64,-2.57099,43.7659,7.99598
-2.01953,41.8,-2.54341,43.6676,2.05741
-2.38672,41.5187,-2.53558,43.5602,0.462556
-4.7125,41.89,-2.64442,43.4767,2.35523
6.69375,45.85,-2.17752,43.5953,12.0741
-3.5,56.2562,-2.24364,44.2284,14.5671
-11.5586,43.925,-2.70939,44.2132,14.7309
-21.3461,60.88,-3.64122,45.0466,19.5772
-31.5352,80.7812,-5.03592,46.8333,22.3579
-2.70703,37.46,-4.98934,46.6458,52.0364
-1.95078,39.4,-4.83742,46.2835,2.08219
-0.855469,38.5687,-4.63832,45.8978,1.37505
-2.45,41.4562,-4.5289,45.6757,3.29851
-3.09375,39.4,-4.45714,45.3619,2.15461
-3.53125,40,-4.41085,45.0938,0.742566
-2.16328,37.05,-4.29847,44.6916,3.25174
-3.9875,39.0363,-4.28292,44.4089,2.69688
-2.58125,28.3263,-4.19784,43.6047,10.8019
-2.125,35.6862,-4.0942,43.2088,7.37403
0.796875,26.9538,-3.84964,42.3961,9.20827
0.424219,27.4562,-3.63595,41.6491,0.625522
1.925,28.84,-3.3579,41.0086,2.04138
0.924219,32.5213,-3.1438,40.5842,3.81491
-1.69609,34.7238,-3.07141,40.2912,3.42301
-3.69688,39.475,-3.10268,40.2504,5.15529
-1.98047,36.7,-3.04657,40.0729,3.26292
-8.61328,39.7012,-3.32491,40.0543,7.2802
-4.45,45.98,-3.38116,40.3506,7.53367
-2.45,43.465,-3.33461,40.5063,3.21329
-3.01484,48.2537,-3.31862,40.8937,4.8219
3,44.3988,-3.00269,41.0689,7.14413
3.25,46.105,-2.69005,41.3207,1.72442
0.621094,48.19,-2.52449,41.6642,3.35535
-8.54297,54.4,-2.82542,42.301,11.07
-6.88359,56.605,-3.02833,43.0162,2.75963
-5.82266,53.5563,-3.16804,43.5432,3.22802
-5.775,54.145,-3.29839,44.0733,0.590625
-9.45,53.8138,-3.60597,44.5603,3.68989
-18.5,62.0687,-4.35067,45.4357,12.2493
-10.5273,43.16,-4.65951,45.3219,20.5208
-4.68125,37.1763,-4.66059,44.9147,8.36546
10.6117,41.4813,-3.89698,44.743,15.8873
-7.65,51.9437,-4.08463,45.103,21.0464
-19.9875,71.1062,-4.87977,46.4032,22.7907
-5.55625,45.94,-4.9136,46.38,29.0103
-4.29688,39.315,-4.88276,46.0268,6.74364
-3.69609,41.965,-4.82343,45.8237,2.71725
-3.025,40.9562,-4.73351,45.5803,1.21163
-1.79297,40.655,-4.58648,45.3341,1.26831
-1.5375,41.25,-4.43403,45.1298,0.647527
-1.4875,39.6912,-4.2867,44.8579,1.5596
-2.36641,40.61,-4.19069,44.6455,1.27149
-2.31875,35.8,-4.09709,44.2032,4.81024
-3.9,35.695,-4.08724,43.7778,1.58473
0,36.2137,-3.88287,43.3996,3.93434
-1.3875,37.3112,-3.75811,43.0952,1.76909
-1.9125,34.1,-3.66583,42.6454,3.25383
4.25,35.6937,-3.27003,42.2979,6.36524
-1.1,30.4188,-3.16153,41.7039,7.51313
-1.75703,31.9,-3.09131,41.2137,1.62038
-1.5375,34.555,-3.01362,40.8808,2.66406
-1.98047,35.455,-2.96196,40.6095,1.00311
-1.08984,34.0938,-2.86835,40.2837,1.62668
-4.4625,39.2313,-2.94806,40.2311,6.14563
-1.975,36.71,-2.89941,40.055,3.54184
-2.92891,36.5,-2.90088,39.8773,0.976752
-2.77266,37.2363,-2.89447,39.7452,0.752698
-1.63125,35.96,-2.83131,39.556,1.71224
-2.15,36.465,-2.79725,39.4014,0.723967
-2.07422,36.6688,-2.76109,39.2648,0.217433
-3.00234,38.1538,-2.77316,39.2092,1.75118
-2.12188,38.1188,-2.74059,39.1547,0.881155
-3.64766,39.7163,-2.78595,39.1828,2.20907
-2.44922,37.3787,-2.76911,39.0926,2.62691
-8.42813,39.385,-3.05206,39.1072,6.30655
-7.77734,38.185,-3.28833,39.0611,1.36511
-7.7,30.175,-3.50891,38.6168,8.01038
-9.625,52.96,-3.81471,39.334,22.8662
-8.1,50.01,-4.02898,39.8678,3.32086
-7.125,49.9,-4.18378,40.3694,0.981185
-3.75547,49.4087,-4.16236,40.8213,3.40516
-5.66953,48.55,-4.23772,41.2078,2.09785
-1.6875,44.3,-4.11021,41.3624,5.82401
-0.424219,25.375,-3.92591,40.563,18.9671
0.4875,32.095,-3.70524,40.1396,6.78157
-0.471094,41.96,-3.54353,40.2306,9.91146
-1.8,42.6538,-3.45636,40.3518,1.49912
-4.86797,46.0088,-3.52694,40.6346,4.54626
-2.23125,43.8063,-3.46215,40.7932,3.43559
-2.20391,46.18,-3.39924,41.0626,2.37386
1.44922,48.3013,-3.15682,41.4245,4.22437
-8.96484,53.8138,-3.44722,42.044,11.7831
-21.9,64.6,-4.36986,43.1718,16.8422
-5.6875,40.3587,-4.43574,43.0311,29.1631
-4.95,42.8,-4.46145,43.0196,2.55026
-5.17578,44.17,-4.49717,43.0771,1.38848
-6.14062,43.525,-4.57934,43.0995,1.16058
-6.18516,41.49,-4.65963,43.019,2.03549
-5.2875,42.98,-4.69103,43.017,1.73951
-2.49375,38.2313,-4.58116,42.7778,5.50955
-3.55,43.9738,-4.5296,42.8376,5.83883
-4.17109,43.2738,-4.51168,42.8594,0.935817
-5.3625,48.2163,-4.55422,43.1272,5.08407
-12.375,55.0062,-4.94526,43.7212,9.76104
-7.26562,47.245,-5.06128,43.8974,9.29204
-7.09141,47.6712,-5.16278,44.0861,0.460431
-5.99609,44.025,-5.20445,44.083,3.80716
-5.7,42.0187,-5.22923,43.9798,2.02803
-7.38672,43.6787,-5.3371,43.9647,2.36656
-5.87891,40,-5.36419,43.7665,3.97572
-1.39688,43.675,-5.16583,43.7619,5.79605
-4.53125,43.75,-5.1341,43.7613,3.13527
-4.34922,43.775,-5.09485,43.762,0.183739
-1.40547,40,-4.91039,43.5739,4.7871
-4.8375,45.0062,-4.90674,43.6455,6.06967
-4,43.96,-4.8614,43.6612,1.34013
-4.82422,43.9,-4.85955,43.6732,0.826401
-2.96484,42.6,-4.76481,43.6195,2.26877
-6.98672,54.0288,-4.87591,44.14,12.1158
-12.5039,64.4062,-5.25731,45.1533,11.7529
-9.73828,57.55,-5.48135,45.7731,7.39298
-2.01953,42.6662,-5.30826,45.6178,16.7662
-1.875,44.13,-5.1366,45.5434,1.47092
-2.5375,41.5062,-5.00664,45.3415,2.70615
-2.1,41.16,-4.86131,45.1325,0.557907
-3.72422,46.215,-4.80446,45.1866,5.30953
-2.30547,45.995,-4.67951,45.227,1.43571
-2.51562,46.8438,-4.57131,45.3078,0.874429
-0.177344,43.745,-4.35161,45.2297,3.88202
-9.63125,57.8063,-4.6156,45.8585,16.9439
0.925781,41.695,-4.33853,45.6504,19.262
-2.00234,41.4938,-4.22172,45.4425,2.93503
-3.04141,40,-4.1627,45.1704,1.81965
-3.06797,41.815,-4.10797,45.0026,1.81519
0.800781,29.7188,-3.86253,44.2384,12.6998
0.163281,38.6688,-3.66124,43.96,8.97268
-0.6875,40.2788,-3.51255,43.7759,1.82097

View File

@ -0,0 +1,410 @@
lastX,lastY,lastXf,lastYf,lastV
2.03672,47.1413,2.03672,47.1413,0
309.694,266.756,8.18985,51.5335,377.999
310.516,264.019,23.3061,62.1578,2.85823
308.138,263.699,37.5477,72.2349,2.39954
311.184,262.95,51.2295,81.7706,3.13676
313.568,262.63,64.3464,90.8136,2.40575
310.137,261.281,76.636,99.337,3.68681
311.85,262.494,88.3967,107.495,2.09893
308.138,263.699,99.3837,115.305,3.90316
311.988,260.22,110.014,122.551,5.18943
304.582,264.175,119.742,129.632,8.3961
308.138,264.48,129.162,136.374,3.56854
310.137,261.281,138.211,142.62,3.77212
310.137,260.5,146.807,148.514,0.78125
310.8,258.769,155.007,154.027,1.85397
308.138,264.019,162.663,159.526,5.88653
307.1,260.894,169.885,164.595,3.29273
307.468,264.1,176.764,169.57,3.22731
308.138,263.369,183.333,174.26,0.991488
311.184,261.066,189.726,178.6,3.81839
308.656,263.75,195.672,182.858,3.68646
311.988,258.24,201.488,186.627,6.43915
316.625,258.845,207.245,190.238,4.67602
316.488,262.679,212.707,193.86,3.83618
315.429,259.434,217.843,197.138,3.41355
321.012,256.25,223.001,200.094,6.42683
322.873,253.36,227.995,202.757,3.43732
321.012,255.256,232.646,205.382,2.65685
327.691,253.785,237.398,207.802,6.8398
329.559,250.74,242.006,209.949,3.57189
325.938,251.65,246.203,212.034,3.73368
333.09,254.2,250.547,214.143,7.59332
335.721,249.1,254.806,215.89,5.73876
339.284,252.731,259.03,217.732,5.08698
338.625,252.925,263.009,219.492,0.686509
328.9,254.2,266.304,221.227,9.80823
331.98,253.35,269.588,222.834,3.19559
327.691,253.785,272.493,224.381,4.31106
321.012,254.2,274.919,225.872,6.69257
319.275,254.804,277.137,227.319,1.83868
316.35,253.75,279.097,228.64,3.10901
315.816,252.299,280.933,229.823,1.54651
310.935,254.2,282.433,231.042,5.23771
314.626,251.469,284.043,232.063,4.59136
312.78,253.551,285.48,233.138,2.78246
310.409,253.75,286.726,234.168,2.38017
313.31,254.2,288.055,235.17,2.93624
312.78,252.52,289.292,236.037,1.76152
312.122,254.804,290.433,236.976,2.37681
313.84,254.841,291.604,237.869,1.71837
312.122,254.2,292.63,238.686,1.83373
315.281,251.451,293.762,239.324,4.18774
312.122,254.404,294.68,240.078,4.32421
312.78,253.75,295.585,240.762,0.927954
313.84,254.841,296.498,241.465,1.5209
305.916,259.814,296.969,242.383,9.35449
305.684,254.14,297.405,242.971,5.67853
306.862,255.071,297.877,243.576,1.50233
290.819,264.981,297.525,244.646,18.8576
290.145,265.28,297.156,245.678,0.737443
282.776,267.719,296.437,246.78,7.76182
280.377,254.201,295.634,247.151,13.7286
270.562,257.91,294.38,247.689,10.4922
260.975,262.94,292.71,248.451,10.8269
257.574,264.496,290.953,249.254,3.73995
248.4,259.644,288.825,249.773,10.3785
242.31,263.725,286.5,250.471,7.33096
235.262,261.65,283.938,251.03,7.34752
228.8,262.959,281.181,251.626,6.59292
224.527,262.381,278.348,252.164,4.31151
221.262,260.116,275.494,252.562,3.9736
211.926,259.675,272.315,252.917,9.34714
200.93,262.066,268.746,253.375,11.2523
188.871,266.931,264.752,254.052,13.0037
180.094,264.25,260.519,254.562,9.17774
171.996,268.9,256.093,255.279,9.3378
164.063,264.775,251.492,255.754,8.94121
163.041,262.269,247.069,256.08,2.70687
158.966,259.179,242.664,256.235,5.11407
144.472,258.684,237.754,256.357,14.5022
130.078,261.875,232.371,256.633,14.7433
120.213,262.609,226.763,256.932,9.8921
112.125,259.581,221.031,257.064,8.63633
98.6813,264.91,214.913,257.457,14.4613
93.9273,260.98,208.864,257.633,6.16802
88.5961,256.031,202.851,257.553,7.2741
79.2063,264.25,196.668,257.888,12.4787
67.3969,270.84,190.205,258.535,13.5237
54.0914,267.36,183.399,258.976,13.753
50.4727,255.28,176.753,258.792,12.6104
46.6594,262.6,170.248,258.982,8.2537
46.168,262.846,164.044,259.175,0.549651
33.7289,263.6,157.528,259.396,12.4619
26.8586,263.706,150.995,259.612,6.87113
25.1258,257.439,144.701,259.503,6.50262
14.7555,263.5,138.204,259.703,12.0118
7.85391,269.644,131.687,260.2,9.23997
2.58984,261.97,125.232,260.289,9.30573
-11.243,263.639,118.408,260.456,13.9331
-20.5875,246.19,111.458,259.743,19.7934
-27.25,238.37,104.523,258.674,10.2733
-32.3594,232.589,97.6788,257.37,7.71548
-42.6562,238.45,90.662,256.424,11.8482
-63.3625,246.23,82.9608,255.914,22.1196
-68.9133,240.936,75.3671,255.165,7.6704
-93.15,247.044,66.9412,254.759,24.9944
-100.231,243.3,58.5826,254.186,8.00997
-118.02,261.13,49.7525,254.534,25.1859
-132.762,267.906,40.6268,255.202,16.2257
-139.5,254.774,31.6204,255.181,14.76
-155.366,254.986,22.2711,255.171,15.8678
-158.838,256.98,13.2156,255.261,4.00362
-166.677,260.894,4.22095,255.543,8.76173
-174.591,263.571,-4.71967,255.944,8.35473
-185.12,264.58,-13.7397,256.376,10.5764
-191.401,255.036,-22.6227,256.309,11.4253
-199.866,249.76,-31.4849,255.982,9.97525
-205.513,242.95,-40.1863,255.33,8.84665
-215.909,249.375,-48.9725,255.032,12.2213
-222.759,233.264,-57.6618,253.944,17.5067
-233.475,235.724,-66.4525,253.033,10.9951
-238.781,229.39,-75.0689,251.851,8.26273
-246.054,235.566,-83.6181,251.037,9.54137
-262.555,254.349,-92.565,251.202,25.0017
-271.99,250.344,-101.536,251.159,10.2493
-268.125,237.094,-109.866,250.456,13.8022
-278.362,243.13,-118.291,250.09,11.8846
-281.438,226.619,-126.448,248.916,16.7952
-292.875,237.291,-134.769,248.335,15.6435
-298.098,233.8,-142.936,247.608,6.28211
-303.831,220.73,-150.98,246.264,14.2723
-308,200.309,-158.831,243.966,20.8424
-308.091,204.64,-166.294,242,4.3322
-319.7,206.08,-173.965,240.204,11.6983
-336.023,222.26,-182.068,239.307,22.983
-328.96,197.5,-189.412,237.217,25.7475
-347.566,228.186,-197.32,236.765,35.8865
-343.125,201.69,-204.61,235.011,26.8659
-334.744,174.846,-211.117,232.003,28.1217
-341.7,165.049,-217.646,228.655,12.0159
-348.621,168.754,-224.195,225.66,7.85038
-350.119,168.206,-230.491,222.788,1.59459
-332.175,122.074,-235.575,217.752,49.4994
-329.906,104.611,-240.292,212.095,17.6093
-405.934,213.969,-243.605,212.132,133.189
-339.973,106.5,-245.532,210.02,126.097
-358.102,124.72,-251.16,205.755,25.7032
-342.166,80.3938,-255.711,199.487,47.1041
-392.953,152.065,-258.456,198.538,87.8416
-335.149,50.455,-259.989,195.577,116.901
-347.73,57.575,-264.376,188.676,14.4562
-371.676,81.2562,-269.741,183.305,33.6776
-336.751,18.97,-271.082,180.019,71.4096
-337.254,8.5,-274.39,171.443,10.4821
-350.107,13.4312,-278.176,163.542,13.7666
-352.171,22.325,-281.876,156.481,9.13012
-371.62,47.15,-286.363,151.015,31.5361
-378.152,40,-290.953,145.464,9.68504
-345.503,-25.5362,-292.044,142.044,73.2187
-338.85,-28.4937,-294.384,133.517,7.28084
-334.434,-42.1912,-296.386,124.732,14.3916
-339.938,-28.1038,-298.564,117.09,15.1242
-341.419,-31.6987,-300.707,109.651,3.88821
-334.345,-55.7687,-302.389,101.38,25.088
-325.67,-83.2738,-303.553,92.1469,28.8406
-333.728,-75.335,-305.061,83.7728,11.3121
-340.875,-65.6,-306.852,76.3042,12.0768
-333.734,-83.025,-308.196,68.3377,18.8313
-316.431,-129.629,-308.608,58.4394,49.7123
-325.862,-135.601,-309.471,48.7374,11.1633
-328.344,-118.85,-310.414,40.358,16.934
-325.67,-131.569,-311.177,31.7616,12.9969
-328.545,-128.269,-312.045,23.7601,4.37672
-322.175,-143.82,-312.552,15.3811,16.8051
-329.594,-128.744,-313.404,8.17487,16.8027
-308.184,-176.326,-313.3,4.48485,52.1775
-314.688,-179.17,-313.369,-4.69789,7.09843
-325.54,-174.2,-313.978,-13.173,11.9363
-318.425,-181.719,-314.2,-21.6003,10.3515
-316.891,-196.574,-314.335,-30.349,14.9339
-315.038,-174.72,-314.37,-37.5675,21.9322
-308.719,-199.7,-314.087,-45.6741,25.7668
-312.007,-184.32,-313.983,-52.6064,15.7276
-301.219,-173.559,-313.345,-58.6541,15.2378
-290.426,-212.119,-312.199,-66.3273,40.042
-288.466,-222.174,-311.012,-74.1196,10.2441
-288.046,-202.696,-309.864,-80.5485,19.482
-269.43,-228.205,-307.842,-87.9313,31.5791
-272.441,-201.134,-306.072,-93.5914,27.2382
-257.625,-225.729,-303.65,-100.198,28.7131
-247.966,-228.11,-300.866,-106.594,9.94781
-259.677,-220.206,-298.806,-112.274,14.1285
-266.581,-183.939,-297.195,-115.858,36.9188
-252.769,-199.069,-294.974,-120.018,20.4866
-244.999,-212.945,-292.475,-124.665,15.9033
-237.979,-217.54,-289.75,-129.308,8.39039
-234.343,-202.625,-286.98,-132.974,15.3518
-236.251,-176.844,-284.443,-135.168,25.8517
-219.887,-198.014,-281.216,-138.31,26.7568
-203.815,-214.2,-277.346,-142.104,22.8106
-199.688,-211.224,-273.463,-145.56,5.08852
-194.97,-192.369,-269.538,-147.901,19.4363
-183.637,-206.82,-265.243,-150.847,18.3645
-176.391,-189.206,-260.8,-152.765,19.0463
-167.035,-201.519,-256.112,-155.202,15.4636
-161.187,-193.651,-251.366,-157.125,9.80316
-154.104,-195.75,-246.503,-159.056,7.38722
-137.923,-193.23,-241.074,-160.765,16.3763
-123.521,-195.766,-235.196,-162.515,14.6232
-114.787,-191.491,-229.176,-163.964,9.72445
-110.849,-182.131,-223.259,-164.872,10.1545
-90.5219,-187.281,-216.622,-165.993,20.9696
-83.2562,-190.85,-209.954,-167.235,8.09477
-77.2125,-192.05,-203.317,-168.476,6.16173
-71.0938,-193.22,-196.706,-169.713,6.22961
-58.9336,-180.275,-189.817,-170.241,17.7607
-49.0875,-173.719,-182.781,-170.415,11.8292
-38.3273,-190.375,-175.558,-171.413,19.8296
-29.2742,-189.911,-168.244,-172.338,9.06499
-17.1711,-185.086,-160.69,-172.976,13.0294
-4.4,-185.225,-152.876,-173.588,12.7718
-1.10312,-184.235,-145.287,-174.12,3.44231
7.16016,-178.916,-137.665,-174.36,9.82705
11.0938,-166.33,-130.227,-173.959,13.1866
26.475,-169.23,-122.392,-173.722,15.6522
38.3906,-160.305,-114.353,-173.051,14.8875
58.7664,-174.12,-105.697,-173.105,24.6176
71,-166.649,-96.8618,-172.782,14.3346
79.65,-170.6,-88.0362,-172.673,9.50973
85.1813,-171.609,-79.3753,-172.62,5.62248
100.1,-177.429,-70.4016,-172.86,16.0138
115.5,-178.984,-61.1065,-173.166,15.4783
118.754,-175.966,-52.1135,-173.306,4.4377
127.6,-180.785,-43.1278,-173.68,10.0734
141.094,-182.169,-33.9167,-174.105,13.5645
148.238,-180.345,-24.809,-174.417,7.37287
164.785,-172.836,-15.3293,-174.338,18.1716
173.723,-173.495,-5.8767,-174.296,8.96174
179.81,-169.776,3.40765,-174.07,7.13349
189.826,-172.701,12.7286,-174.001,10.434
193.6,-176.66,21.7721,-174.134,5.4696
192.5,-179.62,30.3085,-174.408,3.15778
203.438,-185.161,38.965,-174.946,12.2611
211.094,-182.314,47.5714,-175.314,8.16863
218.66,-179,56.1259,-175.499,8.26023
220.521,-176.72,64.3456,-175.56,2.94304
247.457,-164.791,73.5012,-175.021,29.4591
258.3,-165.92,82.7411,-174.566,10.9016
261.203,-164.791,91.6642,-174.078,3.11485
261.834,-163.67,100.173,-173.557,1.28634
258.75,-160.426,108.102,-172.901,4.47553
263.098,-162.946,115.851,-172.403,5.02518
269.812,-156.98,123.549,-171.632,8.9819
272.065,-168.08,130.975,-171.454,11.3264
275.84,-154.479,138.218,-170.605,14.1154
293.322,-155.806,145.974,-169.865,17.5324
300.796,-158.36,153.715,-169.29,7.89845
305.859,-155.935,161.322,-168.622,5.61405
306.387,-149.63,168.575,-167.673,6.32701
319.838,-148.48,176.138,-166.713,13.5006
323.15,-154.559,183.489,-166.105,6.92233
323.321,-147.194,190.481,-165.16,7.36698
326.804,-149.875,197.297,-164.396,4.39533
348.522,-151.16,204.858,-163.734,21.756
352.45,-149.42,212.238,-163.018,4.29626
348.847,-136.175,219.068,-161.676,13.7263
350.301,-130.905,225.63,-160.137,5.46688
356.178,-138.605,232.157,-159.061,9.68675
354.05,-127.085,238.252,-157.462,11.7149
350.87,-119.605,243.883,-155.569,8.12807
334.566,-119.551,248.417,-153.768,16.304
352.616,-84.9762,253.627,-150.329,39.0033
347.332,-89.265,258.312,-147.276,6.80572
346.372,-86.7063,262.715,-144.247,2.73296
340.862,-83.7688,266.622,-141.223,6.24359
332.709,-78.17,269.927,-138.07,9.89101
331.25,-74.9987,272.993,-134.917,3.4906
352.99,-70.2,276.993,-131.681,22.2632
341.87,-60.485,280.237,-128.121,14.7663
340.359,-44.73,283.243,-123.952,15.8273
344.541,-34.7713,286.308,-119.493,10.8012
350.441,-25.52,289.514,-114.794,10.9729
346.294,-16.6238,292.353,-109.885,9.81561
336.538,-11.9537,294.562,-104.989,10.8164
334.432,-1.76,296.556,-99.8275,10.4089
325.875,4.39125,298.022,-94.6165,10.5385
329.062,16.4,299.574,-89.0657,12.4246
328.802,29.56,301.035,-83.1344,13.1626
320.625,40.5762,302.015,-76.9489,13.7196
324.844,48.05,303.156,-70.6989,8.58224
326.2,52.705,304.309,-64.5287,4.84856
325.059,58.8512,305.346,-58.3597,6.25134
324.144,77.1312,306.286,-51.5852,18.3029
331.177,92.6612,307.53,-44.3729,17.0485
326.173,101.994,308.463,-37.0545,10.5897
326.812,107.555,309.38,-29.824,5.59793
330.347,112.724,310.428,-22.6967,6.2616
330.016,121.744,311.408,-15.4746,9.02605
330.715,135.45,312.373,-7.9284,13.724
328.382,144.88,313.174,-0.287976,9.71427
318.368,159.7,313.433,7.71142,17.8861
326.546,167.69,314.089,15.7104,11.4334
321.219,178.6,314.445,23.8548,12.1412
323.552,181.181,314.901,31.7212,3.47972
323.101,187.149,315.311,39.4925,5.98456
319.688,191.04,315.53,47.0699,5.17612
316.809,199.06,315.594,54.6694,8.52107
316.819,196.371,315.655,61.7545,2.68877
312.056,207.4,315.475,69.0368,12.0131
313.012,217.581,315.352,76.464,10.226
311.172,217.225,315.143,83.5021,1.87402
310.23,225.606,314.897,90.6073,8.43395
313.282,224.039,314.816,97.2788,3.43062
314.373,222.785,314.794,103.554,1.66172
317.82,230.5,314.945,109.901,8.44997
306.841,234.18,314.54,116.115,11.5792
309.602,240.43,314.293,122.331,6.83298
301.862,259.48,313.672,129.189,20.5623
302.672,255.574,313.122,135.508,3.98924
303.188,246.841,312.625,141.074,8.74771
301.895,258.7,312.089,146.956,11.929
304.365,246.256,311.702,151.921,12.6866
300.206,267.85,311.128,157.717,21.9905
301.895,258.7,310.666,162.766,9.30445
292.977,261.1,309.781,167.683,9.2345
293.288,265.12,308.957,172.555,4.03194
283.528,269.749,307.685,177.415,10.8014
279.822,270.944,306.292,182.091,3.89416
278.21,274.065,304.888,186.69,3.51281
277.513,273.8,303.519,191.045,0.746273
268.454,275.125,301.766,195.249,9.15499
268.454,272.324,300.1,199.103,2.80124
262.779,275.56,298.234,202.926,6.53292
260.145,266.879,296.33,206.124,9.07215
259.875,267.225,294.507,209.179,0.438791
253.45,268.75,292.454,212.157,6.6035
252.594,269.5,290.461,215.024,1.13827
247.641,271.575,288.32,217.852,5.37021
246.797,267.205,286.244,220.319,4.45073
246.797,264.624,284.272,222.535,2.58124
241.605,263.831,282.138,224.599,5.25155
231.099,256.141,279.586,226.177,13.0199
231.394,253.911,277.177,227.563,2.24935
232.603,258.88,274.948,229.129,5.11381
237.188,255.28,273.06,230.437,5.82894
233.344,250.87,271.074,231.458,5.85
231.562,253.12,269.099,232.541,2.86973
228.288,254.62,267.058,233.645,3.60146
227.2,256.08,265.065,234.767,1.82097
225.715,253.89,263.098,235.723,2.64608
230.344,255.25,261.46,236.7,4.82456
232.116,257.14,259.993,237.722,2.5907
236.223,262.104,258.804,238.941,6.44255
241.312,260.711,257.93,240.029,5.27689
249.331,259.126,257.5,240.984,8.1739
246.6,263.79,256.955,242.124,5.40466
246.34,267.7,256.424,243.403,3.91865
252.438,263.586,256.225,244.412,7.35558
251.318,263.86,255.979,245.385,1.15252
258.524,260.05,256.107,246.118,8.15146
255.363,262.769,256.069,246.951,4.16932
259.188,263.31,256.225,247.768,3.86233
256.487,260.509,256.238,248.405,3.89063
256.487,257.459,256.251,248.858,3.05002
0.6375,39.93,251.139,244.68,335.824
256.248,259.325,251.241,244.973,336.854
253.312,259.776,251.344,245.713,2.96963
256.248,259.004,251.59,246.377,3.0351
253.75,260.22,251.698,247.069,2.77804
255.122,258.354,251.869,247.634,2.31622
250.125,264.36,251.782,248.47,7.81303
249.004,263.725,251.643,249.233,1.28843
251.68,264.186,251.645,249.98,2.71601
252.372,263.725,251.681,250.668,0.831136
247.456,262.3,251.47,251.249,5.11801
244.535,264.36,251.123,251.905,3.57441
247.884,263.725,250.961,252.496,3.40887
244.535,264.36,250.64,253.089,3.40887
243.571,267.051,250.286,253.787,2.85872
249.694,261.976,250.257,254.197,7.95251
250.556,266.091,250.272,254.791,4.20441
246.5,268.119,250.083,255.458,4.53474
243.844,267.311,249.771,256.05,2.77628
247.193,265.466,249.642,256.521,3.82378
246.5,267.815,249.485,257.086,2.44885
241.062,272.06,249.064,257.835,6.89829
238.138,273.179,248.518,258.602,3.13092
236.619,270.85,247.923,259.214,2.78064
236.905,268.62,247.372,259.684,2.24837
234.112,273.09,246.709,260.355,5.27124
234.406,270.541,246.094,260.864,2.5657
231.293,276.666,245.354,261.654,6.87082
230.981,277.33,244.635,262.438,0.733283
229.163,276.459,243.861,263.139,2.01665
231.06,278.744,243.221,263.919,2.97023
235.425,273.22,242.832,264.384,7.04015
233.285,276.644,242.354,264.997,4.03744
234.8,277.431,241.977,265.619,1.70732
231.851,280.349,241.47,266.355,4.14847
227.665,274.63,240.78,266.769,7.08705
231.501,267.76,240.316,266.819,7.86837
230.874,252.681,239.844,266.112,15.0918
229.781,251.896,239.341,265.401,1.34566
229.378,248.38,238.843,264.55,3.53928
227.309,248.331,238.266,263.739,2.07011
226.91,248.925,237.698,262.998,0.715047
224.34,244.82,237.03,262.089,4.84329
223.256,242.601,236.342,261.115,2.46921
225.028

View File

@ -0,0 +1,207 @@
lastX,lastY,lastXf,lastYf,lastV
376.587,281.11,376.587,281.11,0
285.703,245.509,374.77,280.398,97.6085
287,242.484,370.381,278.502,3.29127
287,242.484,366.212,276.701,3.29127
289.943,242.166,362.399,274.975,2.96004
289.8,244,358.769,273.426,1.83932
288.649,244,355.263,271.955,1.15076
290.448,242.725,352.022,270.493,2.20453
292.466,246.154,349.044,269.276,3.97889
293.4,242.631,346.262,267.944,3.64411
292.466,247.36,343.572,266.915,4.82002
292.466,247.124,341.017,265.925,0.236252
290.806,246.316,338.507,264.945,1.84612
291.6,244.784,336.161,263.937,1.72587
289,248.725,333.803,263.176,4.7216
293.262,246.25,331.776,262.33,4.92828
288.845,251.469,329.63,261.787,6.83716
287.194,250.631,327.508,261.229,1.85108
294.419,245.82,325.853,260.458,8.68037
294.419,245.38,324.282,259.705,0.440002
291.457,246.419,322.64,259.04,3.1386
292.612,247.5,321.139,258.463,1.58246
292.106,246.25,319.687,257.853,1.34862
293.119,247.46,318.359,257.333,1.57773
295.577,245.82,317.22,256.757,2.95538
292.466,247.124,315.982,256.276,3.37308
290.655,249.55,314.716,255.939,3.02758
298.676,243.36,313.914,255.31,10.1312
291.309,247.594,312.784,254.925,8.49638
297.899,244.93,312.039,254.425,7.10786
295.577,244,311.216,253.904,2.50122
302.041,244.565,310.758,253.437,6.48873
297.385,243.894,310.089,252.96,4.70439
300.875,243.894,309.628,252.506,3.48984
294.045,242.279,308.849,251.995,7.01881
297.385,245,308.276,251.645,4.30872
297.899,246.461,307.757,251.386,1.54903
298.031,243.31,307.271,250.982,3.15401
295.577,245.82,306.686,250.724,3.51025
297.763,247.681,306.24,250.572,2.8704
298.031,243.31,305.829,250.209,4.3795
295.066,244.784,305.291,249.938,3.31093
298.676,242.5,304.961,249.566,4.2712
297.763,248.116,304.601,249.493,5.69003
296.737,246.25,304.207,249.331,2.12922
296.737,245.38,303.834,249.133,0.869995
300.48,240.8,303.666,248.717,5.91492
292.754,245,303.121,248.531,8.7943
299.193,243.531,302.924,248.281,6.60444
299.71,244.784,302.764,248.106,1.35508
297.385,244.565,302.495,247.929,2.33525
0.6375,39.93,296.458,243.769,360.465
298.413,246.859,296.497,243.831,362.615
295.066,245,296.425,243.889,3.82837
299.837,242.279,296.596,243.809,5.49259
295.066,243.665,296.519,243.802,4.9684
293.4,243.531,296.363,243.788,1.67177
295.712,243.531,296.331,243.775,2.3125
295.066,245,296.268,243.836,1.60457
295.066,244.344,296.208,243.862,0.65625
294.277,248.116,296.111,244.075,3.85414
296.599,247.9,296.135,244.266,2.33192
297.385,245.425,296.198,244.324,2.59679
297.899,246.461,296.283,244.431,1.15675
299.062,246.25,296.422,244.522,1.18229
300.356,243.75,296.619,244.483,2.81493
299.837,242.279,296.78,244.373,1.56003
297.641,240.224,296.823,244.165,3.00761
295.2,241.6,296.742,244.037,2.80259
297.385,242.484,296.774,243.959,2.35709
292.754,241.494,296.573,243.836,4.73589
288,243.82,296.144,243.835,5.29255
282.109,246.4,295.442,243.964,6.43085
274.962,243.276,294.418,243.929,7.80042
273.662,244.861,293.38,243.976,2.04995
268.025,244.861,292.113,244.02,5.63672
263.163,247.506,290.665,244.194,5.53533
255.166,251.869,288.89,244.578,9.10942
264.08,234.331,287.65,244.066,19.6733
264.254,224.6,286.48,243.093,9.73279
197.977,327.98,284.71,244.79,122.801
223.265,277.656,283.481,245.448,56.32
253.219,227.976,282.876,245.098,58.0115
246.725,231.125,281.068,244.4,7.21688
234.984,235.96,278.764,243.978,12.6972
224.656,234.781,276.059,243.518,10.3952
216.684,234.7,273.09,243.077,7.97307
207.298,235,269.8,242.673,9.39073
197.691,241.524,266.195,242.616,11.612
192.806,234.756,262.525,242.223,8.34648
185.637,232.041,258.681,241.714,7.66638
180.562,228.76,254.775,241.066,6.04271
176.834,229.706,250.878,240.498,3.8471
165.069,232.096,246.587,240.078,12.0051
161.4,230.125,242.328,239.58,4.16481
147.95,234.805,237.609,239.341,14.241
139.993,234.35,232.728,239.092,7.97003
137.863,233.219,227.985,238.798,2.41218
134.712,230.336,223.321,238.375,4.2704
136.837,226.349,218.997,237.774,4.51874
123.973,225.325,214.246,237.151,12.9055
107.563,220.649,208.912,236.326,17.0627
99.1633,214.589,203.424,235.239,10.3578
81.443,219.286,197.325,234.442,18.3324
71.775,211.6,191.048,233.3,12.351
65.8758,207.099,184.789,231.99,7.42038
54.5945,214.435,178.279,231.112,13.4569
45.9375,218.35,171.662,230.474,9.50113
25.7445,230.859,164.366,230.493,23.7534
23.9477,221.464,157.346,230.042,9.5653
-0.830469,237.135,149.437,230.396,29.318
0.819531,217.6,142.006,229.756,19.6045
-12.3633,222,134.287,229.369,13.8977
-26.45,229.83,126.251,229.392,16.1166
-42.7523,245.654,117.8,230.205,22.7191
-47.782,242.02,109.521,230.795,6.20499
-45.9336,232.8,101.749,230.896,9.40346
-62.5195,238.45,93.5351,231.273,17.5219
-70.2188,230.38,85.3474,231.229,11.1536
-73.425,221.074,77.4088,230.721,9.84309
-86.9375,226.506,69.1915,230.51,14.5636
-98.4445,226.73,60.8097,230.321,11.5092
-119.127,243.625,51.8128,230.986,26.7062
-128.468,238.469,42.7988,231.361,10.6693
-128.725,227,34.2226,231.143,11.4716
-133.806,240.02,25.8212,231.586,13.9764
-141.559,234.6,17.4522,231.737,9.45914
-150.15,233.684,9.07206,231.834,8.64012
-154.984,223.04,0.869235,231.395,11.6902
-163.8,221.094,-7.36423,230.88,9.02791
-159.388,205.87,-14.9654,229.629,15.8501
-179.156,221.271,-23.175,229.211,25.0594
-188.353,210.145,-31.4339,228.258,14.4352
-192.375,200.634,-39.4809,226.877,10.3266
-196.113,201.436,-47.3125,225.605,3.82269
-198.534,199.469,-54.8736,224.298,3.12034
-211.188,203.24,-62.6893,223.245,13.2032
-220.509,205.095,-70.5803,222.338,9.50464
-230.985,191.92,-78.6006,220.817,16.8322
-233.535,187.521,-86.3473,219.152,5.08443
-244.521,173.734,-94.256,216.881,17.6291
-253.594,176.29,-102.223,214.851,9.4259
-257.231,177.806,-109.973,212.999,3.94088
-263.466,183,-117.648,211.499,8.11434
-264.156,179.75,-124.973,209.912,3.32257
-264.5,181.9,-131.95,208.511,2.1773
-264.644,164.836,-138.584,206.327,17.0644
-284.377,180.825,-145.874,205.052,25.3979
-298.519,199.201,-153.506,204.76,23.1876
-283.5,145.869,-156.106,203.582,55.4068
-282.669,126.456,-162.434,199.726,19.4303
-281.934,121.375,-168.409,195.808,5.13405
-292.719,123.831,-174.625,192.209,11.0605
-301.962,130.956,-180.992,189.147,11.671
-282.909,76.135,-183.03,186.886,58.0378
-289.015,69.745,-188.329,181.029,8.83792
-296.25,78.0938,-193.725,175.883,11.0476
-304.441,79.9,-199.261,171.083,8.38819
-318.734,98.8438,-205.235,167.471,23.7304
-295.029,28.4062,-207.031,164.69,74.3193
-301,30.01,-211.729,157.956,6.18272
-338.121,74.2,-214.257,156.281,57.7125
-323.35,36.605,-219.712,150.297,40.3927
-306.513,3.095,-224.052,142.937,37.5023
-309.15,3.04,-228.307,135.942,2.63806
-314.438,-2.28125,-232.613,129.031,7.50156
-328.212,5.7,-237.393,122.865,15.9201
-316.094,-24.79,-241.328,115.482,32.8101
-299.259,-66.3913,-244.225,106.388,44.8783
-312.818,-55.76,-247.654,98.2807,17.2296
-330.738,-41.8387,-251.809,91.2747,22.6923
-333.644,-38.4688,-255.9,84.7876,4.44956
-344.941,-33.92,-260.352,78.8522,12.179
-319.087,-71.8812,-263.289,71.3155,45.9291
-317.5,-91.48,-266,63.1757,19.6629
-314.185,-106.944,-268.409,54.6698,15.815
-333.728,-88.2063,-271.675,47.526,27.0744
-329.716,-96.5,-274.577,40.3247,9.21304
-291.656,-162.449,-274.919,36.2692,76.1434
-297.332,-167.969,-276.039,26.0573,7.91738
-303.105,-160.1,-277.393,16.7494,9.7596
0.6375,39.93,-271.832,17.213,363.692
-322.875,-147.919,-272.853,13.9104,374.096
-349.629,-112.469,-276.692,7.59145,44.4125
-376.763,-79.0312,-281.695,3.26031,43.0616
-297.048,-191.82,-282.002,-0.641291,138.115
-299.334,-179.551,-282.869,-9.58679,12.48
-304.174,-172.021,-283.934,-17.7085,8.95125
-305.381,-173.559,-285.006,-25.501,1.95469
-299.334,-168.271,-285.723,-32.6395,8.03257
-298.184,-160.216,-286.346,-39.0184,8.1368
-283.5,-183.74,-286.204,-46.2545,27.7304
-271.274,-192.651,-285.457,-53.5743,15.1288
-271.09,-195.646,-284.739,-60.6779,3.00068
-267.129,-174.5,-283.858,-66.369,21.514
-250.125,-200.87,-282.172,-73.0941,31.3769
-277.296,-126.776,-282.074,-74.1677,78.9186
-252.7,-169.464,-280.605,-78.9325,49.2665
-288.447,-96.325,-280.762,-79.2803,81.4071
-282.691,-97.0537,-280.859,-80.169,5.80142
-259.188,-123.494,-279.775,-82.3353,35.3766
-249.862,-112.64,-278.279,-83.8505,14.3099
-226.462,-142.081,-275.689,-86.762,37.6073
-212.128,-154.786,-272.511,-90.1632,19.1544
-207.274,-151.205,-269.249,-93.2153,6.03207
-182.45,-164.851,-264.909

View File

@ -0,0 +1,203 @@
393.24,243.5,393.24,243.5,0
300.48,241.906,393.147,243.498,92.7731
301.001,243.36,391.304,243.496,1.54406
303.45,241.305,389.547,243.452,3.19714
300.48,242.746,387.766,243.438,3.30082
298.547,246.044,385.981,243.49,3.8226
299.062,245.82,384.243,243.536,0.562075
300.094,246.316,382.56,243.592,1.14444
302.809,240.571,380.965,243.532,6.35417
305.469,233.27,379.455,243.326,7.77075
301.762,240.07,377.901,243.261,7.74481
304.938,235.615,376.442,243.108,5.47107
304.594,229.97,375.005,242.846,5.65546
306.913,230.8,373.643,242.605,2.46283
309.318,228.81,372.357,242.329,3.12191
309.318,228.191,371.096,242.046,0.618744
310.69,223.101,369.888,241.667,5.27164
308.234,227.23,368.655,241.378,4.80414
311.85,222.281,367.519,240.996,6.12932
308.438,218.8,366.337,240.553,4.87486
310.69,221.2,365.224,240.165,3.29136
308.074,227.956,364.081,239.921,7.2449
311.85,220.29,363.036,239.529,8.54565
307.763,221.5,361.931,239.168,4.26283
304.145,229.895,360.775,238.983,9.14144
308.92,227.119,359.738,238.745,5.52342
308.374,227.04,358.711,238.511,0.550976
311.787,230.181,357.772,238.345,4.63817
319.454,226.344,357.006,238.105,8.57394
311.85,227.59,356.103,237.894,7.70536
314.837,215.175,355.278,237.44,12.7694
310.69,227.976,354.386,237.251,13.4564
308.306,223.381,353.464,236.973,5.17645
307.763,222.835,352.55,236.691,0.770735
314.785,222.905,351.795,236.415,7.02299
307.149,215.36,350.902,235.994,10.7347
306.607,205.435,350.016,235.383,9.9398
306.534,208.125,349.146,234.837,2.69098
308.306,213.841,348.33,234.417,5.98457
311.172,207.4,347.586,233.877,7.04994
305.837,210.73,346.751,233.414,6.28844
313.563,219.829,346.088,233.142,11.9363
310.078,218.035,345.368,232.84,3.91968
0.6375,39.93,345.023,232.647,357.036
308.92,205.799,344.987,232.621,350.072
316.559,202.87,344.418,232.026,8.18126
315.34,203.35,343.837,231.452,1.30987
312.335,207.4,343.207,230.971,5.04288
304.84,225.26,342.439,230.857,19.369
304.5,218.245,341.68,230.605,7.02323
306.984,205.6,340.987,230.104,12.8867
312.225,201.471,340.411,229.532,6.67164
309.969,191.45,339.802,228.77,10.2721
311.09,179.65,339.228,227.788,11.8531
306.568,182.931,338.575,226.891,5.58695
311.609,174.865,338.036,225.85,9.5121
314.854,165.494,337.572,224.643,9.91703
313.622,160.285,337.093,223.356,5.35246
308.438,154.95,336.52,221.988,7.4391
306.152,153.636,335.913,220.621,2.63588
313.431,142.66,335.463,219.061,13.1704
307.594,134.01,334.906,217.36,10.4355
305.774,121.42,334.323,215.442,12.7208
310.316,116.799,333.843,213.469,6.4792
306.25,108.145,333.291,211.362,9.56121
300.625,94.5212,332.638,209.025,14.7393
307.07,86.7087,332.126,206.579,10.1275
306.8,75.6087,331.62,203.96,11.1033
306.8,71.4688,331.123,201.31,4.14
313.294,52.87,330.767,198.341,19.6998
308.851,44.1387,330.328,195.257,9.79668
319.496,42.35,330.112,192.199,10.7946
324.543,33.5513,330,189.026,10.1434
320.257,22.9988,329.805,185.705,11.3897
312.163,14.4688,329.453,182.281,11.7593
311.362,5.49,329.091,178.745,9.01432
313.2,-3.845,328.773,175.093,9.51413
323.675,-19,328.671,171.211,18.4228
319.487,-26.8438,328.487,167.25,8.89155
315.356,-30.5,328.225,163.295,5.51681
307.359,-24.075,327.807,159.548,10.2582
307.519,-23.4737,327.402,155.887,0.622013
318.381,-40.0737,327.221,151.968,19.8382
314.895,-42.5,326.975,148.079,4.24782
308.932,-53.3112,326.614,144.051,12.3464
329.975,-88.075,326.681,139.408,40.6365
340.545,-101.181,326.958,134.597,16.8371
337.75,-102.6,327.174,129.853,3.13404
333.216,-106.306,327.295,125.13,5.85575
324.913,-117.76,327.247,120.272,14.1472
327.354,-120.035,327.249,115.466,3.33708
331.568,-127.434,327.336,110.608,8.51467
328.284,-133.426,327.355,105.727,6.83317
330.682,-140.4,327.421,100.804,7.37441
326.6,-138.391,327.405,96.0205,4.54951
324.044,-143.75,327.338,91.2251,5.93722
316.819,-150.099,327.127,86.3986,9.61808
315.246,-146.2,326.89,81.7467,4.204
314.388,-143.465,326.64,77.2424,2.86637
313.801,-143.511,326.383,72.8274,0.589312
313.388,-146.431,326.123,68.4422,2.9491
314.098,-147.956,325.882,64.1142,1.68225
306.73,-144.15,325.499,59.949,8.29235
308.848,-146.766,325.166,55.8147,3.3656
317.824,-150.099,325.019,51.6964,9.57519
314.557,-143.491,324.81,47.7926,7.37113
310.395,-146.431,324.522,43.9082,5.09608
303.045,-147.331,324.092,40.0834,7.4049
259.959,-144.756,322.81,36.3866,43.162
255.875,-143.166,321.471,32.7955,4.38296
247.28,-143.229,319.987,29.2751,8.59476
238.034,-139.955,318.348,25.8905,9.80855
215.919,-138.149,316.3,22.6097,22.1893
206.024,-143.544,314.094,19.2866,11.2698
184.316,-141.051,311.499,16.0799,21.8512
166.434,-137.84,308.597,13.0015,18.1681
163.269,-137.189,305.691,9.99766,3.23115
158.775,-136.906,302.752,7.05959,4.50263
151.696,-140.749,299.731,4.10342,8.05454
143.887,-135.499,296.614,1.31138,9.41004
140.691,-140.401,293.496,-1.52287,5.8523
127.604,-143.556,290.178,-4.36353,13.4617
115.5,-133.5,286.684,-6.94626,15.7363
93.6633,-130.88,282.824,-9.42493,21.9933
75.0383,-129.28,278.668,-11.822,18.6936
69.4,-129.009,274.483,-14.1658,5.6448
61.8063,-129.009,270.229,-16.4626,7.59375
54.0625,-132.511,265.906,-18.7836,8.49901
46.2852,-133.36,261.514,-21.0751,7.82352
38.2812,-128.789,257.049,-23.2294,9.21731
26.682,-136.3,252.442,-25.4908,13.8189
12.4523,-130.97,247.642,-27.6004,15.1952
7.03828,-136.811,242.83,-29.7846,7.96444
-5.97266,-131.919,237.854,-31.8273,13.9004
-15.1812,-127.344,232.793,-33.7376,10.2825
-19.0586,-131.856,227.756,-35.7,5.94949
-33.7125,-132.9,222.527,-37.644,14.691
-54.3727,-123.499,216.989,-39.3611,22.6986
-66.0773,-125.255,211.327,-41.0789,11.8357
-66.4563,-131.72,205.772,-42.8918,6.4761
-88.4062,-136.79,199.888,-44.7697,22.5279
-102.916,-126.534,193.832,-46.405,17.7689
-111.309,-123.036,187.729,-47.9376,9.09183
-123.2,-114.285,181.511,-49.2646,14.7645
-146.812,-110.92,174.944,-50.4977,23.8511
-155.959,-110.425,168.326,-51.6962,9.16026
-159.405,-116.465,161.772,-52.9916,6.95392
-155.105,-130.781,155.434,-54.5474,14.9481
-177.959,-130.4,148.766,-56.0644,22.8571
-191.35,-110.8,141.964,-57.1591,23.7375
-203.887,-107.5,135.047,-58.166,12.9638
-215.472,-107.245,128.037,-59.1475,11.588
-224.623,-120.519,120.983,-60.375,16.1223
-228.762,-135.291,113.988,-61.8733,15.3414
-233.35,-127.67,107.042,-63.1892,8.89583
-241.812,-130.37,100.065,-64.5328,8.88278
-267.668,-125.261,92.71,-65.7474,26.3554
-282.994,-115.194,85.1959,-66.7363,18.3367
-295.969,-106.704,77.5726,-67.5357,15.5058
-299.843,-115.94,70.0243,-68.5038,10.0159
-319.437,-106.731,62.2351,-69.2683,21.6499
-342.575,-81.5263,54.1389,-69.5135,34.2151
-354.138,-71.9037,45.9734,-69.5613,15.0433
-441.975,45.6738,45.4854,-69.446,146.764
-433.704,38.1113,35.9016,-67.2949,11.2072
-440.263,40,26.3784,-65.149,6.82587
-365.395,-83.59,25.9866,-65.1675,144.499
0.6375,39.93,25.9612,-65.0624,386.312
-312.649,-171.901,25.6226,-65.1692,378.181
-316.406,-165.774,18.7821,-67.1813,7.18759
-322.109,-159.586,11.9643,-69.0294,8.41438
-329.098,-150.059,5.14303,-70.65,11.8161
-330.284,-142.696,-1.5655,-72.0909,7.45741
-320.938,-138.139,-7.95293,-73.4118,10.3981
-309.225,-149.27,-13.9784,-74.929,16.1582
-337.312,-95.85,-14.3017,-74.9499,60.354
-335.562,-80.19,-20.7269,-75.0547,15.7575
-318.75,-107,-26.6874,-75.6936,31.6455
-328.653,-70.4863,-32.7267,-75.5895,37.8329
-323.916,-64.55,-38.5505,-75.3687,7.59445
-325.671,-52.2863,-44.2929,-74.907,12.3886
-324.825,-48.6763,-49.9035,-74.3824,3.70782
-307.099,-53.9813,-55.0474,-73.9744,18.5026
-318.509,-23.6863,-60.3166,-72.9686,32.3722
-313.915,-13.1263,-65.3886,-71.7718,11.5159
-435.204,209.05,-65.7584,-71.491,253.127
-305.905,23.075,-65.9985,-71.3964,226.506
-298.209,34.9787,-70.6428,-69.2689,14.1749
-298.209,48.3187,-75.1941,-66.9172,13.34
-298.7,54.9738,-79.6642,-64.4793,6.67306
-317.656,93.84,-84.424,-61.313,43.2426
-309.629,90.25,-88.9281,-58.2817,8.79354
-295.5,88.0312,-93.0596,-55.3555,14.3021
-390.875,255.025,-93.3574,-55.0451,192.31
-309.659,132.469,-93.5737,-54.8576,147.024
-314.093,144.935,-97.984,-50.8617,13.2312
-316.462,170.419,-102.354,-46.4361,25.5937
-313.88,178.375,-106.584,-41.9399,8.36474
-310.73,170.419,-110.667,-37.6927,8.55713
-331.287,217.84,-110.888,-37.4372,51.6849
-323.552,223.6,-115.141,-32.2165,9.64356
-294.816,177.145,-115.321,-32.0071,54.6248
-265.916,173.66,-118.333,-27.8938,29.1086

View File

@ -0,0 +1,203 @@
393.24,243.5,393.24,243.5,0
300.48,241.906,393.147,243.498,92.7737
301.001,243.36,391.304,243.496,1.54452
303.45,241.305,389.547,243.452,3.19698
300.48,242.746,387.766,243.438,3.30112
298.547,246.044,385.982,243.49,3.82274
299.062,245.82,384.243,243.536,0.561619
300.094,246.316,382.56,243.592,1.14498
302.809,240.571,380.965,243.532,6.35423
305.469,233.27,379.455,243.326,7.77047
301.762,240.07,377.901,243.261,7.7448
304.938,235.615,376.442,243.108,5.4712
304.594,229.97,375.005,242.846,5.65548
306.913,230.8,373.643,242.605,2.46306
309.318,228.81,372.357,242.329,3.12156
309.318,228.191,371.096,242.046,0.619003
310.69,223.101,369.888,241.667,5.27167
308.234,227.23,368.655,241.378,4.80422
311.85,222.281,367.519,240.996,6.12927
308.438,218.8,366.337,240.552,4.87435
310.69,221.2,365.224,240.165,3.29113
308.074,227.956,364.081,239.921,7.24479
311.85,220.29,363.037,239.529,8.54551
307.763,221.5,361.931,239.168,4.26236
304.145,229.895,360.775,238.983,9.14145
308.92,227.119,359.738,238.745,5.52332
308.374,227.04,358.711,238.511,0.551707
311.787,230.181,357.773,238.345,4.63837
319.454,226.344,357.006,238.105,8.57355
311.85,227.59,356.103,237.894,7.70541
314.837,215.175,355.278,237.44,12.7693
310.69,227.976,354.386,237.251,13.456
308.306,223.381,353.464,236.973,5.17663
307.763,222.835,352.55,236.69,0.770035
314.785,222.905,351.795,236.415,7.02235
307.149,215.36,350.902,235.994,10.7348
306.607,205.435,350.016,235.383,9.93979
306.534,208.125,349.147,234.837,2.69099
308.306,213.841,348.33,234.417,5.98437
311.172,207.4,347.587,233.877,7.04986
305.837,210.73,346.752,233.414,6.28896
313.563,219.829,346.088,233.142,11.9366
310.078,218.035,345.368,232.84,3.91963
0.6375,39.93,345.023,232.647,357.036
308.92,205.799,344.987,232.621,350.072
316.559,202.87,344.418,232.026,8.18126
315.34,203.35,343.837,231.452,1.3101
312.335,207.4,343.207,230.971,5.04306
304.84,225.26,342.439,230.857,19.3689
304.5,218.245,341.681,230.605,7.02323
306.984,205.6,340.987,230.104,12.8867
312.225,201.471,340.411,229.532,6.67209
309.969,191.45,339.803,228.77,10.2718
311.09,179.65,339.228,227.788,11.8531
306.568,182.931,338.575,226.891,5.58691
311.609,174.865,338.036,225.85,9.51168
314.854,165.494,337.572,224.643,9.91694
313.622,160.285,337.093,223.356,5.35271
308.438,154.95,336.52,221.988,7.43884
306.152,153.636,335.913,220.621,2.63672
313.431,142.66,335.463,219.061,13.1703
307.594,134.01,334.906,217.36,10.4352
305.774,121.42,334.323,215.442,12.7209
310.316,116.799,333.843,213.469,6.47947
306.25,108.145,333.291,211.362,9.5616
300.625,94.5212,332.638,209.025,14.7393
307.07,86.7087,332.126,206.579,10.1278
306.8,75.6087,331.62,203.96,11.1033
306.8,71.4688,331.123,201.31,4.1399
313.294,52.87,330.767,198.341,19.6999
308.851,44.1387,330.329,195.257,9.79672
319.496,42.35,330.112,192.199,10.7942
324.543,33.5513,330,189.026,10.1434
320.257,22.9988,329.806,185.705,11.3897
312.163,14.4688,329.453,182.281,11.759
311.362,5.49,329.091,178.745,9.01446
313.2,-3.845,328.773,175.093,9.51423
323.675,-19,328.671,171.211,18.4228
319.487,-26.8438,328.487,167.25,8.89182
315.356,-30.5,328.225,163.295,5.51662
307.359,-24.075,327.808,159.548,10.2583
307.519,-23.4737,327.402,155.887,0.622225
318.381,-40.0737,327.221,151.968,19.8379
314.895,-42.5,326.975,148.079,4.24727
308.932,-53.3112,326.614,144.051,12.3466
329.975,-88.075,326.681,139.408,40.6366
340.545,-101.181,326.958,134.597,16.8372
337.75,-102.6,327.174,129.853,3.13459
333.216,-106.306,327.295,125.13,5.8559
324.913,-117.76,327.247,120.272,14.1469
327.354,-120.035,327.25,115.466,3.33679
331.568,-127.434,327.336,110.608,8.51486
328.284,-133.426,327.355,105.727,6.83291
330.682,-140.4,327.421,100.804,7.37476
326.6,-138.391,327.405,96.0205,4.54959
324.044,-143.75,327.338,91.2251,5.93734
316.819,-150.099,327.127,86.3987,9.61824
315.246,-146.2,326.89,81.7467,4.20435
314.388,-143.465,326.64,77.2425,2.86643
313.801,-143.511,326.383,72.8274,0.588806
313.388,-146.431,326.123,68.4422,2.94906
314.098,-147.956,325.883,64.1143,1.68217
306.73,-144.15,325.499,59.949,8.29294
308.848,-146.766,325.166,55.8147,3.36591
317.824,-150.099,325.02,51.6964,9.57484
314.557,-143.491,324.81,47.7927,7.3715
310.395,-146.431,324.522,43.9082,5.09569
303.045,-147.331,324.092,40.0834,7.40487
259.959,-144.756,322.81,36.3867,43.1629
255.875,-143.166,321.471,32.7956,4.38261
247.28,-143.229,319.987,29.2751,8.59523
238.034,-139.955,318.348,25.8905,9.80855
215.919,-138.149,316.3,22.6097,22.1886
206.024,-143.544,314.094,19.2867,11.2702
184.316,-141.051,311.499,16.0799,21.8507
166.434,-137.84,308.597,13.0015,18.168
163.269,-137.189,305.691,9.9977,3.23127
158.775,-136.906,302.752,7.05963,4.5029
151.696,-140.749,299.731,4.10346,8.05486
143.887,-135.499,296.614,1.31142,9.40973
140.691,-140.401,293.496,-1.52283,5.85185
127.604,-143.556,290.178,-4.36349,13.4619
115.5,-133.5,286.685,-6.94622,15.7363
93.6633,-130.88,282.824,-9.42489,21.9933
75.0383,-129.28,278.668,-11.822,18.6936
69.4,-129.009,274.483,-14.1657,5.64481
61.8063,-129.009,270.229,-16.4626,7.5937
54.0625,-132.511,265.906,-18.7836,8.49885
46.2852,-133.36,261.514,-21.0751,7.8235
38.2812,-128.789,257.049,-23.2294,9.21727
26.682,-136.3,252.442,-25.4908,13.8187
12.4523,-130.97,247.642,-27.6004,15.1952
7.03828,-136.811,242.83,-29.7846,7.96423
-5.97266,-131.919,237.854,-31.8273,13.9002
-15.1812,-127.344,232.793,-33.7376,10.2824
-19.0586,-131.856,227.756,-35.7,5.94915
-33.7125,-132.9,222.527,-37.644,14.691
-54.3727,-123.499,216.989,-39.3611,22.6985
-66.0773,-125.255,211.327,-41.0789,11.8356
-66.4563,-131.72,205.772,-42.8917,6.4761
-88.4062,-136.79,199.888,-44.7697,22.5278
-102.916,-126.534,193.832,-46.405,17.7685
-111.309,-123.036,187.729,-47.9376,9.09276
-123.2,-114.285,181.511,-49.2646,14.764
-146.812,-110.92,174.944,-50.4977,23.8506
-155.959,-110.425,168.326,-51.6962,9.16039
-159.405,-116.465,161.772,-52.9916,6.95388
-155.105,-130.781,155.434,-54.5474,14.9478
-177.959,-130.4,148.766,-56.0644,22.8572
-191.35,-110.8,141.964,-57.1591,23.7377
-203.887,-107.5,135.047,-58.166,12.964
-215.472,-107.245,128.037,-59.1475,11.5878
-224.623,-120.519,120.983,-60.375,16.1226
-228.762,-135.291,113.988,-61.8733,15.3409
-233.35,-127.67,107.042,-63.1892,8.89548
-241.812,-130.37,100.065,-64.5328,8.8823
-267.668,-125.261,92.71,-65.7474,26.3559
-282.994,-115.194,85.1959,-66.7363,18.3366
-295.969,-106.704,77.5726,-67.5357,15.5058
-299.843,-115.94,70.0243,-68.5038,10.0156
-319.437,-106.731,62.2351,-69.2683,21.6502
-342.575,-81.5263,54.1389,-69.5135,34.2147
-354.138,-71.9037,45.9734,-69.5613,15.0432
-441.975,45.6738,45.4855,-69.446,146.764
-433.704,38.1113,35.9017,-67.2949,11.2072
-440.263,40,26.3784,-65.149,6.82551
-365.395,-83.59,25.9866,-65.1674,144.498
0.6375,39.93,25.9613,-65.0623,386.312
-312.649,-171.901,25.6227,-65.1692,378.181
-316.406,-165.774,18.7821,-67.1813,7.18716
-322.109,-159.586,11.9643,-69.0294,8.4152
-329.098,-150.059,5.14304,-70.65,11.8156
-330.284,-142.696,-1.56549,-72.0909,7.45791
-320.938,-138.139,-7.95294,-73.4118,10.3978
-309.225,-149.27,-13.9784,-74.929,16.1584
-337.312,-95.85,-14.3017,-74.9499,60.3538
-335.562,-80.19,-20.7269,-75.0547,15.7575
-318.75,-107,-26.6874,-75.6936,31.6452
-328.653,-70.4863,-32.7267,-75.5895,37.8328
-323.916,-64.55,-38.5504,-75.3687,7.59467
-325.671,-52.2863,-44.2929,-74.907,12.3886
-324.825,-48.6763,-49.9035,-74.3824,3.7078
-307.099,-53.9813,-55.0474,-73.9744,18.5028
-318.509,-23.6863,-60.3166,-72.9687,32.3724
-313.915,-13.1263,-65.3886,-71.7718,11.516
-435.204,209.05,-65.7584,-71.491,253.127
-305.905,23.075,-65.9985,-71.3964,226.506
-298.209,34.9787,-70.6427,-69.2689,14.1748
-298.209,48.3187,-75.1941,-66.9172,13.34
-298.7,54.9738,-79.6642,-64.4794,6.67319
-317.656,93.84,-84.424,-61.313,43.2425
-309.629,90.25,-88.9281,-58.2817,8.79323
-295.5,88.0312,-93.0595,-55.3555,14.3022
-390.875,255.025,-93.3573,-55.0451,192.31
-309.659,132.469,-93.5736,-54.8576,147.024
-314.093,144.935,-97.984,-50.8617,13.2311
-316.462,170.419,-102.354,-46.4361,25.5939
-313.88,178.375,-106.584,-41.9399,8.36448
-310.73,170.419,-110.667,-37.6927,8.55689
-331.287,217.84,-110.888,-37.4372,51.685
-323.552,223.6,-115.141,-32.2165,9.64405
-294.816,177.145,-115.321,-32.0071,54.6244
-265.916,173.66,-118.332,-27.8938,29.1094

View File

@ -0,0 +1,15 @@
clc;
clear;
% 读取数据文件
data = csvread('a3_out.txt');
figure;
for i = 1:length(data(:,1))
% 分别提取 x、y、xf 和 yf 列
x = data(1:i, 1);
y = data(1:i, 2);
xf = data(1:i, 3);
yf = data(1:i, 4);
%plot(x,y,'b+');
hold on;
plot(xf,yf,'r.');
end

View File

@ -0,0 +1,31 @@

Microsoft Visual Studio Solution File, Format Version 12.00
# Visual Studio Version 16
VisualStudioVersion = 16.0.32106.194
MinimumVisualStudioVersion = 10.0.40219.1
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "UWBFIlter", "UWBFIlter\UWBFIlter.vcxproj", "{1EE3EC3B-52C0-45F2-886D-B4BEF5B55C3F}"
EndProject
Global
GlobalSection(SolutionConfigurationPlatforms) = preSolution
Debug|x64 = Debug|x64
Debug|x86 = Debug|x86
Release|x64 = Release|x64
Release|x86 = Release|x86
EndGlobalSection
GlobalSection(ProjectConfigurationPlatforms) = postSolution
{1EE3EC3B-52C0-45F2-886D-B4BEF5B55C3F}.Debug|x64.ActiveCfg = Debug|x64
{1EE3EC3B-52C0-45F2-886D-B4BEF5B55C3F}.Debug|x64.Build.0 = Debug|x64
{1EE3EC3B-52C0-45F2-886D-B4BEF5B55C3F}.Debug|x86.ActiveCfg = Debug|Win32
{1EE3EC3B-52C0-45F2-886D-B4BEF5B55C3F}.Debug|x86.Build.0 = Debug|Win32
{1EE3EC3B-52C0-45F2-886D-B4BEF5B55C3F}.Release|x64.ActiveCfg = Release|x64
{1EE3EC3B-52C0-45F2-886D-B4BEF5B55C3F}.Release|x64.Build.0 = Release|x64
{1EE3EC3B-52C0-45F2-886D-B4BEF5B55C3F}.Release|x86.ActiveCfg = Release|Win32
{1EE3EC3B-52C0-45F2-886D-B4BEF5B55C3F}.Release|x86.Build.0 = Release|Win32
EndGlobalSection
GlobalSection(SolutionProperties) = preSolution
HideSolutionNode = FALSE
EndGlobalSection
GlobalSection(ExtensibilityGlobals) = postSolution
SolutionGuid = {84E6EAE7-D9EA-4986-8C9D-95A2E4002DA7}
EndGlobalSection
EndGlobal

View File

@ -0,0 +1,11 @@
<?xml version="1.0" encoding="utf-8"?>
<Project>
<ProjectOutputs>
<ProjectOutput>
<FullPath>D:\UWBLoc\Filter\UWBFIlter\Debug\UWBFIlter.exe</FullPath>
</ProjectOutput>
</ProjectOutputs>
<ContentFiles />
<SatelliteDlls />
<NonRecipeFileRefs />
</Project>

View File

@ -0,0 +1,2 @@
 main.cpp
UWBFIlter.vcxproj -> D:\UWBLoc\Filter\UWBFIlter\Debug\UWBFIlter.exe

View File

@ -0,0 +1,2 @@
PlatformToolSet=v142:VCToolArchitecture=Native32Bit:VCToolsVersion=14.29.30133:VCServicingVersionMFC=14.29.30136:VCServicingVersionCrtHeaders=14.29.30136:TargetPlatformVersion=10.0.20348.0:
Debug|Win32|D:\UWBLoc\Filter\UWBFIlter\|

View File

@ -0,0 +1,151 @@
<?xml version="1.0" encoding="utf-8"?>
<Project DefaultTargets="Build" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
<ItemGroup Label="ProjectConfigurations">
<ProjectConfiguration Include="Debug|Win32">
<Configuration>Debug</Configuration>
<Platform>Win32</Platform>
</ProjectConfiguration>
<ProjectConfiguration Include="Release|Win32">
<Configuration>Release</Configuration>
<Platform>Win32</Platform>
</ProjectConfiguration>
<ProjectConfiguration Include="Debug|x64">
<Configuration>Debug</Configuration>
<Platform>x64</Platform>
</ProjectConfiguration>
<ProjectConfiguration Include="Release|x64">
<Configuration>Release</Configuration>
<Platform>x64</Platform>
</ProjectConfiguration>
</ItemGroup>
<PropertyGroup Label="Globals">
<VCProjectVersion>16.0</VCProjectVersion>
<Keyword>Win32Proj</Keyword>
<ProjectGuid>{1ee3ec3b-52c0-45f2-886d-b4bef5b55c3f}</ProjectGuid>
<RootNamespace>UWBFIlter</RootNamespace>
<WindowsTargetPlatformVersion>10.0</WindowsTargetPlatformVersion>
</PropertyGroup>
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.Default.props" />
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'" Label="Configuration">
<ConfigurationType>Application</ConfigurationType>
<UseDebugLibraries>true</UseDebugLibraries>
<PlatformToolset>v142</PlatformToolset>
<CharacterSet>Unicode</CharacterSet>
</PropertyGroup>
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'" Label="Configuration">
<ConfigurationType>Application</ConfigurationType>
<UseDebugLibraries>false</UseDebugLibraries>
<PlatformToolset>v142</PlatformToolset>
<WholeProgramOptimization>true</WholeProgramOptimization>
<CharacterSet>Unicode</CharacterSet>
</PropertyGroup>
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|x64'" Label="Configuration">
<ConfigurationType>Application</ConfigurationType>
<UseDebugLibraries>true</UseDebugLibraries>
<PlatformToolset>v142</PlatformToolset>
<CharacterSet>Unicode</CharacterSet>
</PropertyGroup>
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|x64'" Label="Configuration">
<ConfigurationType>Application</ConfigurationType>
<UseDebugLibraries>false</UseDebugLibraries>
<PlatformToolset>v142</PlatformToolset>
<WholeProgramOptimization>true</WholeProgramOptimization>
<CharacterSet>Unicode</CharacterSet>
</PropertyGroup>
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.props" />
<ImportGroup Label="ExtensionSettings">
</ImportGroup>
<ImportGroup Label="Shared">
</ImportGroup>
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
</ImportGroup>
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
</ImportGroup>
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Debug|x64'">
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
</ImportGroup>
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Release|x64'">
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
</ImportGroup>
<PropertyGroup Label="UserMacros" />
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
<LinkIncremental>true</LinkIncremental>
</PropertyGroup>
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
<LinkIncremental>false</LinkIncremental>
</PropertyGroup>
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|x64'">
<LinkIncremental>true</LinkIncremental>
</PropertyGroup>
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|x64'">
<LinkIncremental>false</LinkIncremental>
</PropertyGroup>
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
<ClCompile>
<WarningLevel>Level3</WarningLevel>
<SDLCheck>true</SDLCheck>
<PreprocessorDefinitions>WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions)</PreprocessorDefinitions>
<ConformanceMode>true</ConformanceMode>
</ClCompile>
<Link>
<SubSystem>Console</SubSystem>
<GenerateDebugInformation>true</GenerateDebugInformation>
</Link>
</ItemDefinitionGroup>
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
<ClCompile>
<WarningLevel>Level3</WarningLevel>
<FunctionLevelLinking>true</FunctionLevelLinking>
<IntrinsicFunctions>true</IntrinsicFunctions>
<SDLCheck>true</SDLCheck>
<PreprocessorDefinitions>WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions)</PreprocessorDefinitions>
<ConformanceMode>true</ConformanceMode>
</ClCompile>
<Link>
<SubSystem>Console</SubSystem>
<EnableCOMDATFolding>true</EnableCOMDATFolding>
<OptimizeReferences>true</OptimizeReferences>
<GenerateDebugInformation>true</GenerateDebugInformation>
</Link>
</ItemDefinitionGroup>
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Debug|x64'">
<ClCompile>
<WarningLevel>Level3</WarningLevel>
<SDLCheck>true</SDLCheck>
<PreprocessorDefinitions>_DEBUG;_CONSOLE;%(PreprocessorDefinitions)</PreprocessorDefinitions>
<ConformanceMode>true</ConformanceMode>
</ClCompile>
<Link>
<SubSystem>Console</SubSystem>
<GenerateDebugInformation>true</GenerateDebugInformation>
</Link>
</ItemDefinitionGroup>
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Release|x64'">
<ClCompile>
<WarningLevel>Level3</WarningLevel>
<FunctionLevelLinking>true</FunctionLevelLinking>
<IntrinsicFunctions>true</IntrinsicFunctions>
<SDLCheck>true</SDLCheck>
<PreprocessorDefinitions>NDEBUG;_CONSOLE;%(PreprocessorDefinitions)</PreprocessorDefinitions>
<ConformanceMode>true</ConformanceMode>
</ClCompile>
<Link>
<SubSystem>Console</SubSystem>
<EnableCOMDATFolding>true</EnableCOMDATFolding>
<OptimizeReferences>true</OptimizeReferences>
<GenerateDebugInformation>true</GenerateDebugInformation>
</Link>
</ItemDefinitionGroup>
<ItemGroup>
<ClCompile Include="main.cpp" />
<ClCompile Include="UWBFilter.cpp" />
</ItemGroup>
<ItemGroup>
<ClInclude Include="UWBFilter.h" />
</ItemGroup>
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.targets" />
<ImportGroup Label="ExtensionTargets">
</ImportGroup>
</Project>

View File

@ -0,0 +1,30 @@
<?xml version="1.0" encoding="utf-8"?>
<Project ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
<ItemGroup>
<Filter Include="源文件">
<UniqueIdentifier>{4FC737F1-C7A5-4376-A066-2A32D752A2FF}</UniqueIdentifier>
<Extensions>cpp;c;cc;cxx;c++;cppm;ixx;def;odl;idl;hpj;bat;asm;asmx</Extensions>
</Filter>
<Filter Include="头文件">
<UniqueIdentifier>{93995380-89BD-4b04-88EB-625FBE52EBFB}</UniqueIdentifier>
<Extensions>h;hh;hpp;hxx;h++;hm;inl;inc;ipp;xsd</Extensions>
</Filter>
<Filter Include="资源文件">
<UniqueIdentifier>{67DA6AB6-F800-4c08-8B7A-83BB121AAD01}</UniqueIdentifier>
<Extensions>rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms</Extensions>
</Filter>
</ItemGroup>
<ItemGroup>
<ClCompile Include="main.cpp">
<Filter>源文件</Filter>
</ClCompile>
<ClCompile Include="UWBFilter.cpp">
<Filter>源文件</Filter>
</ClCompile>
</ItemGroup>
<ItemGroup>
<ClInclude Include="UWBFilter.h">
<Filter>头文件</Filter>
</ClInclude>
</ItemGroup>
</Project>

View File

@ -0,0 +1,4 @@
<?xml version="1.0" encoding="utf-8"?>
<Project ToolsVersion="Current" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
<PropertyGroup />
</Project>

View File

@ -0,0 +1,30 @@
#include "UWBFilter.h"
#include "math.h"
UWBFilter::UWBFilter() {
}
void UWBFilter::update(float& x, float& y,float& vo) {
if (initFlag == false) {
lastX = x;
lastY = y;
lastXf = x;
lastYf = y;
initFlag = true;
}
float d2 = (x - lastX) * (x - lastX) + (y - lastY) * (y - lastY);
lastX = x;
lastY = y;
// 判断速度是否有效遇到重复值速度为0
float v = d2 == 0 ? lastV : sqrtf(d2);
// 根据速度参数选择不同滤波器参数
float alpha = v < 50 ? 0.98f : 0.999f;
x = lastXf * alpha + (1 - alpha) * x;
y = lastYf * alpha + (1 - alpha) * y;
// 记录上一次的滤波值
lastXf = x;
lastYf = y;
lastV = v;
vo = v;
;}

View File

@ -0,0 +1,14 @@
#pragma once
class UWBFilter {
public:
UWBFilter();
void update(float& x, float& y, float& vo);
private:
float lastX;
float lastY;
float lastXf;
float lastYf;
float lastV = 0.0f;
int thres = 50;
bool initFlag = false;
};

View File

@ -0,0 +1,46 @@
#include <iostream>
#include <fstream>
#include <sstream>
#include <vector>
#include "UWBFilter.h"
struct Point {
float x;
float y;
};
int main() {
std::ifstream file("a3.txt"); // 假设数据保存在名为 data.txt 的文件中
std::ofstream fileOut("a3_out.txt");
std::vector<Point> points;
UWBFilter filter;
if (file.is_open() && fileOut.is_open()) {
std::string line;
// 逐行读取数据
while (std::getline(file, line)) {
std::stringstream ss(line);
Point p;
char delimiter;
// 从每行中读取 x 和 y 值,并用逗号分隔
if (ss >> p.x >> delimiter >> p.y) {
float xf = p.x;
float yf = p.y;
float v = 0.0f;
filter.update(xf, yf, v);
fileOut << p.x << "," << p.y << "," << xf << "," << yf << "," << v << std::endl;
}
}
file.close();
fileOut.close();
}
else {
std::cerr << "无法打开文件!" << std::endl;
return 1;
}
// 打印读取到的数据
for (const auto& point : points) {
std::cout << "x: " << point.x << ", y: " << point.y << std::endl;
}
return 0;
}

View File

@ -0,0 +1,13 @@
d:\uwbloc\filter\uwbfilter\uwbfilter\x64\debug\vc142.pdb
d:\uwbloc\filter\uwbfilter\uwbfilter\x64\debug\vc142.idb
d:\uwbloc\filter\uwbfilter\uwbfilter\x64\debug\uwbfilter.obj
d:\uwbloc\filter\uwbfilter\uwbfilter\x64\debug\main.obj
d:\uwbloc\filter\uwbfilter\x64\debug\uwbfilter.exe
d:\uwbloc\filter\uwbfilter\uwbfilter\x64\debug\uwbfilter.ilk
d:\uwbloc\filter\uwbfilter\x64\debug\uwbfilter.pdb
d:\uwbloc\filter\uwbfilter\uwbfilter\x64\debug\uwbfilter.tlog\cl.command.1.tlog
d:\uwbloc\filter\uwbfilter\uwbfilter\x64\debug\uwbfilter.tlog\cl.read.1.tlog
d:\uwbloc\filter\uwbfilter\uwbfilter\x64\debug\uwbfilter.tlog\cl.write.1.tlog
d:\uwbloc\filter\uwbfilter\uwbfilter\x64\debug\uwbfilter.tlog\link.command.1.tlog
d:\uwbloc\filter\uwbfilter\uwbfilter\x64\debug\uwbfilter.tlog\link.read.1.tlog
d:\uwbloc\filter\uwbfilter\uwbfilter\x64\debug\uwbfilter.tlog\link.write.1.tlog

View File

@ -0,0 +1,11 @@
<?xml version="1.0" encoding="utf-8"?>
<Project>
<ProjectOutputs>
<ProjectOutput>
<FullPath>D:\UWBLoc\Filter\UWBFIlter\x64\Debug\UWBFIlter.exe</FullPath>
</ProjectOutput>
</ProjectOutputs>
<ContentFiles />
<SatelliteDlls />
<NonRecipeFileRefs />
</Project>

View File

@ -0,0 +1,4 @@
 main.cpp
UWBFilter.cpp
正在生成代码...
UWBFIlter.vcxproj -> D:\UWBLoc\Filter\UWBFIlter\x64\Debug\UWBFIlter.exe

View File

@ -0,0 +1,2 @@
PlatformToolSet=v142:VCToolArchitecture=Native32Bit:VCToolsVersion=14.29.30133:VCServicingVersionMFC=14.29.30136:VCServicingVersionCrtHeaders=14.29.30136:TargetPlatformVersion=10.0.20348.0:
Debug|x64|D:\UWBLoc\Filter\UWBFIlter\|

Some files were not shown because too many files have changed in this diff Show More