Merge remote-tracking branch 'origin/master'

This commit is contained in:
xinyang
2019-08-06 14:14:13 +08:00
20 changed files with 41326 additions and 17923 deletions

View File

@@ -92,8 +92,9 @@ void ArmorFinder::run(cv::Mat &src) {
stateStandBy();
}
end:
antiTop();
// antiTop();
if(target_box.rect != cv::Rect2d())
sendBoxPosition(0);
if (show_armor_box) { // 根据条件显示当前目标装甲板
showArmorBox("box", src, target_box);
cv::waitKey(1);

View File

@@ -27,10 +27,10 @@ static bool isValidLightBlob(const std::vector<cv::Point> &contour, const cv::Ro
// 此函数可以有性能优化.
static uint8_t get_blob_color(const cv::Mat &src, const cv::RotatedRect &blobPos) {
auto region = blobPos.boundingRect();
region.x -= fmax(2, region.width * 0.1);
region.y -= fmax(2, region.height * 0.05);
region.width += 2 * fmax(2, region.width * 0.1);
region.height += 2 * fmax(2, region.height * 0.05);
region.x -= fmax(3, region.width * 0.1);
region.y -= fmax(3, region.height * 0.05);
region.width += 2 * fmax(3, region.width * 0.1);
region.height += 2 * fmax(3, region.height * 0.05);
region &= cv::Rect(0, 0, src.cols, src.rows);
cv::Mat roi = src(region);
int red_cnt = 0, blue_cnt = 0;

View File

@@ -30,10 +30,10 @@ using namespace std;
McuData mcu_data = { // 单片机端回传结构体
0, // 当前云台yaw角
0, // 当前云台pitch角
BIG_ENERGY_STATE, // 当前状态,自瞄-大符-小符
ARMOR_STATE, // 当前状态,自瞄-大符-小符
0, // 云台角度标记位
1, // 是否启用数字识别
ENEMY_RED, // 敌方颜色
ENEMY_BLUE, // 敌方颜色
0, // 能量机关x轴补偿量
0, // 能量机关y轴补偿量
};
@@ -63,11 +63,11 @@ int main(int argc, char *argv[]) {
while (true) {
// 打开视频源
if (from_camera) {
video_gimbal = new CameraWrapper(ARMOR_CAMERA_GAIN, 2/*, "armor"*/);
video_chassis = new CameraWrapper(ENERGY_CAMERA_GAIN, 2/*, "energy"*/);
video_gimbal = new CameraWrapper(ARMOR_CAMERA_EXPOSURE, ARMOR_CAMERA_GAIN, 2/*, "armor"*/);
video_chassis = new CameraWrapper(ENERGY_CAMERA_EXPOSURE, ENERGY_CAMERA_GAIN, 2/*, "energy"*/);
} else {
video_gimbal = new VideoWrapper("/home/sun/项目/RM_auto-aim/gimbal_video/57.avi");
video_chassis = new VideoWrapper("/home/sun/项目/RM_auto-aim/gimbal_video/57.avi");
video_gimbal = new VideoWrapper(PROJECT_DIR"/26.avi");
video_chassis = new VideoWrapper(PROJECT_DIR"/26.avi");
}
if (video_gimbal->init()) {
LOGM("video_gimbal source initialization successfully.");
@@ -100,7 +100,7 @@ int main(int argc, char *argv[]) {
destroyAllWindows();
if (from_camera) {
delete video_gimbal;
video_gimbal = new CameraWrapper(ENERGY_CAMERA_GAIN, 2/*, "armor"*/);
video_gimbal = new CameraWrapper(ENERGY_CAMERA_EXPOSURE, ENERGY_CAMERA_GAIN, 2/*, "armor"*/);
if (video_gimbal->init()) {
LOGM("video_gimbal source initialization successfully.");
} else {
@@ -122,15 +122,15 @@ int main(int argc, char *argv[]) {
if (!from_camera) extract(gimbal_src, chassis_src);
if (save_video) saveVideos(gimbal_src, chassis_src);//保存视频
if (show_origin) showOrigin(gimbal_src, chassis_src);//显示原始图像
// energy.runBig(gimbal_src, chassis_src);
energy.runBig(gimbal_src);
energy.runBig(gimbal_src, chassis_src);
// energy.runBig(gimbal_src);
} else if (mcu_data.state == SMALL_ENERGY_STATE) {
if (last_state != SMALL_ENERGY_STATE) {
LOGM(STR_CTR(WORD_GREEN, "Start Small Energy!"));
destroyAllWindows();
if (from_camera) {
delete video_gimbal;
video_gimbal = new CameraWrapper(ENERGY_CAMERA_GAIN, 2/*, "armor"*/);
video_gimbal = new CameraWrapper(ENERGY_CAMERA_EXPOSURE, ENERGY_CAMERA_GAIN, 2/*, "armor"*/);
if (video_gimbal->init()) {
LOGM("video_gimbal source initialization successfully.");
} else {
@@ -154,7 +154,7 @@ int main(int argc, char *argv[]) {
destroyAllWindows();
if (from_camera) {
delete video_gimbal;
video_gimbal = new CameraWrapper(ARMOR_CAMERA_GAIN, 2/*, "armor"*/);
video_gimbal = new CameraWrapper(ARMOR_CAMERA_EXPOSURE, ARMOR_CAMERA_GAIN, 2/*, "armor"*/);
if (video_gimbal->init()) {
LOGM("video_gimbal source initialization successfully.");
} else {
@@ -164,7 +164,7 @@ int main(int argc, char *argv[]) {
}
last_state = mcu_data.state;
CNT_TIME(STR_CTR(WORD_GREEN, "read img"), {
if (!checkReconnect(video_gimbal->read(gimbal_src))) continue;
if(!checkReconnect(video_gimbal->read(gimbal_src))) continue;
});
#ifdef GIMBAL_FLIP_MODE
flip(gimbal_src, gimbal_src, GIMBAL_FLIP_MODE);

View File

@@ -41,8 +41,9 @@ private:
RoundQueue<cv::Mat, 2> src_queue;
public:
int gain;
int exposure;
CameraWrapper(int gain, int camera_mode=1, const std::string &n="NULL");
CameraWrapper(int exposure, int gain, int camera_mode=1, const std::string &n="NULL");
~CameraWrapper() final;
bool init() final;

View File

@@ -8,8 +8,12 @@
#warning "Without config.h"
#endif
#ifndef CAMERA_EXPOSURE
#define CAMERA_EXPOSURE (10)
#ifndef ARMOR_CAMERA_EXPOSURE
#define ARMOR_CAMERA_EXPOSURE (10)
#endif
#ifndef ENERGY_CAMERA_EXPOSURE
#define ENERGY_CAMERA_EXPOSURE (10)
#endif
#ifndef CAMERA_RED_GAIN

View File

@@ -77,14 +77,16 @@ cv::VideoWriter initVideoWriter(const std::string &filename_prefix) {
bool checkReconnect(bool is_camera_0_connect, bool is_camera_1_connect) {
if (!is_camera_0_connect) {
int curr_gain = ((CameraWrapper* )video_gimbal)->gain;
int curr_exposure = ((CameraWrapper* )video_gimbal)->exposure;
delete video_gimbal;
video_gimbal = new CameraWrapper(curr_gain, 0/*, "armor"*/);
video_gimbal = new CameraWrapper(curr_exposure, curr_gain, 0/*, "armor"*/);
is_camera_0_connect = video_gimbal->init();
}
if (!is_camera_1_connect) {
int curr_gain = ((CameraWrapper* )video_gimbal)->gain;
int curr_exposure = ((CameraWrapper* )video_gimbal)->exposure;
delete video_chassis;
video_chassis = new CameraWrapper(curr_gain, 0/*, "energy"*/);
video_chassis = new CameraWrapper(curr_exposure, curr_gain, 0/*, "energy"*/);
is_camera_1_connect = video_chassis->init();
}
return is_camera_0_connect && is_camera_1_connect;
@@ -93,8 +95,9 @@ bool checkReconnect(bool is_camera_0_connect, bool is_camera_1_connect) {
bool checkReconnect(bool is_camera_connect) {
if (!is_camera_connect) {
int curr_gain = ((CameraWrapper* )video_gimbal)->gain;
int curr_exposure = ((CameraWrapper* )video_gimbal)->exposure;
delete video_gimbal;
video_gimbal = new CameraWrapper(curr_gain, 0/*, "armor"*/);
video_gimbal = new CameraWrapper(curr_exposure, curr_gain, 0/*, "armor"*/);
is_camera_connect = video_gimbal->init();
}
return is_camera_connect;

View File

@@ -11,7 +11,7 @@
using namespace std;
using namespace cv;
CameraWrapper::CameraWrapper(int gain, int camera_mode, const std::string &n) :
CameraWrapper::CameraWrapper(int exposure, int gain, int camera_mode, const std::string &n) :
name(n),
init_done(false),
mode(camera_mode),
@@ -20,7 +20,8 @@ CameraWrapper::CameraWrapper(int gain, int camera_mode, const std::string &n) :
iplImage(nullptr),
rgb_buffer(nullptr),
channel(3),
gain(gain){
gain(gain),
exposure(exposure){
}
void cameraCallback(CameraHandle hCamera, BYTE *pFrameBuffer, tSdkFrameHead* pFrameHead,PVOID pContext){
@@ -85,7 +86,7 @@ bool CameraWrapper::init() {
CameraReadParameterFromFile(h_camera, PROJECT_DIR"/others/MV-UB31-Group0.config");
CameraLoadParameter(h_camera, PARAMETER_TEAM_A);
CameraSetAeState(h_camera, false);
CameraSetExposureTime(h_camera, CAMERA_EXPOSURE * 1000);
CameraSetExposureTime(h_camera, exposure * 1000);
CameraSetAnalogGain(h_camera, gain);
#endif
double t;

View File

@@ -8,8 +8,10 @@ import forward
import cv2
import numpy as np
import mvsdk
print("Finish!")
def save_kernal(fp, val):
print(val.shape[2], file=fp)
print(val.shape[3], file=fp)
@@ -49,24 +51,24 @@ def save_para(folder, paras, names, info):
fp.close()
STEPS = 50000
BATCH = 30
LEARNING_RATE_BASE = 0.0005
STEPS = 100000
BATCH = 40
LEARNING_RATE_BASE = 0.0002
LEARNING_RATE_DECAY = 0.99
MOVING_AVERAGE_DECAY = 0.99
def train(dataset, show_bar=False):
x = tf.placeholder(tf.float32, [None, generate.SRC_ROWS, generate.SRC_COLS, generate.SRC_CHANNELS])
y_= tf.placeholder(tf.float32, [None, forward.OUTPUT_NODES])
y_ = tf.placeholder(tf.float32, [None, forward.OUTPUT_NODES])
keep_rate = tf.placeholder(tf.float32)
nodes, vars, vars_name = forward.forward(x, 0.01)
nodes, vars, vars_name = forward.forward(x, 0.01, keep_rate)
y = nodes[-1]
ce = tf.nn.sparse_softmax_cross_entropy_with_logits(logits=y, labels=tf.argmax(y_, 1))
# ce = tf.nn.weighted_cross_entropy_with_logits(logits=y, labels=tf.argmax(y_, 1), pos_weight=1)
# ce = tf.nn.weighted_cross_entropy_with_logits(logits=y, labels=tf.argmax(y_, 1), pos_weight=1)
cem = tf.reduce_mean(ce)
loss= cem + tf.add_n(tf.get_collection("losses"))
loss = cem + tf.add_n(tf.get_collection("losses"))
global_step = tf.Variable(0, trainable=False)
learning_rate = tf.train.exponential_decay(
@@ -92,31 +94,33 @@ def train(dataset, show_bar=False):
bar = tqdm(range(STEPS), ascii=True, dynamic_ncols=True)
for i in bar:
images_samples, labels_samples = dataset.sample_train_sets(BATCH)
images_samples, labels_samples = dataset.sample_train_sets(BATCH, 0.03)
_, loss_value, step = sess.run(
[train_op, loss, global_step],
feed_dict={x: images_samples, y_: labels_samples, keep_rate:0.3}
feed_dict={x: images_samples, y_: labels_samples, keep_rate: 0.3}
)
if step % 500 == 0:
test_images, test_labels = dataset.sample_test_sets(6000)
test_acc, output = sess.run([accuracy, y], feed_dict={x: test_images, y_: test_labels, keep_rate:1.0})
test_images, test_labels = dataset.sample_test_sets(10000)
test_acc, output = sess.run([accuracy, y],
feed_dict={x: test_images, y_: test_labels, keep_rate: 1.0})
output = np.argmax(output, axis=1)
real = np.argmax(test_labels, axis=1)
print("=============test-set===============")
for n in range(forward.OUTPUT_NODES):
print("label: %d, precise: %f, recall: %f" %
(n, np.mean(real[output==n]==n), np.mean(output[real==n]==n)))
(n, np.mean(real[output == n] == n), np.mean(output[real == n] == n)))
train_images, train_labels = dataset.sample_train_sets(6000)
train_acc, output = sess.run([accuracy, y], feed_dict={x: train_images, y_: train_labels, keep_rate:1.0})
train_images, train_labels = dataset.sample_train_sets(10000)
train_acc, output = sess.run([accuracy, y],
feed_dict={x: train_images, y_: train_labels, keep_rate: 1.0})
output = np.argmax(output, axis=1)
real = np.argmax(train_labels, axis=1)
print("=============train-set===============")
for n in range(forward.OUTPUT_NODES):
print("label: %d, precise: %f, recall: %f" %
(n, np.mean(real[output==n]==n), np.mean(output[real==n]==n)))
(n, np.mean(real[output == n] == n), np.mean(output[real == n] == n)))
print("\n")
if train_acc >= 0.99 and test_acc >= 0.99:
vars_val = sess.run(vars)
@@ -131,8 +135,8 @@ def train(dataset, show_bar=False):
# pred = sess.run(y, feed_dict={x: test_images, keep_rate:1.0})
# nodes_val = sess.run(nodes, feed_dict={x:test_images})
# return vars_val, nodes_val
# nodes_val = sess.run(nodes, feed_dict={x:test_images})
# return vars_val, nodes_val
DevList = mvsdk.CameraEnumerateDevice()
nDev = len(DevList)
if nDev < 1:
@@ -150,7 +154,7 @@ def train(dataset, show_bar=False):
try:
hCamera = mvsdk.CameraInit(DevInfo, -1, -1)
except mvsdk.CameraException as e:
print("CameraInit Failed({}): {}".format(e.error_code, e.message) )
print("CameraInit Failed({}): {}".format(e.error_code, e.message))
return
# 获取相机特性描述
@@ -192,24 +196,25 @@ def train(dataset, show_bar=False):
# 把pFrameBuffer转换成opencv的图像格式以进行后续算法处理
frame_data = (mvsdk.c_ubyte * FrameHead.uBytes).from_address(pFrameBuffer)
frame = np.frombuffer(frame_data, dtype=np.uint8)
frame = frame.reshape((FrameHead.iHeight, FrameHead.iWidth, 1 if FrameHead.uiMediaType == mvsdk.CAMERA_MEDIA_TYPE_MONO8 else 3) )
frame = frame.reshape((FrameHead.iHeight, FrameHead.iWidth,
1 if FrameHead.uiMediaType == mvsdk.CAMERA_MEDIA_TYPE_MONO8 else 3))
frame = cv2.resize(frame, (640,480), interpolation = cv2.INTER_LINEAR)
frame = cv2.resize(frame, (640, 480), interpolation=cv2.INTER_LINEAR)
cv2.imshow("Press q to end", frame)
if (cv2.waitKey(1)&0xFF) == ord(' '):
if (cv2.waitKey(1) & 0xFF) == ord(' '):
roi = cv2.selectROI("roi", frame)
roi = frame[roi[1]:roi[1]+roi[3], roi[0]:roi[0]+roi[2]]
roi = frame[roi[1]:roi[1] + roi[3], roi[0]:roi[0] + roi[2]]
print(roi)
cv2.imshow("box", roi)
image = cv2.resize(roi, (48, 36))
image = image.astype(np.float32) / 255.0
out = sess.run(y, feed_dict={x:[image]})
out = sess.run(y, feed_dict={x: [image]})
print(out)
print(np.argmax(out))
except mvsdk.CameraException as e:
if e.error_code != mvsdk.CAMERA_STATUS_TIME_OUT:
print("CameraGetImageBuffer failed({}): {}".format(e.error_code, e.message) )
print("CameraGetImageBuffer failed({}): {}".format(e.error_code, e.message))
# 关闭相机
mvsdk.CameraUnInit(hCamera)

View File

@@ -35,16 +35,16 @@ CONV1_OUTPUT_CHANNELS = 4
CONV2_KERNAL_SIZE = 3
# 第二层卷积输出通道数
CONV2_OUTPUT_CHANNELS = 6
CONV2_OUTPUT_CHANNELS = 8
# 第三层卷积核大小
CONV3_KERNAL_SIZE = 3
# 第三层卷积输出通道数
CONV3_OUTPUT_CHANNELS = 8
CONV3_OUTPUT_CHANNELS = 16
# 第一层全连接宽度
FC1_OUTPUT_NODES = 50
FC1_OUTPUT_NODES = 60
# 第二层全连接宽度(输出标签类型数)
FC2_OUTPUT_NODES = 15
@@ -113,4 +113,3 @@ def forward(x, regularizer=None, keep_rate=tf.constant(1.0)):
nodes.extend([fc2])
return nodes, vars, vars_name

View File

@@ -4,6 +4,7 @@ import cv2
import random
from tqdm import tqdm
from forward import OUTPUT_NODES
# 原图像行数
SRC_ROWS = 36
@@ -40,38 +41,64 @@ class DataSet:
files = os.listdir(dir)
for file in tqdm(files, postfix={"loading id": i}, dynamic_ncols=True):
if file[-3:] == "jpg":
sample = self.file2nparray("%s/%s" % (dir, file))
label = self.id2label(i)
if random.random() > 0.7:
self.train_samples.append(self.file2nparray("%s/%s" % (dir, file)))
self.train_labels.append(self.id2label(i))
self.train_samples.append(sample)
self.train_labels.append(label)
if i == 0:
tmp = sample.copy()
tmp = tmp[:, :, ::-1]
self.train_samples.append(tmp)
self.train_labels.append(label)
else:
self.test_samples.append(self.file2nparray("%s/%s" % (dir, file)))
self.test_labels.append(self.id2label(i))
tmp = sample.copy()
tmp = 1.2 * tmp
tmp = np.where(tmp > 1, 1, tmp)
tmp = np.where(tmp < 0, 0, tmp)
self.train_samples.append(tmp)
self.train_labels.append(label)
tmp = sample.copy()
tmp = 0.8 * tmp
tmp = np.where(tmp > 1, 1, tmp)
tmp = np.where(tmp < 0, 0, tmp)
self.train_samples.append(tmp)
self.train_labels.append(label)
else:
self.test_samples.append(sample)
self.test_labels.append(label)
self.train_samples = np.array(self.train_samples)
self.train_labels = np.array(self.train_labels)
self.test_samples = np.array(self.test_samples)
self.test_labels = np.array(self.test_labels)
return sets
def sample_train_sets(self, length):
def sample_train_sets(self, length, std=0.0):
samples = []
labels = []
for i in range(length):
id = random.randint(0, len(self.train_samples)-1)
id = random.randint(0, len(self.train_samples) - 1)
samples.append(self.train_samples[id])
labels.append(self.train_labels[id])
return np.array(samples), np.array(labels)
samples = np.array(samples).copy()
samples += np.random.normal(0, std, samples.shape)
labels = np.array(labels)
return samples, labels
def sample_test_sets(self, length):
def sample_test_sets(self, length, std=0.0):
samples = []
labels = []
for i in range(length):
id = random.randint(0, len(self.test_samples)-1)
id = random.randint(0, len(self.test_samples) - 1)
samples.append(self.test_samples[id])
labels.append(self.test_labels[id])
return np.array(samples), np.array(labels)
samples = np.array(samples).copy()
samples += np.random.normal(0, std, samples.shape)
labels = np.array(labels)
return samples, labels
def all_train_sets(self):
def all_train_sets(self, std=0.0):
return self.train_samples[:], self.train_labels[:]
def all_test_sets(self):
def all_test_sets(self, std=0.0):
return self.test_samples[:], self.test_labels[:]

View File

@@ -1,5 +1,5 @@
4
-0.028037319
0.5437552
0.26716635
0.15804483
0.021338634
-0.28292254
0.39307028
0.46493095

View File

@@ -2,303 +2,303 @@
4
5
5
0.2558705
0.50322264
0.5455292
0.3266633
0.45495397
0.33181077
0.4608274
0.44561535
0.30626073
0.5907795
0.45085132
0.32935262
0.33333394
0.42217836
0.47149
0.26239944
0.106058985
0.4186091
0.33606878
0.47154978
0.29413304
0.2689295
0.043931372
0.41913906
0.3930859
-0.42042395
-0.19382745
-0.37871224
-0.36034295
-0.35385096
-0.13182718
-0.15764016
-0.18180493
-0.35480255
-0.38093758
-0.26962438
-0.13433722
-0.11590976
-0.12100729
-0.41767576
-0.088450246
-0.15360384
-0.21754275
-0.33203712
-0.36672434
-0.33835274
-0.09806653
-0.25720394
-0.48649773
-0.28400043
0.015362165
0.17902431
0.34508342
0.30716935
0.40274766
0.14824653
0.3363854
0.61393374
0.61485726
0.185212
0.27937973
0.4085319
0.56713074
0.50924385
0.14822921
-0.11108435
0.1610854
0.2802524
0.04015192
0.08895228
-0.19824773
-0.06844609
-0.069947205
-0.21471545
-0.21651222
-0.28975108
-0.36048082
-0.121744774
-0.32950944
-0.2776884
-0.38737568
-0.09360009
-0.116772
-0.2323865
-0.3063033
-0.09292303
-0.120976545
-0.098381124
-0.13898924
-0.24542217
-0.018138783
0.1710496
0.116988935
-0.30227587
-0.25962535
-0.20448786
-0.0741184
-0.021265341
-0.21863441
-0.24914841
0.3989018
0.38929248
0.24901842
0.28578317
0.35204405
0.21083018
0.30775398
0.17769343
0.24103095
0.43094385
0.24827914
0.12439884
0.11712248
0.3559909
0.16364971
0.038071744
0.13404451
0.12091028
-0.023739764
0.08232509
-0.0009516679
0.15716548
-0.10213259
0.0639761
-0.10133095
-0.009949305
0.09284781
0.40186858
0.25586432
0.14342904
0.18849348
0.32841587
0.3101156
0.4123818
0.081568226
0.27615616
0.34650272
0.5694975
0.23792551
0.29921243
0.33980817
0.49298054
0.60243934
0.42826438
0.27227885
0.1948353
0.3062418
0.46926793
0.38606012
0.13854483
1.1108605
1.6619372
2.0544205
1.9469278
1.4682909
1.3129491
2.1375504
2.6406689
2.372072
1.4637381
1.306143
2.2453067
2.5116432
2.3163383
1.5179764
1.1999305
1.7840445
2.1370907
1.8682098
1.1948502
0.7644319
1.183056
1.2842283
1.0330013
0.5353385
0.357544
0.4590763
0.57521755
0.40281096
0.15203553
0.66836417
0.83691925
1.0917046
0.85563093
0.4185427
0.8069128
1.1880662
1.2418958
0.98703665
0.45376477
0.8052862
1.1458472
1.0837129
0.8163929
0.5508064
0.84074473
1.0375632
1.0029732
0.73068154
0.4793337
-0.08648754
0.05313617
0.055096295
-0.03580858
-0.14844808
-0.21981032
0.0398141
-0.20938458
-0.21056286
-0.19792278
-0.06431722
-0.11274485
-0.13580588
-0.14901595
-0.06539131
-0.1703085
-0.044613708
-0.057758514
-0.2657268
-0.29268163
-0.2251643
-0.25461197
-0.28155822
-0.32777157
-0.3724289
0.16466168
0.44934547
0.43256435
0.47452745
0.3779059
0.20698643
0.52107
0.30781397
0.4135147
0.29526445
0.25912467
0.54579914
0.4920371
0.43895373
0.38483474
0.33639383
0.47148314
0.5128957
0.5233807
0.34624586
0.25116408
0.44631884
0.48539376
0.2042739
0.40311766
0.10143137
0.8512386
1.06337
0.82065773
0.22343788
0.51960915
1.0729233
1.5161965
1.220796
0.4743648
0.6052472
1.3462025
1.4488021
1.060846
0.3372449
0.678654
0.9629113
0.96115077
0.70128
0.17687131
0.20191273
0.5066497
0.54581857
0.121072926
-0.21051502
0.15686111
0.14152882
0.56596214
0.36766517
0.07481751
0.45787486
0.58694565
0.58544177
0.4505106
0.32433945
0.6037763
0.8595476
1.0671577
0.9353241
0.4558103
0.6039449
1.1056548
1.0452515
0.5983469
0.4096005
0.46692336
0.82347125
0.8806483
0.70173585
0.1955107
-0.13702177
0.21050254
0.36467823
0.5402022
0.40832496
0.1387463
0.19035818
0.5167714
0.4201423
0.5083453
-0.051313818
0.3746486
0.63895
0.63608116
0.5083911
0.030827409
0.27007273
0.47528267
0.48452747
0.34628776
-0.012611773
0.14452507
0.24958582
0.24960107
0.09575767
0.4102461
0.16927694
0.25459746
0.14307313
0.22898436
0.27788675
0.18775325
0.17099449
0.29020998
0.12541296
0.24403335
0.20092988
0.2530348
0.33398342
0.21587689
0.27797526
0.18172115
0.29734236
0.3033162
0.16939764
0.34889936
0.48381668
0.48425403
0.3000259
0.25757793
0.11239407
0.386269
0.37761775
0.3539963
0.14623448
0.38261685
0.27638507
0.2794403
0.40329304
0.33892003
0.24993245
0.37628546
0.33176056
0.50890356
0.2852119
0.22748284
0.39088395
0.4474231
0.39215663
0.28798044
0.17954169
0.42095885
0.3309427
0.39483225
0.35767367
-0.34148782
0.02509864
0.25426164
0.15086658
-0.057787858
-0.2226174
0.24070105
0.27239412
0.37470704
0.1674131
0.09444013
0.27578765
0.35690555
0.28290647
0.12817492
0.03777765
0.09609396
0.3188331
0.23712997
0.13440847
-0.25731155
0.04675058
0.09360328
-0.02120951
-0.06166972
0.060209647
0.5212034
0.6552245
1.1144388
0.87935585
0.24459931
0.82035065
1.1500704
1.2405574
1.1069012
0.18140063
0.8443062
1.2205642
1.1933382
0.90612733
0.32195792
0.6922394
1.0292921
1.0286875
0.94453853
0.24980143
0.5049856
0.74141055
0.7709616
0.5752724
0.17445572
0.07466022
-0.015276491
-0.04395921
-0.008553515
0.029532298
0.06765997
0.03481855
0.04099438
-0.044199117
0.16554591
0.06800105
-0.03995652
-0.006857331
0.075305216
0.3299388
0.11230784
0.20430015
0.039782282
0.111880876
0.13587818
0.1557568
0.16976745
0.14694355
0.32170033
-0.18491521
-0.15177341
0.035023104
0.048158385
0.29693007
-0.006829154
-0.046136864
0.1754336
0.24777764
0.2627956
0.13168007
-0.019214094
0.24687423
0.2204638
0.19275916
0.18035437
0.06386187
0.37380666
0.5433795
0.376532
0.20183952
0.3305568
0.33506978
0.43323225
0.3904595
0.33164555
0.74478495
1.172562
1.0576042
0.67135817
0.69610703
1.0034271
1.1407355
1.1464756
0.8193199
0.8561313
1.1586075
1.4729795
1.2343186
0.91004986
0.5244973
1.1102248
1.1765453
0.95950526
0.68363196
0.4048567
0.711899
0.9118936
0.52612954
0.39844343
-0.24287723
-0.052871097
0.07779769
0.11068013
0.1380818
-0.22056513
0.09362486
0.24791956
0.4390582
0.39413136
0.05775401
0.21399756
0.37228948
0.46872202
0.2922827
-0.10300668
0.03232777
0.34301633
0.29448983
0.044470448
-0.19424956
0.073454
-0.07377538
-0.01566619
-0.2193558
-0.48625758
-0.38693368
-0.51900584
-0.33943936
-0.28173432
-0.4239597
-0.43534985
-0.3587125
-0.33114514
-0.41164148
-0.44184446
-0.37156865
-0.26118872
-0.27542785
-0.2835131
-0.27856454
-0.30060688
-0.30000862
-0.26170778
-0.050582133
-0.17061539
-0.06258438
-0.31230104
-0.05868557
-0.16282676
-0.19877611
-0.41529313
-0.2597882
-0.29055542
-0.24465893
-0.37368765
-0.2763039
-0.16017292
-0.15159445
-0.09162989
-0.08486519
-0.214406
0.036507495
-0.18162069
-0.12156283
0.13781281
0.14959772
0.13058542
-0.04205288
-0.025140587
-0.031447563
-0.023655139
0.16892198
0.24700916
-0.05444677
0.4252524
1.0224841
1.0721366
1.0220312
0.62805945
0.60496604
1.2682245
1.3119446
1.2881455
0.93665457
0.7735541
1.3761095
1.3804561
1.3370488
0.932327
0.8111979
0.8535967
1.2361982
0.90493304
0.70505273
0.48489514
0.7006285
0.74297637
0.76787454
0.35748747

View File

@@ -1,7 +1,9 @@
6
0.7724807
-0.87169737
-0.42373934
1.2762932
0.41549298
-0.471356
8
-0.552405
-0.26979932
0.94369894
-0.000667131
0.34170008
0.34912753
1.0474143
-0.39599916

View File

@@ -1,220 +1,292 @@
4
6
8
3
3
-0.48382398
-0.36632606
-0.5114979
-0.14837296
-0.44867024
-0.4505499
-0.35961452
-0.28533116
-0.25498483
0.21828032
0.40261173
0.4014606
0.4331948
0.57971007
0.48511884
0.4658404
0.23746017
0.25643173
-0.42512512
-0.32099026
-0.4071419
-0.07042966
-0.18999289
-0.41244265
-0.05782267
-0.26706457
-0.39842066
-0.42635453
-0.54127145
-0.50406104
-0.2970212
-0.2382909
-0.373955
-0.26274928
0.09654497
0.0068873395
0.4851344
0.71676046
0.83653075
0.36806846
0.59301347
0.43608147
0.26763174
0.24044617
0.3138616
0.32284674
0.48771864
0.47890294
0.59924245
0.58470404
0.66103566
0.4588577
0.66345775
0.5417458
0.33620733
0.6311169
0.5712364
0.27047473
0.5663411
0.62967324
0.23675068
0.18819211
0.26856497
-0.24069026
0.06490354
-0.20222004
0.12556747
-0.081858225
-0.14404371
0.15644343
0.0056566484
-0.27573076
0.6260534
0.6114578
0.4143709
0.78654826
0.6670694
0.3971862
0.88891
0.7200758
0.4331128
0.5375012
0.69176656
0.5500048
0.76812154
0.8269794
1.0226717
0.521159
0.94419754
0.90338296
-0.037811022
0.11793418
-0.09947335
0.021074628
-0.15378062
-0.18899523
-0.21934026
-0.32867467
-0.4491826
0.17542738
0.22719054
-0.14938504
0.34901783
0.23809595
-0.29363006
0.14916919
0.1632361
-0.4462076
0.054292772
0.19464755
0.17956488
0.07731212
0.19792339
0.30400968
-0.039353892
0.14735414
0.18343678
0.23884599
0.30334124
0.21813673
0.12249429
0.38291413
0.22569945
0.25905365
0.33474848
0.0037524912
0.30396467
0.1846092
-0.121808626
0.7777901
0.397566
0.16061927
0.7874323
0.28439802
0.02147841
-0.14355433
0.30293295
0.046388533
0.19284728
0.61074996
0.4691993
0.35759884
0.6659188
0.45006895
0.22897986
0.15777227
0.3959882
0.16480199
0.09506794
0.072772376
-0.15479131
-0.025542457
0.07265022
0.26197845
0.46316504
0.08801226
0.45165384
0.68206656
0.201606
0.49978983
0.38383794
0.08902087
0.11398645
0.34106824
0.19092785
0.096165456
0.31517446
0.39403793
-0.12153064
-0.044383097
0.21368785
0.057617243
0.2975022
0.2852436
0.37886962
0.24867283
0.037312325
0.26485252
0.05155589
-0.04473265
0.55817014
0.46386358
0.1817731
0.7077902
0.6132932
0.38195252
0.57377195
0.47097227
0.12158713
0.21322925
0.31647044
0.5527038
0.47462723
0.6149222
0.65007806
0.11145787
0.44169205
0.51498264
0.072121754
0.02085787
-0.02330407
0.0030019032
0.13602144
-0.16190982
-0.10533785
-0.1734815
-0.2510002
0.4735372
0.58126503
0.19582687
0.45889878
0.54310197
0.21080907
0.20235369
0.2099934
-0.04946122
-0.32726097
-0.0048638796
-0.32321292
0.13319272
0.012297149
-0.10513384
0.19061892
0.4101147
0.08123453
0.2558452
0.38487348
0.27844468
0.5007668
0.550769
0.114901684
0.4507436
0.3535035
0.3076304
0.1479239
0.09292402
-0.4041034
0.38143447
-0.069753066
-0.27865863
0.16946647
-0.045003142
-0.111094154
0.0009370859
-0.09843764
-0.0066839033
0.015192114
0.18330237
-0.091846526
-0.093767345
-0.036863815
-0.023914052
-0.10209015
-0.02862692
-0.11142951
-0.21141496
-0.2307057
-0.06516248
0.020834371
-0.031347763
-0.039252505
-0.27983642
-0.03970919
0.20645477
-0.12705953
0.33821788
0.13405067
0.2445887
0.44188142
-0.0038982031
-0.13979559
-0.20385139
0.117509395
-0.005715718
-0.080601916
0.09685326
-0.066362664
0.008437556
-0.10210685
0.7539002
0.6952307
0.28752255
0.80205274
0.4766971
0.17297089
0.2882549
0.098174155
0.0020970956
0.19470583
0.09950261
-0.09694061
0.29215577
0.12278695
-0.037522893
0.17075685
0.33552113
0.13674323
-0.07577733
0.31630826
0.34378958
-0.15304123
0.12785366
0.086952396
-0.31330797
-0.001654931
0.12654537
-0.86122245
-0.68093973
-0.22129026
-0.8326889
-0.7481235
-0.14792675
-0.8588496
-0.66041034
0.013661266
-0.06239793
-0.1387425
-0.059888713
0.03536964
0.062088303
0.011600256
0.08357481
0.025985636
-0.057800315
-0.8058461
-0.8655415
-0.8878307
-1.0268383
-0.8895686
-0.870193
-0.92634207
-0.7991516
-0.84145725
0.22383228
0.04903484
-0.65011233
0.34974617
-0.22466241
-0.44892547
0.043155216
-0.32732686
-0.85459894
-0.11874903
-0.47783476
-0.5260095
-0.29938856
-0.46704254
-0.4449409
-0.48969412
-0.42000425
-0.5598123
-0.5296795
-0.8521746
-0.67211694
-0.80781704
-0.94732684
-0.57418257
-0.77279216
-0.6926591
-0.45179915
-0.19991966
-0.0625157
-0.5307898
0.15330955
-0.0213713
-0.26861903
0.23867297
0.22922835
0.16720639
0.59522456
0.6892708
0.3867164
0.44517902
0.47505063
0.4654438
0.22130506
0.387733
0.19797981
0.33539343
0.24232638
-0.10490481
0.13891292
-0.076867625
0.12750566
0.05550657
-0.02150966
0.17238574
-0.092911184
-0.16721976
0.009027423
-0.19101651
-0.029071758
-0.069601566
-0.09827422
-0.08287598
-0.022561137
-0.22663862
-0.47552612
-0.17845595
-0.46161267
-0.43686563
-0.22974852
-0.36118308
-0.2722955
-0.14243911
0.1847469
0.34657878
0.42981294
0.18554401
0.33521423
0.27269012
0.45541444
0.41730106
0.16927144
0.22624063
0.30033535
0.116721414
0.12135912
0.284733
0.3730829
0.09463956
0.22056812
0.1317617
0.15912417
0.19767475
-0.22404052
-0.23200901
-0.36393234
-0.4101935
-0.24772424
-0.6499398
-0.6035362
-0.13825883
-0.21811308
-0.31700268
0.10087058
0.0777835
-0.14945805
0.26013204
0.35406354
0.11850203
0.024606973
0.12879103
-0.095771246
0.35835484
0.28432438
0.17027797
0.04460398
0.2106631
-0.09346488
0.24641933
0.034816552
-0.12438573
0.54997367
0.31058714
-0.21279928
0.17215224
0.010456621
0.013317943
-0.008930922
-0.030233396
0.008761597
0.03480156
0.037845217
-0.031645544
-0.08237756
0.0050705066
-0.06625244
0.3866179
0.29360098
0.35600394
0.2591941
0.18063474
0.38357696
0.23095702
0.17364517
0.15391372
-0.5093487
-0.22992536
0.27934852
-0.2374083
0.039487418
0.3051096
-0.056948155
0.24535167
0.19844466
-0.10930642
-0.05106426
0.0033689137
-0.09231472
0.27303606
0.1450588
0.102419965
0.22690499
0.26383835
0.6005564
0.97944826
0.6462157
0.5086828
0.93819946
0.600236
0.19520918
0.19155432
-0.1607842

View File

@@ -1,9 +1,17 @@
8
1.8607159
0.8140447
0.02090901
0.12166861
1.401096
1.6002591
0.9205242
0.52036697
16
0.18449903
0.58430743
0.26267084
0.15215518
0.17875981
0.26728117
0.38014928
0.32304344
0.20345993
0.051697854
0.08828824
0.17220211
0.30045128
0.7321825
0.32318887
0.64071155

File diff suppressed because it is too large Load Diff

View File

@@ -1,51 +1,61 @@
50
0.27732438
-0.42984757
0.77958596
0.50327533
-0.4008876
-0.013967511
0.2507846
-0.22089948
-0.074136175
-0.69092935
-0.016178658
0.3531398
0.017891733
0.46746168
-0.14891404
0.22245038
0.16725647
-0.01826465
0.30017307
-0.13458814
-0.03478663
-0.017660717
-0.40806273
-0.030123862
0.2801973
0.27446425
0.5195524
0.64331424
0.008353927
0.35976186
0.59728014
-0.061037164
-0.5944482
0.569236
-0.36547965
0.8237916
0.32342234
0.32420716
-0.012236862
-0.030580053
0.48695275
-0.5278198
-0.329191
0.72754157
-0.013564502
0.30172536
-0.44324636
0.6108572
-0.10568087
-0.19255634
60
-0.039159678
0.029541148
0.46619368
0.39806518
0.17867364
-0.17273445
0.049488015
0.3954818
0.006907484
-0.65876406
0.20659731
0.33826667
0.102885984
-0.3502921
0.25347513
-0.26725784
0.07709998
-0.04353281
-0.18644187
0.3938342
-0.025656475
0.4239288
-0.19141191
-0.4522367
-0.11141183
-0.4640547
0.5636213
-0.089869745
0.21497346
0.20390627
-0.25163013
-0.46159822
0.08521984
0.04547417
0.22536296
0.26892447
0.24108179
0.3650224
-0.12725092
0.35256448
-0.21991397
-0.0061194855
-0.029125368
0.120918676
-0.18983841
-0.46133506
-0.12631308
0.26642975
0.12274385
0.060510684
-0.037945624
0.40486556
0.09022891
-0.100966334
0.114066094
0.29244682
0.16922234
-0.060573082
0.5995527
-0.091098264

File diff suppressed because it is too large Load Diff

View File

@@ -1,16 +1,16 @@
15
0.6056967
-0.13792518
-0.21883932
-0.20325783
-0.43291906
-0.25540975
0.39662966
-0.1248626
0.011282514
-0.27768156
-0.27011594
-0.06521889
-0.46317244
0.37428737
0.1406347
0.04959415
-0.15338269
-0.30548725
-0.21866404
-0.4217409
-0.032290496
0.31138745
0.1469873
0.07883086
-0.11234011
-0.15009451
0.19498166
-0.13619435
0.37006247
0.41003358

File diff suppressed because it is too large Load Diff