diff --git a/.gitignore b/.gitignore index a88a8c81c..f6ac31f3d 100755 --- a/.gitignore +++ b/.gitignore @@ -19,4 +19,6 @@ examples/cmake-build*/* */data/* **/activation.raisim data/* -**/.DS_Store \ No newline at end of file +**/.DS_Store +/raisimGymTorch/raisimGymTorch/algo/pre_sin.py +/raisimGymTorch/raisimGymTorch/env/deploy/data/ diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 000000000..7575e7b6c --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "raisimGymTorch/A1_raspi_py"] + path = raisimGymTorch/A1_raspi_py + url = https://github.com/Lr-2002/A1_raspi_py.git diff --git a/README.md b/README.md index f6dc5e34c..7d40787c9 100755 --- a/README.md +++ b/README.md @@ -6,6 +6,9 @@ Click to watch the video Documentation available on the [RaiSim Tech website](http://raisim.com). +Click here to read chinese version [中文简体](./Readme_zh.md) + + ## New update! RaisimUnreal (Alpha version) is now released. You can get it [here](https://github.com/raisimTech/raisimLib/releases). diff --git a/Readme_zh.md b/Readme_zh.md new file mode 100644 index 000000000..b42d9d842 --- /dev/null +++ b/Readme_zh.md @@ -0,0 +1,114 @@ +# Raisim 中文使用指南 + +## 写在前面 + +相信大家都是因为自己老师的要求,过来学习Raisim,或者之前也已经尝试过一些别的项目(issac,gazebo,webots)之类的。 + +首先,我想说一下,为什么要使用Raisim + +1. `C++` + `Python`,这个软件对`python`还是比较友好的,但是为了提高你的使用体验,你需要有一定的`C++`基础,尤其是强化学习部分,你需要自己动手修改`Environment.hpp` 如果不太理解`C++`的面对对象的概念,以及一些`STL`的基本结构(`iterator`之类的),使用起来会有一些难度 +2. `Linux, Win, Mac` 友好。目前为止我只尝试了`win` 和`linux`,这两个系统的支持度还都是挺好的,尤其是`linux`,对视频的录制很好用,不需要一直盯着屏幕。 +3. 强化学习很快,由于代码完全开放,相较于`Unity`而言,你的自由度更高,你可以很轻松的添加你自己的东西。 + +其次,我说一下本版本相较于作者的原版本的区别 + +1. 添加了更详细的`log`系统,在`gym`文件夹的`helper`里添加了`logging`系统,使用起来能够在对应的`saver.dir`中生成名为`train.log`的文件,方便后期查询自己的日志 +2. 训练过程中自动保存最优的模型,后期会修改把之前的弱鸡模型给删除 +3. 完善了`runner.py --mode test`模块,在`gymtorch`文件夹中,你的`runner`可以直接通过运行`python yourfilepath(imply it use your path)/runner.py --mode test --weight yourweightpath`在`unity`等渲染引擎中展示你的模型 + +## 怎么使用 + +### 复制项目 + +1. `fork`本`repo`到你个人的`github`中(右上角有一个`fork`按钮) +2. 在你自己的`fork`版本中,选择`code`按钮,复制`https`链接 +3. 在你本地打开`powershell`(windows)或者是`base/zsh`(linux),然后`git clone your-repo-http`(不清楚的自行`google`) +4. 切换到你的目标位置,通常是`raisimLib` + +### 编译项目 + +编译是`C/C++`在执行之前都需要进行的事情,简单来说,就是把做饭需要的菜都放到桌子上,具体执行方式如下 + +#### 安装依赖 + +我下边只列出来你需要安装的软件,如果有不会的请自行`google` + +1. `cmake` +2. `Eigen` (`C++`需要用到) +3. 编译器 + 1. Linux: `gnu` + 2. Windows: `Visual Studio`(注意不要安装错误了,是紫色的VS,不是蓝色的VSC) + +#### 设置路径 + +##### Windows + +自行`google`: 如何将路径添加到环境变量 + +##### Linux + +自行`google`: 如何将路径添加到`Linux`路径 + +#### checklist(检查你需要添加的路径) + +1. `cmake`:添加的路径下需要有`cmake.exe`文件 + +2. `eigen`:添加的路径需要有`Dense.hpp`文件 +3. `WORKSPACE`:这个变量指向的是`RaisimLib`的位置,这个路径在windows中需要单独列出来,在环境变量中直接新建,而不是通过`path`建立 +4. `LOCAL_INSTALL`:这个变量指向的是你希望在那里部署你的库文件, 建议直接在`raisimLib`下新建文件夹,命名为`raisim_build`,然后指向这个位置即可 + +#### 开始部署/编译 + +1. 让你的终端切换到`raisimlib`文件夹 +2. 创建`build`文件夹,并切换进去 +3. 参考[官方文档](https://raisim.com/sections/Installation.html#building-raisim-examples-and-installing-raisimpy)的建议,运行对应的命令,如果你不想编译`python`,就把`-DRAISIM_PY=ON`删掉(他的`python`好像作者自己都不喜欢用) + +### 激活文件 + +1. [点这里申请你的激活文件](https://docs.google.com/forms/d/e/1FAIpQLScNL0vbZPDNS93L6Jv6fgR51WTsvXxfhnVOtKDVRdAmHIoG4w/viewform?usp=sf_link) + 1. 写自己的信息 + 2. 通过提供的`google drive`获取软件,读取你的机器码 + 3. 将机器码复制进去,然后申请`license`就可以了(他们会给你的邮箱发一个`activation.raisim`) +2. 在你的根目录(`linux`就是`~/`,`windows`是`c:users/xxx(你的账户)/`),创建一个文件夹,命名为`.raisim`,将`activation.raisim`复制进去即可。 + +### 运行例子 + +#### Linux + +生成的`example`就在你创建的`build`文件夹下,进去就可以找到类似`alingo`之类的二进制文件,你需要通过`chmod +X ./alingo` 运行即可 + +#### Windows + +如果你是通过VS建立的项目,这个路径通常在`RasimLib/raisim/win32/bin`里,会有一大堆的`exe`,点击运行即可 + + + + + +# `RaisimGymTorch` + +如果你是要学习`RaisimGymTorch`进行强化学习,那就需要理解以下几个基本概念 + +1. `setup.py`(`raisimlib/raisimgymtorch/`) 对所有的环境进行编译,生成在python中可以使用的库 +2. `Environment.hpp` 这个文件定义了你的机器人与环境作用的方式 + 1. 执行你的`action` + 2. 计算`reward` + 3. 更新`observation` +3. `runner.py` 这个文件是你的`python`的主框架 + 1. 记录`log` + 2. 更新`observation` + 3. 记录`state-action`对 对应函数为`ppo.step` + 4. `ppo`计算 对应的函数是`ppo.act` + 5. 生成`action` + 6. 更新`model` +4. `cfg.yaml` 定义超参数 + 1. `num_envs`:子空间的数量(开多空间) + 2. `eval_per_iters`:执行多少个`iters`之后会记录并展示 + + + + + +## 欢迎PR + +有问题发`Issue`,觉得ok的话,点一个`star`,tks! \ No newline at end of file diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 2d578b77b..2af672918 100755 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -4,7 +4,7 @@ project(raisim_examples LANGUAGES CXX) #== # Dependencies #== - +#set(raisim /home/lr-2002/code/raisimLib/raisim/linux/lib/cmake/raisim/) find_package(raisim CONFIG REQUIRED) find_package(Eigen3 REQUIRED HINTS ${Eigen3_HINT}) @@ -77,6 +77,8 @@ create_executable(deletion src/server/deletion.cpp) create_executable(inverseDynamics src/server/inverseDynamics.cpp) create_executable(dzhanibekovEffect src/server/dzhanibekovEffect.cpp) create_executable(go1 src/server/go1.cpp) +create_executable(leg src/server/leg.cpp) +create_executable(quat src/server/quat_m.cpp) # xml reader create_executable(xmlRader src/xml/xmlReader.cpp) @@ -96,3 +98,5 @@ create_executable(anymals src/maps/anymals.cpp) create_executable(hill1 src/maps/hill1.cpp) create_executable(kinova src/maps/kinova.cpp) +create_executable(skate src/server/skate.cpp) + diff --git a/examples/src/maps/anymals.cpp b/examples/src/maps/anymals.cpp index daddc496d..c55e2b3ed 100755 --- a/examples/src/maps/anymals.cpp +++ b/examples/src/maps/anymals.cpp @@ -2,6 +2,88 @@ // Inc. prior to usage. #include "raisim/RaisimServer.hpp" +#include +#include +#define PI 3.1415926 +int cnt1=0, cnt2=0; +void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +{ +// std::cout<< "size is "<< angle_list.size() << std::endl; + double base1= 0.4, base3=0.03; + double base2 = -2 * base1; + double ang = abs(sin( float(idx) / T * PI)) * rate; + double ang2 = ang * 1.2; + if (idx % int(T) == 1) cnt1++; + int idx_base = 0; +// std::cout<> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); + std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } + std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} int main(int argc, char* argv[]) { auto binaryPath = raisim::Path::setFromArgv(argv[0]); @@ -10,13 +92,12 @@ int main(int argc, char* argv[]) { /// create raisim world raisim::World world; - world.setTimeStep(0.001); + world.setTimeStep(0.01); /// create objects auto ground = world.addGround(0, "gnd"); ground->setAppearance("hidden"); - auto anymalB = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\anymal\\urdf\\anymal.urdf"); - auto anymalC = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\anymal_c\\urdf\\anymal.urdf"); + auto anymalC = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\go1\\go1.urdf"); /// anymalC joint PD controller Eigen::VectorXd jointNominalConfig(anymalC->getGeneralizedCoordinateDim()), jointVelocityTarget(anymalC->getDOF()); @@ -24,21 +105,33 @@ int main(int argc, char* argv[]) { jointVelocityTarget.setZero(); Eigen::VectorXd jointPgain(anymalC->getDOF()), jointDgain(anymalC->getDOF()); - jointPgain.tail(12).setConstant(100.0); - jointDgain.tail(12).setConstant(1.0); + jointPgain.tail(12).setConstant(200); + jointDgain.tail(12).setConstant(4); +// jointDgain[7] = 2; +// jointDgain[10] = 2; +// jointDgain[13] = 2; +// jointDgain[16] = 2; + +// std::vector footIndices_; +// +// footIndices_.push_back(anymalC->getFrameIdxByName("LF_SHANK")); +// footIndices_.push_back(anymalC->getFrameIdxByName("RF_SHANK")); +// footIndices_.push_back(anymalC->getFrameIdxByName("LH_SHANK")); +// footIndices_.push_back(anymalC->getFrameIdxByName("RH_SHANK")); + +// auto footframeindex = anymalC->getFrameIdxByName("foot") anymalC->setGeneralizedCoordinate(jointNominalConfig); anymalC->setGeneralizedForce(Eigen::VectorXd::Zero(anymalC->getDOF())); anymalC->setPdGains(jointPgain, jointDgain); - anymalC->setPdTarget(jointNominalConfig, jointVelocityTarget); anymalC->setName("anymalC"); - +// std::vector> foot_list; +// for(auto i=0; igetFramePosition(footIndices_[i], foot_list[i]); +// std::cout<<"posi " << foot_list[i] <setGeneralizedCoordinate(jointNominalConfig); - anymalB->setGeneralizedForce(Eigen::VectorXd::Zero(anymalB->getDOF())); - anymalB->setPdGains(jointPgain, jointDgain); - anymalB->setPdTarget(jointNominalConfig, jointVelocityTarget); - anymalB->setName("anymalB"); /// friction example. uncomment it to see the effect // anymalB->getCollisionBody("LF_FOOT/0").setMaterial("LF_FOOT"); @@ -53,23 +146,35 @@ int main(int argc, char* argv[]) { /// graphs std::vector jointNames = {"LF_HAA", "LF_HFE", "LF_KFE", "RF_HAA", "RF_HFE", "RF_KFE", "LH_HAA", "LH_HFE", "LH_KFE", "RH_HAA", "RH_HFE", "RH_KFE"}; - auto jcGraph = server.addTimeSeriesGraph("joint position", jointNames, "time", "position"); - auto jvGraph = server.addTimeSeriesGraph("joint velocity", jointNames, "time", "velocity"); - auto jfGraph = server.addTimeSeriesGraph("joint torque", jointNames, "time", "torque"); raisim::VecDyn jc(12), jv(12), jf(12); + Eigen::VectorXd angle_list(12); + Eigen::Vector3d pose(0, 0, 3); +// Eigen::Vector2d join; + auto join = anymalC->getJointLimits(); + Eigen::VectorXd limit_list; + Eigen::VectorXd gene_angle; + gene_angle.setZero(12); + map_from_origin_to_limit(join, limit_list, gene_angle); + std::cout<setBasePos(pose); + angle_generator(angle_list, i, 30.f, 0.3); + + jointNominalConfig.tail(12) = angle_list; if (i % 10 == 0) { - jc = anymalC->getGeneralizedCoordinate().e().tail(12); - jv = anymalC->getGeneralizedVelocity().e().tail(12); - jf = anymalC->getGeneralizedForce().e().tail(12); - jcGraph->addDataPoints(world.getWorldTime(), jc); - jvGraph->addDataPoints(world.getWorldTime(), jv); - jfGraph->addDataPoints(world.getWorldTime(), jf); + } + anymalC->setPdTarget(jointNominalConfig, jointVelocityTarget); +// anymalC->setBasePos_e(pose); +// anymalC->setGeneralizedCoordinate(jointNominalConfig); } server.killServer(); diff --git a/examples/src/server/go1.cpp b/examples/src/server/go1.cpp index 2d5ebffa5..b19442107 100644 --- a/examples/src/server/go1.cpp +++ b/examples/src/server/go1.cpp @@ -3,41 +3,340 @@ #include "raisim/RaisimServer.hpp" #include "raisim/World.hpp" +#define PI 3.1415926 +#include +auto ToEulerAngles(Eigen::Quaterniond q) { + Eigen::Vector3d angles; + // roll (x-axis rotation) + double sinr_cosp = 2 * (q.w() * q.x() + q.y() * q.z()); + double cosr_cosp = 1 - 2 * (q.x ()* q.x() + q.y() * q.y()); + angles[0] = std::atan2(sinr_cosp, cosr_cosp); + + // pitch (y-axis rotation) + double sinp = std::sqrt(1 + 2 * (q.w ()* q.y ()- q.x() * q.z())); + double cosp = std::sqrt(1 - 2 * (q.w ()* q.y() - q.x() * q.z())); + angles[1] = 2 * std::atan2(sinp, cosp) - M_PI / 2; + + // yaw (z-axis rotation) + double siny_cosp = 2 * (q.w() * q.z() + q.x() * q.y()); + double cosy_cosp = 1 - 2 * (q.y() * q.y() + q.z() * q.z()); + angles[2] = std::atan2(siny_cosp, cosy_cosp); + + return angles; +} + +void swap(Eigen::VectorXd &ob, int a, int b) +{ + double tmp = ob[a]; + ob[a] = ob[b]; + ob[b] = ob[a]; +} +//void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +//{ +// // todo ang2, rate, ang +//// std::cout<< "size is "<< angle_list.size() << std::endl; +// double base1= 0.523, base3=0.0; +// double base2 = -2 * base1; +// double ang = abs(sin( float(idx) / T * PI)) * rate; +// double ang2 = -0.15 * ang * 0; +// double ang3 = ang2 * -2; +// int idx_base = 0; +//// std::cout<& mat, Eigen::Vector3d& euler) +{ + euler[0] = atan2(mat[2], mat[8]); + euler[1] = asin(- mat[5]); + euler[2] = atan2(mat[3], mat[4]); +} + +void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +{ +// std::cout<< "size is "<< angle_list.size() << std::endl; + double base1= 0.523, base3=0.0; + double base2 = -2 * base1; + double ang = abs(sin( float(idx) / T * PI)) * rate; + + int idx_base = 0; +// std::cout<getGeneralizedCoordinateDim()), jointVelocityTarget(go1->getDOF()); - jointNominalConfig << 0, 0, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// jointNominalConfig << 0, 0, 0.41, 1.0, 0.0, 0.0, 0.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; + Eigen::VectorXd board_posi(board->getGeneralizedCoordinateDim()); + board_posi << 0,0,0.11, 0.707, 0,0, 0.707,0,0; + board->setGeneralizedCoordinate(board_posi); + board->setName("board"); + jointNominalConfig << -0, 0, 0.49, 1.0, 0.0, 0, 0, 0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976 ; // todo implement in python using list +// jointNominalConfig << 0, 0, 0.33, 1.0, 0.0, 0, 0, 0, 1, -2.2, 0.0, 1, -2.2, 0.0, 1, -2.2, 0.0, 1, -2.2; // todo implement in python using list +// jointNominalConfig.tail(12).setZero(); +// Eigen::VectorXd tmp(12); +// tmp.setZero(); +// angle_generator(tmp, 0, 80.f); +// jointNominalConfig.tail(12) = tmp; jointVelocityTarget.setZero(); - + go1->setControlMode(raisim::ControlMode::FORCE_AND_TORQUE); Eigen::VectorXd jointPgain(go1->getDOF()), jointDgain(go1->getDOF()); - jointPgain.tail(12).setConstant(10.0); - jointDgain.tail(12).setConstant(0.1); + jointPgain.tail(12).setConstant(80); + jointDgain.tail(12).setConstant(4); go1->setGeneralizedCoordinate(jointNominalConfig); go1->setGeneralizedForce(Eigen::VectorXd::Zero(go1->getDOF())); go1->setPdGains(jointPgain, jointDgain); go1->setPdTarget(jointNominalConfig, jointVelocityTarget); go1->setName("go1"); + std::cout<< go1->getGeneralizedCoordinate(); + for(auto n : go1->getCollisionBodies()) + { + auto name = n.colObj->name; + go1->getCollisionBody(name).setMaterial("steel"); +// go1->getCollisionBody() + } + + for(auto n : board->getCollisionBodies()) + { + auto name = n.colObj->name; + std::cout << name << std::endl; +// board->getCollisionBody(name).setMaterial("steel"); +// go1->getCollisionBody() + } +// wrl + board->getCollisionBody("base/0").setMaterial("sandpaper"); + board->getCollisionBody("rotater_r/0").setMaterial("rubber"); + board->getCollisionBody("rotater_f/0").setMaterial("rubber"); + go1->getCollisionBody("FL_foot/0").setMaterial("rubber"); + go1->getCollisionBody("FR_foot/0").setMaterial("rubber"); + go1->getCollisionBody("RR_foot/0").setMaterial("rubber"); + go1->getCollisionBody("RL_foot/0").setMaterial("rubber"); + world.setMaterialPairProp("steel", "rubber", 0.8, 0.15, 0.001); + world.setMaterialPairProp("rubber", "sandpaper", 0.99, 0.15, 0.001); + world.setMaterialPairProp("land", "rubber", 0.8, 0.1,0.001); + world.setMaterialPairProp("sandpaper", "land", 0.4, 0.15,0.001); + world.setMaterialPairProp("steel","land", 0.1, 0.05,0.001); +// world.updateMaterialProp(); /// launch raisim server raisim::RaisimServer server(&world); server.focusOn(go1); server.launchServer(); + Eigen::Vector3d pos(0,0, 3); + Eigen::VectorXd ob_(24); + ob_.setZero(); + Eigen::VectorXd gc, gv; + Eigen::VectorXd position, velo; + position.setZero(12), velo.setZero(12); + gc.setZero(19), gv.setZero(18); + size_t dof = go1->getDOF(); +// go1->set + + + raisim::Vec<3> vel; + vel.setZero(); + raisim::Vec<3> acc; + Eigen::Vector3d ma; + ma.setZero(); + Eigen::VectorXd bodyLinearVelocity, bodyAngularVelocity; + bodyAngularVelocity.setZero(3); + bodyLinearVelocity.setZero(3); + auto roott = go1->getBodyIdx("base"); +// go1->getCollisionBodies(); +// auto imu = go1->getSensor("imu_joint"); + + for (int i=0; i<2000000; i++) { + +// std::cin.ignore(); +// imu->getAngularVelocity() + - for (int i=0; i<2000000; i++) { - RS_TIMED_LOOP(int(world.getTimeStep()*1e6)) + go1->getState(gc,gv); + + +// anymal_->getState(gc, gv); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc[3]; quat[1] = gc[4]; quat[2] = gc[5]; quat[3] = gc[6]; + quat /= quat.norm(); + raisim::quatToRotMat(quat, rot); +// auto nn =go1->getCollisionBodies(); +// int cnt = 0; +// for(auto n : nn ) +// { +// +// std::cout<< cnt ++ << " " << n.getMaterial() << std::endl; +// } +// std::cout<getCollisionBody("FL_FOOT/0").getMaterial(); + bodyLinearVelocity = rot.e().transpose() * gv.segment(0, 3); + bodyAngularVelocity = rot.e().transpose() * gv.segment(3, 3); + Eigen::Vector3d eule; + rot2euler(rot, eule); +// std::cout<<"euler " << bodyAngularVelocity< qu{1+double(i)/500 , 0 , 0, 0+ double(i) / 500 }; +// go1->setBaseOrientation(qu); +// Eigen::VectorXd tmp1(12), tmp2(12); +// tmp1 = gc.tail(12); +// tmp2 = gv.tail(12); +// for(auto i=0; i<12; i++){ +// ob_[2*i] = tmp1[i]; +// ob_[2 * i+1] = tmp2[i]; +// } +// for(auto i=0;i <12; i++) +// { +// swap(ob_, i, 12 +i); +// } + + raisim::Vec<3> vel_temp; +// go1->getFrameVelocity("ROOT", vel_temp); +// for(auto i =0;i <2; i++) +// { +// acc = (vel_temp - vel) / 0.01; + vel = vel_temp; +// acc[i] = vel_temp +// } +// std::cout << "vel \n" << vel << std::endl << "acc\n " << acc << std::endl; + usleep(10000); + angle_generator(position, i, 40, 0.35); + jointNominalConfig.tail(12) = position; +// for(auto n: go1->getContacts()) +// { +// std::cout << n.getPairContactIndexInPairObject()<< std::endl; +// } +// for(auto obj:world.getObjList()) +// { +// std::cout<getName()<abs(ma[0]) ) ma[0] = abs(angle[0]); + if (abs(angle[1]) >abs(ma[1]) ) ma[1] = abs(angle[1]); + if (abs(angle[2]) >abs(ma[2]) ) ma[2] = abs(angle[2]); + raisim::Vec<3> angvel; + go1->getAngularVelocity(roott, angvel); +// std::cout<printOutFrameNamesInOrder(); + go1->getFrameAcceleration("floating_base", angvel); +// std::cout<getAngularVelocity(); + RS_TIMED_LOOP(int(world.getTimeStep()*1e6)) +// std::cout<< ob_ << std::endl<setBasePos(pos); +// angle_generator(tmp, i, 50.f, 0.3); +// double rrr = 0; +// for(int i=4; i<=6 ; i++) +// { +// rrr += abs(jointNominalConfig[i] - ) * stable_reward_rate ; +// } +// jointNominalConfig.tail(12) = tmp; +// std::cout<< tmp << std::endl; +// jointNominalConfig[8] = - 0.01 * i ; +go1->setPdTarget(jointNominalConfig, jointVelocityTarget); + +// for(auto& contact : go1->getContacts()) +// { +//// if(contact.getPairContactIndexInPairObject() != raisim::BodyType::STATIC) +//// { +//// world.getObject(contact.getPairObjectIndex())->getContacts(); +//// } +// } +// server.integrateWorldThreadSafe(); + } server.killServer(); diff --git a/examples/src/server/leg.cpp b/examples/src/server/leg.cpp new file mode 100644 index 000000000..d94ab7b6f --- /dev/null +++ b/examples/src/server/leg.cpp @@ -0,0 +1,73 @@ +// +// Created by lr-2002 on 23-7-14. +// +#include "raisim/World.hpp" +#include "raisim/RaisimServer.hpp" +float calculate_angle(float ang) +{ + return ang * 3.14 / 180; +} +void print_collision(raisim::Sphere* sphere) +{ + + auto& contacts = sphere->getContacts(); + for (auto i : contacts) + { + std::cout<< i.getPosition() << std::endl; + } +} +int main(int argc, char * argv[]) +{ + auto binaryPath = raisim::Path::setFromArgv(argv[0]); + raisim::World::setActivationKey(binaryPath.getDirectory() + "\\rsc\\activation.raisim"); + + // create raisim world + raisim::World world; + world.setTimeStep(0.01); + auto ground = world.addGround(); + + world.setMaterialPairProp("steel", "steel", 0.8, 0.95, 0.001); + // launch server + + raisim::RaisimServer server(&world); + server.launchServer(); + + auto sphere = world.addSphere(0.4, 0.3, "steel"); + sphere->setName("sphere"); + auto leg = world.addArticulatedSystem(binaryPath.getDirectory()+"\\rsc\\leg\\leg2.urdf"); + leg->setName("leg"); + +// Eigen::VectorXd gc(3); +// gc << 0, 0, 0; +// leg->setGeneralizedCoordinate(gc); + + +// Eigen::VectorXd gc(3); +// Eigen::VectorXd gv(3); +// gc << calculate_angle(-50), 0, calculate_angle(-50); +// gv << 0, -1, -1; +// sphere->setPosition(0, 0, 0.4); +// int cnt = 0; +// auto foot_index = leg->getBodyIdx("r_2"); + while(1) + { +// cnt ++ ; +// gc << calculate_angle(-50 + 0.8* cnt), 0, calculate_angle(-90); +// print_collision(sphere); +// std::cout<setGeneralizedCoordinate(gc); +// leg->setGeneralizedVelocity(gv); +// leg->setGeneralizedForce(gc); + server.integrateWorldThreadSafe(); + raisim::MSLEEP(10); +// for(auto& contact : leg->getContacts()) +// { +// if(contact.getPairContactIndexInPairObject() != raisim::BodyType::STATIC) +// { +// world.getObject(contact.getPairObjectIndex())->getContacts(); +// } +// } + } + + server.killServer(); +} \ No newline at end of file diff --git a/examples/src/server/sensors.cpp b/examples/src/server/sensors.cpp index 41f814831..f4076bdf1 100755 --- a/examples/src/server/sensors.cpp +++ b/examples/src/server/sensors.cpp @@ -52,6 +52,7 @@ int main(int argc, char **argv) { for (int k = 0; k < loopN; k++) { RS_TIMED_LOOP(int(world.getTimeStep()*1e6)) server.integrateWorldThreadSafe(); + std::cout << imu->getAngularVelocity(); } server.killServer(); diff --git a/examples/src/server/skate.cpp b/examples/src/server/skate.cpp new file mode 100644 index 000000000..78dfcc449 --- /dev/null +++ b/examples/src/server/skate.cpp @@ -0,0 +1,63 @@ +// +// Created by lr-2002 on 23-8-18. +// +// This file is part of RaiSim. You must obtain a valid license from RaiSim Tech +// Inc. prior to usage. + +#include "raisim/RaisimServer.hpp" +#include "raisim/World.hpp" +#include + +int main(int argc, char* argv[]) { + auto binaryPath = raisim::Path::setFromArgv(argv[0]); + + /// create raisim world + raisim::World world; + world.setTimeStep(0.01); + + /// create objects + world.addGround(); + raisim::RaisimServer server(&world); + server.launchServer(); + auto skate = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\skate\\skate.urdf"); + /// skate state + Eigen::VectorXd jointNominalConfig(skate->getGeneralizedCoordinateDim()); + skate->setName("skate"); + jointNominalConfig.setZero(); +// jointNominalConfig[1] = 0.01; + jointNominalConfig<< 0, 0, 0.11, 1 , 0, 0, 0 ,0 , 0; + Eigen::VectorXd jointVelocityTarget(skate->getDOF() ); + jointVelocityTarget.setZero(); + skate->setControlMode(raisim::ControlMode::FORCE_AND_TORQUE); + Eigen::VectorXd jointPgain(skate->getDOF()), jointDgain(skate->getDOF()); + jointPgain.tail(2).setConstant(80); + jointDgain.tail(2).setConstant(4); + + skate->setGeneralizedCoordinate(jointNominalConfig); + skate->setGeneralizedForce(Eigen::VectorXd::Zero(skate->getDOF())); + skate->setPdGains(jointPgain, jointDgain); + skate->setPdTarget(jointNominalConfig, jointVelocityTarget); + skate->setGeneralizedCoordinate(jointNominalConfig); + std::cout << " position " << jointNominalConfig; + /// launch raisim server + + std::cout<<"gra " << world.getGravity(); + std::cout << "\n mov "; + auto na = skate->getMovableJointNames(); + + server.focusOn(skate); + for (auto i:na) + { + std::cout << i << std::endl; + } + for (int i=0; i<200000; i++) { + RS_TIMED_LOOP(int(world.getTimeStep()*1e6)) + server.integrateWorldThreadSafe(); + jointNominalConfig.tail(2).setConstant( 0.02 * i); + jointVelocityTarget.tail(2).setConstant(0); + skate->setPdTarget(jointNominalConfig, jointVelocityTarget); + } + + server.killServer(); +} + diff --git a/raisimGymTorch/CMakeLists.txt b/raisimGymTorch/CMakeLists.txt index cc212d42d..ba4faa5d6 100755 --- a/raisimGymTorch/CMakeLists.txt +++ b/raisimGymTorch/CMakeLists.txt @@ -76,6 +76,8 @@ find_package(raisim CONFIG REQUIRED) SUBDIRLIST(SUBDIRS ${CMAKE_CURRENT_SOURCE_DIR}/raisimGymTorch/env/envs) set(RAISIMGYM_ENV_DIR ${CMAKE_CURRENT_SOURCE_DIR}/raisimGymTorch/env/envs) +set(SUBDIRS rsg) # only build for rsg + ######## Env ########## FOREACH(subdir ${SUBDIRS}) pybind11_add_module(${subdir} raisimGymTorch/env/raisim_gym.cpp raisimGymTorch/env/Yaml.cpp) @@ -108,3 +110,5 @@ FOREACH(subdir ${SUBDIRS}) endif() endif() ENDFOREACH() +add_executable(t_sin ../examples/src/maps/t_sin.cpp) +target_include_directories(t_sin PUBLIC ${EIGEN3_INCLUDE_DIRS} ) diff --git a/raisimGymTorch/raisimGymTorch/.gitignore b/raisimGymTorch/raisimGymTorch/.gitignore new file mode 100644 index 000000000..6321e422d --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/.gitignore @@ -0,0 +1,2 @@ +*.onnx +*.pt diff --git a/raisimGymTorch/raisimGymTorch/algo/ppo/module.py b/raisimGymTorch/raisimGymTorch/algo/ppo/module.py index 2885f2d7a..b888a9b36 100755 --- a/raisimGymTorch/raisimGymTorch/algo/ppo/module.py +++ b/raisimGymTorch/raisimGymTorch/algo/ppo/module.py @@ -18,6 +18,9 @@ def __init__(self, architecture, distribution, device='cpu'): def sample(self, obs): self.action_mean = self.architecture.architecture(obs).cpu().numpy() actions, log_prob = self.distribution.sample(self.action_mean) + # todo + # actions = actions- + # actions =np.clip(actions- 1,-1 ,1) return actions, log_prob def evaluate(self, obs, actions): @@ -110,6 +113,7 @@ def __init__(self, dim, size, init_std, fast_sampler, seed=0): self.std_np = self.std.detach().cpu().numpy() def update(self): + print(self.std) self.std_np = self.std.detach().cpu().numpy() def sample(self, logits): diff --git a/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py b/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py index 885f73e11..af87e6e46 100755 --- a/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py +++ b/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py @@ -5,7 +5,7 @@ import torch.optim as optim from torch.utils.tensorboard import SummaryWriter from .storage import RolloutStorage - +import numpy as np class PPO: def __init__(self, @@ -77,7 +77,12 @@ def act(self, actor_obs): self.actor_obs = actor_obs with torch.no_grad(): self.actions, self.actions_log_prob = self.actor.sample(torch.from_numpy(actor_obs).to(self.device)) - return self.actions + actions = np.clip(self.actions, -1, 1) + return actions + + def forward(self, actor_obs): + return self.act(actor_obs) + def step(self, value_obs, rews, dones): self.storage.add_transitions(self.actor_obs, value_obs, self.actions, self.actor.action_mean, self.actor.distribution.std_np, rews, dones, @@ -89,7 +94,7 @@ def update(self, actor_obs, value_obs, log_this_iteration, update): # Learning step self.storage.compute_returns(last_values.to(self.device), self.critic, self.gamma, self.lam) mean_value_loss, mean_surrogate_loss, infos = self._train_step(log_this_iteration) - self.storage.clear() + # self.storage.clear() if log_this_iteration: self.log({**locals(), **infos, 'it': update}) @@ -105,6 +110,7 @@ def log(self, variables): def _train_step(self, log_this_iteration): mean_value_loss = 0 mean_surrogate_loss = 0 + # cnnt = 0 for epoch in range(self.num_learning_epochs): for actor_obs_batch, critic_obs_batch, actions_batch, old_sigma_batch, old_mu_batch, current_values_batch, advantages_batch, returns_batch, old_actions_log_prob_batch \ in self.batch_sampler(self.num_mini_batches): @@ -164,5 +170,5 @@ def _train_step(self, log_this_iteration): num_updates = self.num_learning_epochs * self.num_mini_batches mean_value_loss /= num_updates mean_surrogate_loss /= num_updates - + # print('cnnt ', cnnt) return mean_value_loss, mean_surrogate_loss, locals() diff --git a/raisimGymTorch/raisimGymTorch/algo/ppo/storage.py b/raisimGymTorch/raisimGymTorch/algo/ppo/storage.py index 32f6689cc..33cb7188b 100755 --- a/raisimGymTorch/raisimGymTorch/algo/ppo/storage.py +++ b/raisimGymTorch/raisimGymTorch/algo/ppo/storage.py @@ -41,7 +41,9 @@ def __init__(self, num_envs, num_transitions_per_env, actor_obs_shape, critic_ob def add_transitions(self, actor_obs, critic_obs, actions, mu, sigma, rewards, dones, actions_log_prob): if self.step >= self.num_transitions_per_env: - raise AssertionError("Rollout buffer overflow") + self.clear() + # raise AssertionError("Rollout buffer overflow") + print("Rollout buffer overflow") self.critic_obs[self.step] = critic_obs self.actor_obs[self.step] = actor_obs self.actions[self.step] = actions diff --git a/raisimGymTorch/raisimGymTorch/deploy_log/anay.py b/raisimGymTorch/raisimGymTorch/deploy_log/anay.py new file mode 100644 index 000000000..9e904cedb --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_log/anay.py @@ -0,0 +1,70 @@ +import re +import pandas as pd +from draw_map import Drawer +ans_list = [] +import numpy as np +drawer = Drawer('reward') +with open("./train.log", 'r') as f: + lines = f.readlines() + for line in lines: + # x = re.search("work_action", line) + # print(x) + if "average" in line: + line = line.strip() + # print(line[-20:]) + x = float(line[-21:]) + ans_list.append(x) + drawer.add_map_list([x]) + + +# with open("./acc_60.log", 'r') as f: +# lines = f.readlines() +# for line in lines: +# tmmp = False +# +# # x = re.search("work_action", line) +# # print(x) +# if "vel [" in line: +# if "Ini" in line : +# continue +# print("line ",line) +# # print(line) +# line = line.strip().split('l [')[1].split(']')[0].strip() +# if ',' in line: +# line = line.split(',') +# else: +# line=line.split(' ') +# # print(line) +# x = [] +# it =0 +# for i in line: +# # it +=1 +# # if it ==1: +# # continue +# if i == '' : +# continue +# if ']' in i : +# i = i.split(']')[0] +# i = float(i.strip()) +# if abs(i) > 100 : +# tmmp = True +# x.append(0) +# continue +# x.append(i) +# # print() +# break +# # print(line[-20:]) +# # x = list(line[-21:]) +# if tmmp == True: +# continue +# print(x) +# # assert len(x) == 1 +# ans_list.append(x) +# drawer.add_map_list(x) + +drawer.draw(["reward"]) +# drawer.draw(['x',y','z']) +df = np.array(ans_list) +dd = pd.DataFrame(df).to_csv('./reward.csv') + + diff --git a/raisimGymTorch/raisimGymTorch/deploy_log/best.csv b/raisimGymTorch/raisimGymTorch/deploy_log/best.csv new file mode 100644 index 000000000..66a7915f4 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_log/best.csv @@ -0,0 +1,301 @@ +,0 +0,0.0105059573 +1,0.0003033897 +2,0.003917296 +3,0.0134380984 +4,0.0004019245 +5,0.0037282128 +6,0.0206206447 +7,0.0109507057 +8,0.0189535058 +9,0.0034565726 +10,-0.0048631438 +11,0.0003007252 +12,0.0079573121 +13,0.0274676303 +14,0.0139254566 +15,0.0062262583 +16,0.0347966491 +17,-0.00357151 +18,0.0074406599 +19,-0.003733962 +20,-0.0003730551 +21,0.006990587 +22,0.0381469058 +23,0.0206179801 +24,0.0437422064 +25,0.0369591363 +26,0.0427408564 +27,0.0233104377 +28,0.041414605 +29,0.0486637289 +30,0.047563844 +31,0.0263730711 +32,0.018490115 +33,0.0363279674 +34,0.0465438526 +35,0.0215447599 +36,0.0307433185 +37,0.0538355878 +38,0.0143568876 +39,0.0149560984 +40,0.0306208138 +41,0.0346102288 +42,0.0330256459 +43,0.0197418018 +44,0.0432149019 +45,0.0271587041 +46,0.0649409691 +47,0.0404931522 +48,0.0880119334 +49,0.0735003694 +50,0.0855085618 +51,0.0823447261 +52,0.083724243 +53,0.0963929021 +54,0.0743525787 +55,0.0864539826 +56,0.0744697595 +57,0.0436250293 +58,0.0689223941 +59,0.0668664348 +60,0.0745896006 +61,0.0563815682 +62,0.0765150665 +63,0.0873061945 +64,0.0875804999 +65,0.0915992107 +66,0.1039163313 +67,0.1161748599 +68,0.1051413845 +69,0.1079456927 +70,0.1159511559 +71,0.104784519 +72,0.1197568119 +73,0.0809785241 +74,0.1102892732 +75,0.113714102 +76,0.1081161344 +77,0.1031812972 +78,0.1297543183 +79,0.1043930366 +80,0.1357118092 +81,0.1312483523 +82,0.1267103257 +83,0.1414136356 +84,0.1435734627 +85,0.1375840119 +86,0.1446333986 +87,0.1177088405 +88,0.129205708 +89,0.1290618959 +90,0.1341005953 +91,0.1405667485 +92,0.1417918043 +93,0.1426786396 +94,0.1494244256 +95,0.173483421 +96,0.1628094731 +97,0.1494057815 +98,0.1303934752 +99,0.131701089 +100,0.1300925401 +101,0.1416719626 +102,0.15579737 +103,0.145054178 +104,0.1641783369 +105,0.1928046542 +106,0.1445961149 +107,0.164492591 +108,0.1490675596 +109,0.1662582674 +110,0.1477093483 +111,0.142907671 +112,0.162830778 +113,0.1774488702 +114,0.2056597358 +115,0.1816140531 +116,0.1792491671 +117,0.1689880067 +118,0.1626123988 +119,0.1623673877 +120,0.1919151578 +121,0.1508279077 +122,0.2163976002 +123,0.2074413933 +124,0.2190447794 +125,0.1987967689 +126,0.2154601658 +127,0.1803623657 +128,0.1846713609 +129,0.1883465233 +130,0.2057103324 +131,0.1908445666 +132,0.2122989937 +133,0.1951748686 +134,0.1781492815 +135,0.1327130893 +136,0.200764844 +137,0.2044240257 +138,0.2053774372 +139,0.2260355799 +140,0.2379798566 +141,0.2045065855 +142,0.2061311121 +143,0.2115320043 +144,0.1891960719 +145,0.2135586702 +146,0.2294470894 +147,0.2089141163 +148,0.2572771208 +149,0.2070472387 +150,0.207273609 +151,0.2030178778 +152,0.2093375586 +153,0.2133988789 +154,0.2290076644 +155,0.222397699 +156,0.2302007606 +157,0.1870761949 +158,0.2034519744 +159,0.2316468585 +160,0.2582651526 +161,0.2188903206 +162,0.2406297023 +163,0.2558736338 +164,0.1954545012 +165,0.1700372918 +166,0.2260781898 +167,0.2413727226 +168,0.2051803675 +169,0.2326615231 +170,0.2614795919 +171,0.2123549228 +172,0.1625458228 +173,0.148260625 +174,0.2660735414 +175,0.25523714 +176,0.2019659288 +177,0.1793450411 +178,0.254020073 +179,0.2445578624 +180,0.2493062802 +181,0.2404352908 +182,0.2651520879 +183,0.2319850826 +184,0.2597352186 +185,0.2492317101 +186,0.2469653596 +187,0.2383819921 +188,0.2526831681 +189,0.2636607178 +190,0.2625368626 +191,0.176143922 +192,0.2464140893 +193,0.2369199175 +194,0.2513968611 +195,0.2537670746 +196,0.1782371658 +197,0.2440438722 +198,0.2562624567 +199,0.2542784 +200,0.2656500987 +201,0.1876274717 +202,0.2796077258 +203,0.2843747837 +204,0.2116278781 +205,0.2706488523 +206,0.2818580969 +207,0.2611040827 +208,0.1787911038 +209,0.1712916423 +210,0.1731052552 +211,0.2500066929 +212,0.2684943575 +213,0.1727084427 +214,0.2567844369 +215,0.2498282598 +216,0.2421769982 +217,0.2694317891 +218,0.2664304029 +219,0.2512930004 +220,0.2643957504 +221,0.2473408674 +222,0.2749951288 +223,0.2704038403 +224,0.2740070964 +225,0.2259237244 +226,0.2368852963 +227,0.2715463382 +228,0.1897979485 +229,0.1866261213 +230,0.187654104 +231,0.3045056174 +232,0.259229218 +233,0.2650162686 +234,0.1877632944 +235,0.1965330804 +236,0.2917970113 +237,0.282486601 +238,0.2660415834 +239,0.2894640828 +240,0.2519747662 +241,0.2566060037 +242,0.2961219858 +243,0.2372980855 +244,0.2759725104 +245,0.2839859627 +246,0.2832695702 +247,0.2938556362 +248,0.2768699961 +249,0.2912830229 +250,0.2845425623 +251,0.2945480579 +252,0.2780843983 +253,0.269932462 +254,0.2402968052 +255,0.2105599513 +256,0.3051208062 +257,0.2853468359 +258,0.2267945786 +259,0.2409066685 +260,0.2761855609 +261,0.2911898124 +262,0.2950913394 +263,0.2778766703 +264,0.2948942686 +265,0.3088092843 +266,0.2923669284 +267,0.281618412 +268,0.2872589863 +269,0.2208450788 +270,0.2057689235 +271,0.2655835197 +272,0.2952751003 +273,0.300926327 +274,0.3070862169 +275,0.2153616264 +276,0.3156429538 +277,0.2892377137 +278,0.2871924072 +279,0.2728832422 +280,0.205534567 +281,0.2799965454 +282,0.2581186785 +283,0.2361289588 +284,0.3108812238 +285,0.2908915356 +286,0.2647606028 +287,0.2824386636 +288,0.244967989 +289,0.2870619113 +290,0.2899567661 +291,0.2229329977 +292,0.2301102155 +293,0.2324617889 +294,0.2300596169 +295,0.2079873361 +296,0.2248158529 +297,0.2176253174 +298,0.2979222807 +299,0.2856317927 diff --git a/raisimGymTorch/raisimGymTorch/deploy_log/best.log b/raisimGymTorch/raisimGymTorch/deploy_log/best.log new file mode 100644 index 000000000..d6f1306fb --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_log/best.log @@ -0,0 +1,1804 @@ +2023-08-23,17:35:45.008 - INFO - actural position [-0.03906593844294548, 0.7168829441070557, -1.468322992324829, 0.040372349321842194, 0.7116150856018066, -1.4694186449050903, -0.041678763926029205, 0.6693463325500488, -1.3866090774536133, 0.04757868871092796, 0.6757099628448486, -1.3807090520858765] +2023-08-23,17:35:50.093 - INFO - actual zero angle : (0.04371739588677883, 0.03283835276961326) +2023-08-23,17:35:50.113 - INFO - pre take action the first time +2023-08-23,17:35:54.748 - INFO - ---------------------------------------------------- +2023-08-23,17:35:54.748 - INFO - 0th iteration +2023-08-23,17:35:54.748 - INFO - average ll reward: 0.0105059573 +2023-08-23,17:35:54.748 - INFO - ---------------------------------------------------- + +2023-08-23,17:35:54.993 - INFO - updating finished +2023-08-23,17:35:59.548 - INFO - ---------------------------------------------------- +2023-08-23,17:35:59.548 - INFO - 1th iteration +2023-08-23,17:35:59.548 - INFO - average ll reward: 0.0003033897 +2023-08-23,17:35:59.548 - INFO - ---------------------------------------------------- + +2023-08-23,17:35:59.849 - INFO - updating finished +2023-08-23,17:36:04.442 - INFO - ---------------------------------------------------- +2023-08-23,17:36:04.442 - INFO - 2th iteration +2023-08-23,17:36:04.442 - INFO - average ll reward: 0.0039172960 +2023-08-23,17:36:04.442 - INFO - ---------------------------------------------------- + +2023-08-23,17:36:04.762 - INFO - updating finished +2023-08-23,17:36:09.258 - INFO - ---------------------------------------------------- +2023-08-23,17:36:09.259 - INFO - 3th iteration +2023-08-23,17:36:09.259 - INFO - average ll reward: 0.0134380984 +2023-08-23,17:36:09.259 - INFO - ---------------------------------------------------- + +2023-08-23,17:36:09.750 - INFO - updating finished +2023-08-23,17:36:14.322 - INFO - ---------------------------------------------------- +2023-08-23,17:36:14.323 - INFO - 4th iteration +2023-08-23,17:36:14.328 - INFO - average ll reward: 0.0004019245 +2023-08-23,17:36:14.328 - INFO - ---------------------------------------------------- + +2023-08-23,17:36:14.668 - INFO - updating finished +2023-08-23,17:36:19.243 - INFO - ---------------------------------------------------- +2023-08-23,17:36:19.243 - INFO - 5th iteration +2023-08-23,17:36:19.243 - INFO - average ll reward: 0.0037282128 +2023-08-23,17:36:19.243 - INFO - ---------------------------------------------------- + +2023-08-23,17:36:19.572 - INFO - updating finished +2023-08-23,17:36:24.215 - INFO - ---------------------------------------------------- +2023-08-23,17:36:24.215 - INFO - 6th iteration +2023-08-23,17:36:24.215 - INFO - average ll reward: 0.0206206447 +2023-08-23,17:36:24.215 - INFO - ---------------------------------------------------- + +2023-08-23,17:36:24.447 - INFO - updating finished +2023-08-23,17:36:29.071 - INFO - ---------------------------------------------------- +2023-08-23,17:36:29.071 - INFO - 7th iteration +2023-08-23,17:36:29.071 - INFO - average ll reward: 0.0109507057 +2023-08-23,17:36:29.071 - INFO - ---------------------------------------------------- + +2023-08-23,17:36:29.337 - INFO - updating finished +2023-08-23,17:36:33.957 - INFO - ---------------------------------------------------- +2023-08-23,17:36:33.957 - INFO - 8th iteration +2023-08-23,17:36:33.957 - INFO - average ll reward: 0.0189535058 +2023-08-23,17:36:33.957 - INFO - ---------------------------------------------------- + +2023-08-23,17:36:34.242 - INFO - updating finished +2023-08-23,17:36:38.836 - INFO - ---------------------------------------------------- +2023-08-23,17:36:38.836 - INFO - 9th iteration +2023-08-23,17:36:38.836 - INFO - average ll reward: 0.0034565726 +2023-08-23,17:36:38.836 - INFO - ---------------------------------------------------- + +2023-08-23,17:36:39.155 - INFO - updating finished +2023-08-23,17:36:43.780 - INFO - ---------------------------------------------------- +2023-08-23,17:36:43.781 - INFO - 10th iteration +2023-08-23,17:36:43.781 - INFO - average ll reward: -0.0048631438 +2023-08-23,17:36:43.781 - INFO - ---------------------------------------------------- + +2023-08-23,17:36:44.067 - INFO - updating finished +2023-08-23,17:36:48.713 - INFO - ---------------------------------------------------- +2023-08-23,17:36:48.714 - INFO - 11th iteration +2023-08-23,17:36:48.714 - INFO - average ll reward: 0.0003007252 +2023-08-23,17:36:48.714 - INFO - ---------------------------------------------------- + +2023-08-23,17:36:48.970 - INFO - updating finished +2023-08-23,17:36:53.607 - INFO - ---------------------------------------------------- +2023-08-23,17:36:53.607 - INFO - 12th iteration +2023-08-23,17:36:53.607 - INFO - average ll reward: 0.0079573121 +2023-08-23,17:36:53.607 - INFO - ---------------------------------------------------- + +2023-08-23,17:36:53.877 - INFO - updating finished +2023-08-23,17:36:58.525 - INFO - ---------------------------------------------------- +2023-08-23,17:36:58.525 - INFO - 13th iteration +2023-08-23,17:36:58.525 - INFO - average ll reward: 0.0274676303 +2023-08-23,17:36:58.525 - INFO - ---------------------------------------------------- + +2023-08-23,17:36:58.799 - INFO - updating finished +2023-08-23,17:37:03.491 - INFO - ---------------------------------------------------- +2023-08-23,17:37:03.491 - INFO - 14th iteration +2023-08-23,17:37:03.492 - INFO - average ll reward: 0.0139254566 +2023-08-23,17:37:03.492 - INFO - ---------------------------------------------------- + +2023-08-23,17:37:03.721 - INFO - updating finished +2023-08-23,17:37:08.334 - INFO - ---------------------------------------------------- +2023-08-23,17:37:08.334 - INFO - 15th iteration +2023-08-23,17:37:08.335 - INFO - average ll reward: 0.0062262583 +2023-08-23,17:37:08.335 - INFO - ---------------------------------------------------- + +2023-08-23,17:37:08.660 - INFO - updating finished +2023-08-23,17:37:13.293 - INFO - ---------------------------------------------------- +2023-08-23,17:37:13.293 - INFO - 16th iteration +2023-08-23,17:37:13.293 - INFO - average ll reward: 0.0347966491 +2023-08-23,17:37:13.293 - INFO - ---------------------------------------------------- + +2023-08-23,17:37:13.573 - INFO - updating finished +2023-08-23,17:37:18.038 - INFO - ---------------------------------------------------- +2023-08-23,17:37:18.038 - INFO - 17th iteration +2023-08-23,17:37:18.038 - INFO - average ll reward: -0.0035715100 +2023-08-23,17:37:18.038 - INFO - ---------------------------------------------------- + +2023-08-23,17:37:18.506 - INFO - updating finished +2023-08-23,17:37:23.125 - INFO - ---------------------------------------------------- +2023-08-23,17:37:23.125 - INFO - 18th iteration +2023-08-23,17:37:23.125 - INFO - average ll reward: 0.0074406599 +2023-08-23,17:37:23.125 - INFO - ---------------------------------------------------- + +2023-08-23,17:37:23.464 - INFO - updating finished +2023-08-23,17:37:28.073 - INFO - ---------------------------------------------------- +2023-08-23,17:37:28.073 - INFO - 19th iteration +2023-08-23,17:37:28.073 - INFO - average ll reward: -0.0037339620 +2023-08-23,17:37:28.073 - INFO - ---------------------------------------------------- + +2023-08-23,17:37:28.411 - INFO - updating finished +2023-08-23,17:37:32.988 - INFO - ---------------------------------------------------- +2023-08-23,17:37:32.988 - INFO - 20th iteration +2023-08-23,17:37:32.988 - INFO - average ll reward: -0.0003730551 +2023-08-23,17:37:32.988 - INFO - ---------------------------------------------------- + +2023-08-23,17:37:33.315 - INFO - updating finished +2023-08-23,17:37:37.923 - INFO - ---------------------------------------------------- +2023-08-23,17:37:37.923 - INFO - 21th iteration +2023-08-23,17:37:37.923 - INFO - average ll reward: 0.0069905870 +2023-08-23,17:37:37.923 - INFO - ---------------------------------------------------- + +2023-08-23,17:37:38.202 - INFO - updating finished +2023-08-23,17:37:42.829 - INFO - ---------------------------------------------------- +2023-08-23,17:37:42.829 - INFO - 22th iteration +2023-08-23,17:37:42.829 - INFO - average ll reward: 0.0381469058 +2023-08-23,17:37:42.829 - INFO - ---------------------------------------------------- + +2023-08-23,17:37:43.131 - INFO - updating finished +2023-08-23,17:37:47.713 - INFO - ---------------------------------------------------- +2023-08-23,17:37:47.713 - INFO - 23th iteration +2023-08-23,17:37:47.713 - INFO - average ll reward: 0.0206179801 +2023-08-23,17:37:47.713 - INFO - ---------------------------------------------------- + +2023-08-23,17:37:48.022 - INFO - updating finished +2023-08-23,17:37:52.607 - INFO - ---------------------------------------------------- +2023-08-23,17:37:52.607 - INFO - 24th iteration +2023-08-23,17:37:52.607 - INFO - average ll reward: 0.0437422064 +2023-08-23,17:37:52.607 - INFO - ---------------------------------------------------- + +2023-08-23,17:37:52.904 - INFO - updating finished +2023-08-23,17:37:57.518 - INFO - ---------------------------------------------------- +2023-08-23,17:37:57.518 - INFO - 25th iteration +2023-08-23,17:37:57.518 - INFO - average ll reward: 0.0369591363 +2023-08-23,17:37:57.518 - INFO - ---------------------------------------------------- + +2023-08-23,17:37:57.840 - INFO - updating finished +2023-08-23,17:38:02.469 - INFO - ---------------------------------------------------- +2023-08-23,17:38:02.469 - INFO - 26th iteration +2023-08-23,17:38:02.469 - INFO - average ll reward: 0.0427408564 +2023-08-23,17:38:02.469 - INFO - ---------------------------------------------------- + +2023-08-23,17:38:02.798 - INFO - updating finished +2023-08-23,17:38:07.429 - INFO - ---------------------------------------------------- +2023-08-23,17:38:07.429 - INFO - 27th iteration +2023-08-23,17:38:07.429 - INFO - average ll reward: 0.0233104377 +2023-08-23,17:38:07.430 - INFO - ---------------------------------------------------- + +2023-08-23,17:38:07.734 - INFO - updating finished +2023-08-23,17:38:12.355 - INFO - ---------------------------------------------------- +2023-08-23,17:38:12.355 - INFO - 28th iteration +2023-08-23,17:38:12.355 - INFO - average ll reward: 0.0414146050 +2023-08-23,17:38:12.355 - INFO - ---------------------------------------------------- + +2023-08-23,17:38:12.691 - INFO - updating finished +2023-08-23,17:38:17.331 - INFO - ---------------------------------------------------- +2023-08-23,17:38:17.331 - INFO - 29th iteration +2023-08-23,17:38:17.331 - INFO - average ll reward: 0.0486637289 +2023-08-23,17:38:17.331 - INFO - ---------------------------------------------------- + +2023-08-23,17:38:17.630 - INFO - updating finished +2023-08-23,17:38:22.229 - INFO - ---------------------------------------------------- +2023-08-23,17:38:22.229 - INFO - 30th iteration +2023-08-23,17:38:22.229 - INFO - average ll reward: 0.0475638440 +2023-08-23,17:38:22.229 - INFO - ---------------------------------------------------- + +2023-08-23,17:38:22.551 - INFO - updating finished +2023-08-23,17:38:27.134 - INFO - ---------------------------------------------------- +2023-08-23,17:38:27.134 - INFO - 31th iteration +2023-08-23,17:38:27.135 - INFO - average ll reward: 0.0263730711 +2023-08-23,17:38:27.135 - INFO - ---------------------------------------------------- + +2023-08-23,17:38:27.437 - INFO - updating finished +2023-08-23,17:38:32.049 - INFO - ---------------------------------------------------- +2023-08-23,17:38:32.049 - INFO - 32th iteration +2023-08-23,17:38:32.050 - INFO - average ll reward: 0.0184901150 +2023-08-23,17:38:32.050 - INFO - ---------------------------------------------------- + +2023-08-23,17:38:32.327 - INFO - updating finished +2023-08-23,17:38:36.942 - INFO - ---------------------------------------------------- +2023-08-23,17:38:36.942 - INFO - 33th iteration +2023-08-23,17:38:36.942 - INFO - average ll reward: 0.0363279674 +2023-08-23,17:38:36.942 - INFO - ---------------------------------------------------- + +2023-08-23,17:38:37.240 - INFO - updating finished +2023-08-23,17:38:41.918 - INFO - ---------------------------------------------------- +2023-08-23,17:38:41.918 - INFO - 34th iteration +2023-08-23,17:38:41.918 - INFO - average ll reward: 0.0465438526 +2023-08-23,17:38:41.918 - INFO - ---------------------------------------------------- + +2023-08-23,17:38:42.205 - INFO - updating finished +2023-08-23,17:38:46.796 - INFO - ---------------------------------------------------- +2023-08-23,17:38:46.796 - INFO - 35th iteration +2023-08-23,17:38:46.796 - INFO - average ll reward: 0.0215447599 +2023-08-23,17:38:46.796 - INFO - ---------------------------------------------------- + +2023-08-23,17:38:47.162 - INFO - updating finished +2023-08-23,17:38:51.820 - INFO - ---------------------------------------------------- +2023-08-23,17:38:51.820 - INFO - 36th iteration +2023-08-23,17:38:51.826 - INFO - average ll reward: 0.0307433185 +2023-08-23,17:38:51.826 - INFO - ---------------------------------------------------- + +2023-08-23,17:38:52.110 - INFO - updating finished +2023-08-23,17:38:56.768 - INFO - ---------------------------------------------------- +2023-08-23,17:38:56.768 - INFO - 37th iteration +2023-08-23,17:38:56.768 - INFO - average ll reward: 0.0538355878 +2023-08-23,17:38:56.768 - INFO - ---------------------------------------------------- + +2023-08-23,17:38:57.053 - INFO - updating finished +2023-08-23,17:39:01.708 - INFO - ---------------------------------------------------- +2023-08-23,17:39:01.709 - INFO - 38th iteration +2023-08-23,17:39:01.709 - INFO - average ll reward: 0.0143568876 +2023-08-23,17:39:01.709 - INFO - ---------------------------------------------------- + +2023-08-23,17:39:01.995 - INFO - updating finished +2023-08-23,17:39:06.544 - INFO - ---------------------------------------------------- +2023-08-23,17:39:06.544 - INFO - 39th iteration +2023-08-23,17:39:06.550 - INFO - average ll reward: 0.0149560984 +2023-08-23,17:39:06.550 - INFO - ---------------------------------------------------- + +2023-08-23,17:39:06.894 - INFO - updating finished +2023-08-23,17:39:11.458 - INFO - ---------------------------------------------------- +2023-08-23,17:39:11.458 - INFO - 40th iteration +2023-08-23,17:39:11.458 - INFO - average ll reward: 0.0306208138 +2023-08-23,17:39:11.458 - INFO - ---------------------------------------------------- + +2023-08-23,17:39:11.790 - INFO - updating finished +2023-08-23,17:39:16.190 - INFO - ---------------------------------------------------- +2023-08-23,17:39:16.190 - INFO - 41th iteration +2023-08-23,17:39:16.190 - INFO - average ll reward: 0.0346102288 +2023-08-23,17:39:16.190 - INFO - ---------------------------------------------------- + +2023-08-23,17:39:16.672 - INFO - updating finished +2023-08-23,17:39:21.224 - INFO - ---------------------------------------------------- +2023-08-23,17:39:21.224 - INFO - 42th iteration +2023-08-23,17:39:21.224 - INFO - average ll reward: 0.0330256459 +2023-08-23,17:39:21.224 - INFO - ---------------------------------------------------- + +2023-08-23,17:39:21.545 - INFO - updating finished +2023-08-23,17:39:25.967 - INFO - ---------------------------------------------------- +2023-08-23,17:39:25.967 - INFO - 43th iteration +2023-08-23,17:39:25.967 - INFO - average ll reward: 0.0197418018 +2023-08-23,17:39:25.967 - INFO - ---------------------------------------------------- + +2023-08-23,17:39:26.465 - INFO - updating finished +2023-08-23,17:39:31.106 - INFO - ---------------------------------------------------- +2023-08-23,17:39:31.106 - INFO - 44th iteration +2023-08-23,17:39:31.106 - INFO - average ll reward: 0.0432149019 +2023-08-23,17:39:31.106 - INFO - ---------------------------------------------------- + +2023-08-23,17:39:31.448 - INFO - updating finished +2023-08-23,17:39:36.187 - INFO - ---------------------------------------------------- +2023-08-23,17:39:36.187 - INFO - 45th iteration +2023-08-23,17:39:36.193 - INFO - average ll reward: 0.0271587041 +2023-08-23,17:39:36.194 - INFO - ---------------------------------------------------- + +2023-08-23,17:39:36.448 - INFO - updating finished +2023-08-23,17:39:41.107 - INFO - ---------------------------------------------------- +2023-08-23,17:39:41.107 - INFO - 46th iteration +2023-08-23,17:39:41.107 - INFO - average ll reward: 0.0649409691 +2023-08-23,17:39:41.107 - INFO - ---------------------------------------------------- + +2023-08-23,17:39:41.375 - INFO - updating finished +2023-08-23,17:39:46.036 - INFO - ---------------------------------------------------- +2023-08-23,17:39:46.036 - INFO - 47th iteration +2023-08-23,17:39:46.036 - INFO - average ll reward: 0.0404931522 +2023-08-23,17:39:46.036 - INFO - ---------------------------------------------------- + +2023-08-23,17:39:46.291 - INFO - updating finished +2023-08-23,17:39:50.935 - INFO - ---------------------------------------------------- +2023-08-23,17:39:50.936 - INFO - 48th iteration +2023-08-23,17:39:50.936 - INFO - average ll reward: 0.0880119334 +2023-08-23,17:39:50.936 - INFO - ---------------------------------------------------- + +2023-08-23,17:39:51.202 - INFO - updating finished +2023-08-23,17:39:55.820 - INFO - ---------------------------------------------------- +2023-08-23,17:39:55.820 - INFO - 49th iteration +2023-08-23,17:39:55.820 - INFO - average ll reward: 0.0735003694 +2023-08-23,17:39:55.820 - INFO - ---------------------------------------------------- + +2023-08-23,17:39:56.100 - INFO - updating finished +2023-08-23,17:40:00.678 - INFO - ---------------------------------------------------- +2023-08-23,17:40:00.679 - INFO - 50th iteration +2023-08-23,17:40:00.679 - INFO - average ll reward: 0.0855085618 +2023-08-23,17:40:00.679 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:00.987 - INFO - updating finished +2023-08-23,17:40:05.596 - INFO - ---------------------------------------------------- +2023-08-23,17:40:05.596 - INFO - 51th iteration +2023-08-23,17:40:05.597 - INFO - average ll reward: 0.0823447261 +2023-08-23,17:40:05.597 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:05.874 - INFO - updating finished +2023-08-23,17:40:10.369 - INFO - ---------------------------------------------------- +2023-08-23,17:40:10.369 - INFO - 52th iteration +2023-08-23,17:40:10.369 - INFO - average ll reward: 0.0837242430 +2023-08-23,17:40:10.369 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:10.747 - INFO - updating finished +2023-08-23,17:40:15.379 - INFO - ---------------------------------------------------- +2023-08-23,17:40:15.379 - INFO - 53th iteration +2023-08-23,17:40:15.379 - INFO - average ll reward: 0.0963929021 +2023-08-23,17:40:15.379 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:15.652 - INFO - updating finished +2023-08-23,17:40:20.323 - INFO - ---------------------------------------------------- +2023-08-23,17:40:20.323 - INFO - 54th iteration +2023-08-23,17:40:20.323 - INFO - average ll reward: 0.0743525787 +2023-08-23,17:40:20.323 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:20.583 - INFO - updating finished +2023-08-23,17:40:25.169 - INFO - ---------------------------------------------------- +2023-08-23,17:40:25.170 - INFO - 55th iteration +2023-08-23,17:40:25.170 - INFO - average ll reward: 0.0864539826 +2023-08-23,17:40:25.170 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:25.532 - INFO - updating finished +2023-08-23,17:40:30.221 - INFO - ---------------------------------------------------- +2023-08-23,17:40:30.221 - INFO - 56th iteration +2023-08-23,17:40:30.227 - INFO - average ll reward: 0.0744697595 +2023-08-23,17:40:30.227 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:30.512 - INFO - updating finished +2023-08-23,17:40:35.067 - INFO - ---------------------------------------------------- +2023-08-23,17:40:35.067 - INFO - 57th iteration +2023-08-23,17:40:35.067 - INFO - average ll reward: 0.0436250293 +2023-08-23,17:40:35.067 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:35.411 - INFO - updating finished +2023-08-23,17:40:39.990 - INFO - ---------------------------------------------------- +2023-08-23,17:40:39.990 - INFO - 58th iteration +2023-08-23,17:40:39.990 - INFO - average ll reward: 0.0689223941 +2023-08-23,17:40:39.990 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:40.323 - INFO - updating finished +2023-08-23,17:40:44.898 - INFO - ---------------------------------------------------- +2023-08-23,17:40:44.898 - INFO - 59th iteration +2023-08-23,17:40:44.898 - INFO - average ll reward: 0.0668664348 +2023-08-23,17:40:44.898 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:45.224 - INFO - updating finished +2023-08-23,17:40:49.843 - INFO - ---------------------------------------------------- +2023-08-23,17:40:49.843 - INFO - 60th iteration +2023-08-23,17:40:49.843 - INFO - average ll reward: 0.0745896006 +2023-08-23,17:40:49.843 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:50.125 - INFO - updating finished +2023-08-23,17:40:54.724 - INFO - ---------------------------------------------------- +2023-08-23,17:40:54.725 - INFO - 61th iteration +2023-08-23,17:40:54.725 - INFO - average ll reward: 0.0563815682 +2023-08-23,17:40:54.726 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:54.998 - INFO - updating finished +2023-08-23,17:40:59.637 - INFO - ---------------------------------------------------- +2023-08-23,17:40:59.637 - INFO - 62th iteration +2023-08-23,17:40:59.637 - INFO - average ll reward: 0.0765150665 +2023-08-23,17:40:59.637 - INFO - ---------------------------------------------------- + +2023-08-23,17:40:59.884 - INFO - updating finished +2023-08-23,17:41:04.479 - INFO - ---------------------------------------------------- +2023-08-23,17:41:04.480 - INFO - 63th iteration +2023-08-23,17:41:04.480 - INFO - average ll reward: 0.0873061945 +2023-08-23,17:41:04.480 - INFO - ---------------------------------------------------- + +2023-08-23,17:41:04.804 - INFO - updating finished +2023-08-23,17:41:09.332 - INFO - ---------------------------------------------------- +2023-08-23,17:41:09.332 - INFO - 64th iteration +2023-08-23,17:41:09.332 - INFO - average ll reward: 0.0875804999 +2023-08-23,17:41:09.332 - INFO - ---------------------------------------------------- + +2023-08-23,17:41:09.714 - INFO - updating finished +2023-08-23,17:41:14.424 - INFO - ---------------------------------------------------- +2023-08-23,17:41:14.425 - INFO - 65th iteration +2023-08-23,17:41:14.425 - INFO - average ll reward: 0.0915992107 +2023-08-23,17:41:14.425 - INFO - ---------------------------------------------------- + +2023-08-23,17:41:14.677 - INFO - updating finished +2023-08-23,17:41:19.360 - INFO - ---------------------------------------------------- +2023-08-23,17:41:19.361 - INFO - 66th iteration +2023-08-23,17:41:19.361 - INFO - average ll reward: 0.1039163313 +2023-08-23,17:41:19.361 - INFO - ---------------------------------------------------- + +2023-08-23,17:41:19.631 - INFO - updating finished +2023-08-23,17:41:24.258 - INFO - ---------------------------------------------------- +2023-08-23,17:41:24.258 - INFO - 67th iteration +2023-08-23,17:41:24.259 - INFO - average ll reward: 0.1161748599 +2023-08-23,17:41:24.259 - INFO - ---------------------------------------------------- + +2023-08-23,17:41:24.553 - INFO - updating finished +2023-08-23,17:41:29.180 - INFO - ---------------------------------------------------- +2023-08-23,17:41:29.180 - INFO - 68th iteration +2023-08-23,17:41:29.180 - INFO - average ll reward: 0.1051413845 +2023-08-23,17:41:29.180 - INFO - ---------------------------------------------------- + +2023-08-23,17:41:29.445 - INFO - updating finished +2023-08-23,17:41:34.059 - INFO - ---------------------------------------------------- +2023-08-23,17:41:34.059 - INFO - 69th iteration +2023-08-23,17:41:34.059 - INFO - average ll reward: 0.1079456927 +2023-08-23,17:41:34.059 - INFO - ---------------------------------------------------- + +2023-08-23,17:41:34.369 - INFO - updating finished +2023-08-23,17:41:38.950 - INFO - ---------------------------------------------------- +2023-08-23,17:41:38.950 - INFO - 70th iteration +2023-08-23,17:41:38.950 - INFO - average ll reward: 0.1159511559 +2023-08-23,17:41:38.950 - INFO - ---------------------------------------------------- + +2023-08-23,17:41:39.259 - INFO - updating finished +2023-08-23,17:41:43.802 - INFO - ---------------------------------------------------- +2023-08-23,17:41:43.803 - INFO - 71th iteration +2023-08-23,17:41:43.803 - INFO - average ll reward: 0.1047845190 +2023-08-23,17:41:43.803 - INFO - ---------------------------------------------------- + +2023-08-23,17:41:44.134 - INFO - updating finished +2023-08-23,17:41:48.682 - INFO - ---------------------------------------------------- +2023-08-23,17:41:48.682 - INFO - 72th iteration +2023-08-23,17:41:48.682 - INFO - average ll reward: 0.1197568119 +2023-08-23,17:41:48.682 - INFO - ---------------------------------------------------- + +2023-08-23,17:41:49.014 - INFO - updating finished +2023-08-23,17:41:53.622 - INFO - ---------------------------------------------------- +2023-08-23,17:41:53.622 - INFO - 73th iteration +2023-08-23,17:41:53.622 - INFO - average ll reward: 0.0809785241 +2023-08-23,17:41:53.622 - INFO - ---------------------------------------------------- + +2023-08-23,17:41:53.904 - INFO - updating finished +2023-08-23,17:41:58.576 - INFO - ---------------------------------------------------- +2023-08-23,17:41:58.577 - INFO - 74th iteration +2023-08-23,17:41:58.577 - INFO - average ll reward: 0.1102892732 +2023-08-23,17:41:58.577 - INFO - ---------------------------------------------------- + +2023-08-23,17:41:58.882 - INFO - updating finished +2023-08-23,17:42:03.537 - INFO - ---------------------------------------------------- +2023-08-23,17:42:03.537 - INFO - 75th iteration +2023-08-23,17:42:03.537 - INFO - average ll reward: 0.1137141020 +2023-08-23,17:42:03.537 - INFO - ---------------------------------------------------- + +2023-08-23,17:42:03.804 - INFO - updating finished +2023-08-23,17:42:08.465 - INFO - ---------------------------------------------------- +2023-08-23,17:42:08.465 - INFO - 76th iteration +2023-08-23,17:42:08.465 - INFO - average ll reward: 0.1081161344 +2023-08-23,17:42:08.466 - INFO - ---------------------------------------------------- + +2023-08-23,17:42:08.738 - INFO - updating finished +2023-08-23,17:42:13.390 - INFO - ---------------------------------------------------- +2023-08-23,17:42:13.390 - INFO - 77th iteration +2023-08-23,17:42:13.390 - INFO - average ll reward: 0.1031812972 +2023-08-23,17:42:13.390 - INFO - ---------------------------------------------------- + +2023-08-23,17:42:13.670 - INFO - updating finished +2023-08-23,17:42:18.281 - INFO - ---------------------------------------------------- +2023-08-23,17:42:18.282 - INFO - 78th iteration +2023-08-23,17:42:18.282 - INFO - average ll reward: 0.1297543183 +2023-08-23,17:42:18.282 - INFO - ---------------------------------------------------- + +2023-08-23,17:42:18.618 - INFO - updating finished +2023-08-23,17:42:23.191 - INFO - ---------------------------------------------------- +2023-08-23,17:42:23.191 - INFO - 79th iteration +2023-08-23,17:42:23.191 - INFO - average ll reward: 0.1043930366 +2023-08-23,17:42:23.191 - INFO - ---------------------------------------------------- + +2023-08-23,17:42:23.532 - INFO - updating finished +2023-08-23,17:42:28.131 - INFO - ---------------------------------------------------- +2023-08-23,17:42:28.131 - INFO - 80th iteration +2023-08-23,17:42:28.131 - INFO - average ll reward: 0.1357118092 +2023-08-23,17:42:28.131 - INFO - ---------------------------------------------------- + +2023-08-23,17:42:28.418 - INFO - updating finished +2023-08-23,17:42:33.038 - INFO - ---------------------------------------------------- +2023-08-23,17:42:33.038 - INFO - 81th iteration +2023-08-23,17:42:33.039 - INFO - average ll reward: 0.1312483523 +2023-08-23,17:42:33.040 - INFO - ---------------------------------------------------- + +2023-08-23,17:42:33.326 - INFO - updating finished +2023-08-23,17:42:37.966 - INFO - ---------------------------------------------------- +2023-08-23,17:42:37.966 - INFO - 82th iteration +2023-08-23,17:42:37.966 - INFO - average ll reward: 0.1267103257 +2023-08-23,17:42:37.966 - INFO - ---------------------------------------------------- + +2023-08-23,17:42:38.236 - INFO - updating finished +2023-08-23,17:42:42.855 - INFO - ---------------------------------------------------- +2023-08-23,17:42:42.856 - INFO - 83th iteration +2023-08-23,17:42:42.856 - INFO - average ll reward: 0.1414136356 +2023-08-23,17:42:42.856 - INFO - ---------------------------------------------------- + +2023-08-23,17:42:43.117 - INFO - updating finished +2023-08-23,17:42:47.719 - INFO - ---------------------------------------------------- +2023-08-23,17:42:47.719 - INFO - 84th iteration +2023-08-23,17:42:47.719 - INFO - average ll reward: 0.1435734627 +2023-08-23,17:42:47.719 - INFO - ---------------------------------------------------- + +2023-08-23,17:42:48.030 - INFO - updating finished +2023-08-23,17:42:52.630 - INFO - ---------------------------------------------------- +2023-08-23,17:42:52.630 - INFO - 85th iteration +2023-08-23,17:42:52.630 - INFO - average ll reward: 0.1375840119 +2023-08-23,17:42:52.630 - INFO - ---------------------------------------------------- + +2023-08-23,17:42:52.954 - INFO - updating finished +2023-08-23,17:42:57.665 - INFO - ---------------------------------------------------- +2023-08-23,17:42:57.665 - INFO - 86th iteration +2023-08-23,17:42:57.665 - INFO - average ll reward: 0.1446333986 +2023-08-23,17:42:57.665 - INFO - ---------------------------------------------------- + +2023-08-23,17:42:57.954 - INFO - updating finished +2023-08-23,17:43:02.623 - INFO - ---------------------------------------------------- +2023-08-23,17:43:02.623 - INFO - 87th iteration +2023-08-23,17:43:02.623 - INFO - average ll reward: 0.1177088405 +2023-08-23,17:43:02.623 - INFO - ---------------------------------------------------- + +2023-08-23,17:43:02.869 - INFO - updating finished +2023-08-23,17:43:07.460 - INFO - ---------------------------------------------------- +2023-08-23,17:43:07.460 - INFO - 88th iteration +2023-08-23,17:43:07.460 - INFO - average ll reward: 0.1292057080 +2023-08-23,17:43:07.460 - INFO - ---------------------------------------------------- + +2023-08-23,17:43:07.761 - INFO - updating finished +2023-08-23,17:43:12.378 - INFO - ---------------------------------------------------- +2023-08-23,17:43:12.378 - INFO - 89th iteration +2023-08-23,17:43:12.378 - INFO - average ll reward: 0.1290618959 +2023-08-23,17:43:12.378 - INFO - ---------------------------------------------------- + +2023-08-23,17:43:12.712 - INFO - updating finished +2023-08-23,17:43:17.252 - INFO - ---------------------------------------------------- +2023-08-23,17:43:17.252 - INFO - 90th iteration +2023-08-23,17:43:17.252 - INFO - average ll reward: 0.1341005953 +2023-08-23,17:43:17.252 - INFO - ---------------------------------------------------- + +2023-08-23,17:43:17.609 - INFO - updating finished +2023-08-23,17:43:22.189 - INFO - ---------------------------------------------------- +2023-08-23,17:43:22.189 - INFO - 91th iteration +2023-08-23,17:43:22.189 - INFO - average ll reward: 0.1405667485 +2023-08-23,17:43:22.189 - INFO - ---------------------------------------------------- + +2023-08-23,17:43:22.466 - INFO - updating finished +2023-08-23,17:43:27.001 - INFO - ---------------------------------------------------- +2023-08-23,17:43:27.001 - INFO - 92th iteration +2023-08-23,17:43:27.002 - INFO - average ll reward: 0.1417918043 +2023-08-23,17:43:27.002 - INFO - ---------------------------------------------------- + +2023-08-23,17:43:27.343 - INFO - updating finished +2023-08-23,17:43:31.892 - INFO - ---------------------------------------------------- +2023-08-23,17:43:31.892 - INFO - 93th iteration +2023-08-23,17:43:31.899 - INFO - average ll reward: 0.1426786396 +2023-08-23,17:43:31.899 - INFO - ---------------------------------------------------- + +2023-08-23,17:43:32.181 - INFO - updating finished +2023-08-23,17:43:36.752 - INFO - ---------------------------------------------------- +2023-08-23,17:43:36.752 - INFO - 94th iteration +2023-08-23,17:43:36.752 - INFO - average ll reward: 0.1494244256 +2023-08-23,17:43:36.752 - INFO - ---------------------------------------------------- + +2023-08-23,17:43:37.092 - INFO - updating finished +2023-08-23,17:43:41.742 - INFO - ---------------------------------------------------- +2023-08-23,17:43:41.742 - INFO - 95th iteration +2023-08-23,17:43:41.742 - INFO - average ll reward: 0.1734834210 +2023-08-23,17:43:41.742 - INFO - ---------------------------------------------------- + +2023-08-23,17:43:42.047 - INFO - updating finished +2023-08-23,17:43:46.692 - INFO - ---------------------------------------------------- +2023-08-23,17:43:46.692 - INFO - 96th iteration +2023-08-23,17:43:46.692 - INFO - average ll reward: 0.1628094731 +2023-08-23,17:43:46.692 - INFO - ---------------------------------------------------- + +2023-08-23,17:43:46.973 - INFO - updating finished +2023-08-23,17:43:51.600 - INFO - ---------------------------------------------------- +2023-08-23,17:43:51.600 - INFO - 97th iteration +2023-08-23,17:43:51.600 - INFO - average ll reward: 0.1494057815 +2023-08-23,17:43:51.600 - INFO - ---------------------------------------------------- + +2023-08-23,17:43:51.933 - INFO - updating finished +2023-08-23,17:43:56.603 - INFO - ---------------------------------------------------- +2023-08-23,17:43:56.603 - INFO - 98th iteration +2023-08-23,17:43:56.603 - INFO - average ll reward: 0.1303934752 +2023-08-23,17:43:56.603 - INFO - ---------------------------------------------------- + +2023-08-23,17:43:56.888 - INFO - updating finished +2023-08-23,17:44:01.451 - INFO - ---------------------------------------------------- +2023-08-23,17:44:01.451 - INFO - 99th iteration +2023-08-23,17:44:01.451 - INFO - average ll reward: 0.1317010890 +2023-08-23,17:44:01.451 - INFO - ---------------------------------------------------- + +2023-08-23,17:44:01.790 - INFO - updating finished +2023-08-23,17:44:06.368 - INFO - ---------------------------------------------------- +2023-08-23,17:44:06.368 - INFO - 100th iteration +2023-08-23,17:44:06.368 - INFO - average ll reward: 0.1300925401 +2023-08-23,17:44:06.368 - INFO - ---------------------------------------------------- + +2023-08-23,17:44:06.723 - INFO - updating finished +2023-08-23,17:44:11.380 - INFO - ---------------------------------------------------- +2023-08-23,17:44:11.380 - INFO - 101th iteration +2023-08-23,17:44:11.385 - INFO - average ll reward: 0.1416719626 +2023-08-23,17:44:11.385 - INFO - ---------------------------------------------------- + +2023-08-23,17:44:11.628 - INFO - updating finished +2023-08-23,17:44:16.190 - INFO - ---------------------------------------------------- +2023-08-23,17:44:16.191 - INFO - 102th iteration +2023-08-23,17:44:16.191 - INFO - average ll reward: 0.1557973700 +2023-08-23,17:44:16.191 - INFO - ---------------------------------------------------- + +2023-08-23,17:44:16.494 - INFO - updating finished +2023-08-23,17:44:21.101 - INFO - ---------------------------------------------------- +2023-08-23,17:44:21.101 - INFO - 103th iteration +2023-08-23,17:44:21.101 - INFO - average ll reward: 0.1450541780 +2023-08-23,17:44:21.101 - INFO - ---------------------------------------------------- + +2023-08-23,17:44:21.386 - INFO - updating finished +2023-08-23,17:44:25.998 - INFO - ---------------------------------------------------- +2023-08-23,17:44:25.998 - INFO - 104th iteration +2023-08-23,17:44:25.998 - INFO - average ll reward: 0.1641783369 +2023-08-23,17:44:25.998 - INFO - ---------------------------------------------------- + +2023-08-23,17:44:26.286 - INFO - updating finished +2023-08-23,17:44:30.733 - INFO - ---------------------------------------------------- +2023-08-23,17:44:30.734 - INFO - 105th iteration +2023-08-23,17:44:30.734 - INFO - average ll reward: 0.1928046542 +2023-08-23,17:44:30.734 - INFO - ---------------------------------------------------- + +2023-08-23,17:44:31.181 - INFO - updating finished +2023-08-23,17:44:35.736 - INFO - ---------------------------------------------------- +2023-08-23,17:44:35.736 - INFO - 106th iteration +2023-08-23,17:44:35.736 - INFO - average ll reward: 0.1445961149 +2023-08-23,17:44:35.736 - INFO - ---------------------------------------------------- + +2023-08-23,17:44:36.051 - INFO - updating finished +2023-08-23,17:44:40.604 - INFO - ---------------------------------------------------- +2023-08-23,17:44:40.605 - INFO - 107th iteration +2023-08-23,17:44:40.605 - INFO - average ll reward: 0.1644925910 +2023-08-23,17:44:40.605 - INFO - ---------------------------------------------------- + +2023-08-23,17:44:40.926 - INFO - updating finished +2023-08-23,17:44:45.567 - INFO - ---------------------------------------------------- +2023-08-23,17:44:45.567 - INFO - 108th iteration +2023-08-23,17:44:45.572 - INFO - average ll reward: 0.1490675596 +2023-08-23,17:44:45.572 - INFO - ---------------------------------------------------- + +2023-08-23,17:44:45.825 - INFO - updating finished +2023-08-23,17:44:50.339 - INFO - ---------------------------------------------------- +2023-08-23,17:44:50.339 - INFO - 109th iteration +2023-08-23,17:44:50.339 - INFO - average ll reward: 0.1662582674 +2023-08-23,17:44:50.339 - INFO - ---------------------------------------------------- + +2023-08-23,17:44:50.752 - INFO - updating finished +2023-08-23,17:44:55.373 - INFO - ---------------------------------------------------- +2023-08-23,17:44:55.373 - INFO - 110th iteration +2023-08-23,17:44:55.373 - INFO - average ll reward: 0.1477093483 +2023-08-23,17:44:55.373 - INFO - ---------------------------------------------------- + +2023-08-23,17:44:55.667 - INFO - updating finished +2023-08-23,17:45:00.256 - INFO - ---------------------------------------------------- +2023-08-23,17:45:00.256 - INFO - 111th iteration +2023-08-23,17:45:00.256 - INFO - average ll reward: 0.1429076710 +2023-08-23,17:45:00.256 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:00.553 - INFO - updating finished +2023-08-23,17:45:05.169 - INFO - ---------------------------------------------------- +2023-08-23,17:45:05.169 - INFO - 112th iteration +2023-08-23,17:45:05.169 - INFO - average ll reward: 0.1628307780 +2023-08-23,17:45:05.169 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:05.499 - INFO - updating finished +2023-08-23,17:45:10.214 - INFO - ---------------------------------------------------- +2023-08-23,17:45:10.214 - INFO - 113th iteration +2023-08-23,17:45:10.214 - INFO - average ll reward: 0.1774488702 +2023-08-23,17:45:10.214 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:10.528 - INFO - updating finished +2023-08-23,17:45:15.142 - INFO - ---------------------------------------------------- +2023-08-23,17:45:15.143 - INFO - 114th iteration +2023-08-23,17:45:15.143 - INFO - average ll reward: 0.2056597358 +2023-08-23,17:45:15.143 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:15.515 - INFO - updating finished +2023-08-23,17:45:20.040 - INFO - ---------------------------------------------------- +2023-08-23,17:45:20.040 - INFO - 115th iteration +2023-08-23,17:45:20.040 - INFO - average ll reward: 0.1816140531 +2023-08-23,17:45:20.040 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:20.378 - INFO - updating finished +2023-08-23,17:45:24.906 - INFO - ---------------------------------------------------- +2023-08-23,17:45:24.906 - INFO - 116th iteration +2023-08-23,17:45:24.906 - INFO - average ll reward: 0.1792491671 +2023-08-23,17:45:24.906 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:25.246 - INFO - updating finished +2023-08-23,17:45:29.836 - INFO - ---------------------------------------------------- +2023-08-23,17:45:29.836 - INFO - 117th iteration +2023-08-23,17:45:29.836 - INFO - average ll reward: 0.1689880067 +2023-08-23,17:45:29.836 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:30.100 - INFO - updating finished +2023-08-23,17:45:34.678 - INFO - ---------------------------------------------------- +2023-08-23,17:45:34.678 - INFO - 118th iteration +2023-08-23,17:45:34.678 - INFO - average ll reward: 0.1626123988 +2023-08-23,17:45:34.678 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:34.983 - INFO - updating finished +2023-08-23,17:45:39.535 - INFO - ---------------------------------------------------- +2023-08-23,17:45:39.535 - INFO - 119th iteration +2023-08-23,17:45:39.535 - INFO - average ll reward: 0.1623673877 +2023-08-23,17:45:39.535 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:39.872 - INFO - updating finished +2023-08-23,17:45:44.430 - INFO - ---------------------------------------------------- +2023-08-23,17:45:44.430 - INFO - 120th iteration +2023-08-23,17:45:44.430 - INFO - average ll reward: 0.1919151578 +2023-08-23,17:45:44.430 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:44.764 - INFO - updating finished +2023-08-23,17:45:49.342 - INFO - ---------------------------------------------------- +2023-08-23,17:45:49.343 - INFO - 121th iteration +2023-08-23,17:45:49.343 - INFO - average ll reward: 0.1508279077 +2023-08-23,17:45:49.343 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:49.639 - INFO - updating finished +2023-08-23,17:45:54.344 - INFO - ---------------------------------------------------- +2023-08-23,17:45:54.344 - INFO - 122th iteration +2023-08-23,17:45:54.344 - INFO - average ll reward: 0.2163976002 +2023-08-23,17:45:54.344 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:54.562 - INFO - updating finished +2023-08-23,17:45:59.250 - INFO - ---------------------------------------------------- +2023-08-23,17:45:59.250 - INFO - 123th iteration +2023-08-23,17:45:59.251 - INFO - average ll reward: 0.2074413933 +2023-08-23,17:45:59.251 - INFO - ---------------------------------------------------- + +2023-08-23,17:45:59.483 - INFO - updating finished +2023-08-23,17:46:04.143 - INFO - ---------------------------------------------------- +2023-08-23,17:46:04.143 - INFO - 124th iteration +2023-08-23,17:46:04.143 - INFO - average ll reward: 0.2190447794 +2023-08-23,17:46:04.143 - INFO - ---------------------------------------------------- + +2023-08-23,17:46:04.416 - INFO - updating finished +2023-08-23,17:46:09.101 - INFO - ---------------------------------------------------- +2023-08-23,17:46:09.101 - INFO - 125th iteration +2023-08-23,17:46:09.101 - INFO - average ll reward: 0.1987967689 +2023-08-23,17:46:09.101 - INFO - ---------------------------------------------------- + +2023-08-23,17:46:09.409 - INFO - updating finished +2023-08-23,17:46:14.000 - INFO - ---------------------------------------------------- +2023-08-23,17:46:14.000 - INFO - 126th iteration +2023-08-23,17:46:14.000 - INFO - average ll reward: 0.2154601658 +2023-08-23,17:46:14.000 - INFO - ---------------------------------------------------- + +2023-08-23,17:46:14.342 - INFO - updating finished +2023-08-23,17:46:18.891 - INFO - ---------------------------------------------------- +2023-08-23,17:46:18.891 - INFO - 127th iteration +2023-08-23,17:46:18.891 - INFO - average ll reward: 0.1803623657 +2023-08-23,17:46:18.891 - INFO - ---------------------------------------------------- + +2023-08-23,17:46:19.215 - INFO - updating finished +2023-08-23,17:46:23.779 - INFO - ---------------------------------------------------- +2023-08-23,17:46:23.779 - INFO - 128th iteration +2023-08-23,17:46:23.779 - INFO - average ll reward: 0.1846713609 +2023-08-23,17:46:23.779 - INFO - ---------------------------------------------------- + +2023-08-23,17:46:24.078 - INFO - updating finished +2023-08-23,17:46:28.702 - INFO - ---------------------------------------------------- +2023-08-23,17:46:28.703 - INFO - 129th iteration +2023-08-23,17:46:28.703 - INFO - average ll reward: 0.1883465233 +2023-08-23,17:46:28.703 - INFO - ---------------------------------------------------- + +2023-08-23,17:46:28.953 - INFO - updating finished +2023-08-23,17:46:33.605 - INFO - ---------------------------------------------------- +2023-08-23,17:46:33.605 - INFO - 130th iteration +2023-08-23,17:46:33.605 - INFO - average ll reward: 0.2057103324 +2023-08-23,17:46:33.605 - INFO - ---------------------------------------------------- + +2023-08-23,17:46:33.876 - INFO - updating finished +2023-08-23,17:46:38.519 - INFO - ---------------------------------------------------- +2023-08-23,17:46:38.519 - INFO - 131th iteration +2023-08-23,17:46:38.519 - INFO - average ll reward: 0.1908445666 +2023-08-23,17:46:38.519 - INFO - ---------------------------------------------------- + +2023-08-23,17:46:38.770 - INFO - updating finished +2023-08-23,17:46:43.373 - INFO - ---------------------------------------------------- +2023-08-23,17:46:43.373 - INFO - 132th iteration +2023-08-23,17:46:43.373 - INFO - average ll reward: 0.2122989937 +2023-08-23,17:46:43.373 - INFO - ---------------------------------------------------- + +2023-08-23,17:46:43.662 - INFO - updating finished +2023-08-23,17:46:48.298 - INFO - ---------------------------------------------------- +2023-08-23,17:46:48.298 - INFO - 133th iteration +2023-08-23,17:46:48.298 - INFO - average ll reward: 0.1951748686 +2023-08-23,17:46:48.298 - INFO - ---------------------------------------------------- + +2023-08-23,17:46:48.560 - INFO - updating finished +2023-08-23,17:46:53.213 - INFO - ---------------------------------------------------- +2023-08-23,17:46:53.213 - INFO - 134th iteration +2023-08-23,17:46:53.213 - INFO - average ll reward: 0.1781492815 +2023-08-23,17:46:53.213 - INFO - ---------------------------------------------------- + +2023-08-23,17:46:53.463 - INFO - updating finished +2023-08-23,17:46:58.039 - INFO - ---------------------------------------------------- +2023-08-23,17:46:58.039 - INFO - 135th iteration +2023-08-23,17:46:58.040 - INFO - average ll reward: 0.1327130893 +2023-08-23,17:46:58.040 - INFO - ---------------------------------------------------- + +2023-08-23,17:46:58.364 - INFO - updating finished +2023-08-23,17:47:02.944 - INFO - ---------------------------------------------------- +2023-08-23,17:47:02.945 - INFO - 136th iteration +2023-08-23,17:47:02.945 - INFO - average ll reward: 0.2007648440 +2023-08-23,17:47:02.945 - INFO - ---------------------------------------------------- + +2023-08-23,17:47:03.275 - INFO - updating finished +2023-08-23,17:47:07.851 - INFO - ---------------------------------------------------- +2023-08-23,17:47:07.851 - INFO - 137th iteration +2023-08-23,17:47:07.851 - INFO - average ll reward: 0.2044240257 +2023-08-23,17:47:07.851 - INFO - ---------------------------------------------------- + +2023-08-23,17:47:08.188 - INFO - updating finished +2023-08-23,17:47:12.874 - INFO - ---------------------------------------------------- +2023-08-23,17:47:12.875 - INFO - 138th iteration +2023-08-23,17:47:12.880 - INFO - average ll reward: 0.2053774372 +2023-08-23,17:47:12.880 - INFO - ---------------------------------------------------- + +2023-08-23,17:47:13.125 - INFO - updating finished +2023-08-23,17:47:17.740 - INFO - ---------------------------------------------------- +2023-08-23,17:47:17.740 - INFO - 139th iteration +2023-08-23,17:47:17.740 - INFO - average ll reward: 0.2260355799 +2023-08-23,17:47:17.740 - INFO - ---------------------------------------------------- + +2023-08-23,17:47:18.116 - INFO - updating finished +2023-08-23,17:47:22.806 - INFO - ---------------------------------------------------- +2023-08-23,17:47:22.807 - INFO - 140th iteration +2023-08-23,17:47:22.807 - INFO - average ll reward: 0.2379798566 +2023-08-23,17:47:22.807 - INFO - ---------------------------------------------------- + +2023-08-23,17:47:23.095 - INFO - updating finished +2023-08-23,17:47:27.710 - INFO - ---------------------------------------------------- +2023-08-23,17:47:27.710 - INFO - 141th iteration +2023-08-23,17:47:27.710 - INFO - average ll reward: 0.2045065855 +2023-08-23,17:47:27.710 - INFO - ---------------------------------------------------- + +2023-08-23,17:47:28.011 - INFO - updating finished +2023-08-23,17:47:32.582 - INFO - ---------------------------------------------------- +2023-08-23,17:47:32.582 - INFO - 142th iteration +2023-08-23,17:47:32.582 - INFO - average ll reward: 0.2061311121 +2023-08-23,17:47:32.582 - INFO - ---------------------------------------------------- + +2023-08-23,17:47:32.907 - INFO - updating finished +2023-08-23,17:47:37.492 - INFO - ---------------------------------------------------- +2023-08-23,17:47:37.493 - INFO - 143th iteration +2023-08-23,17:47:37.493 - INFO - average ll reward: 0.2115320043 +2023-08-23,17:47:37.493 - INFO - ---------------------------------------------------- + +2023-08-23,17:47:37.809 - INFO - updating finished +2023-08-23,17:47:42.210 - INFO - ---------------------------------------------------- +2023-08-23,17:47:42.210 - INFO - 144th iteration +2023-08-23,17:47:42.210 - INFO - average ll reward: 0.1891960719 +2023-08-23,17:47:42.210 - INFO - ---------------------------------------------------- + +2023-08-23,17:47:42.715 - INFO - updating finished +2023-08-23,17:47:47.239 - INFO - ---------------------------------------------------- +2023-08-23,17:47:47.240 - INFO - 145th iteration +2023-08-23,17:47:47.240 - INFO - average ll reward: 0.2135586702 +2023-08-23,17:47:47.240 - INFO - ---------------------------------------------------- + +2023-08-23,17:47:47.600 - INFO - updating finished +2023-08-23,17:47:52.221 - INFO - ---------------------------------------------------- +2023-08-23,17:47:52.221 - INFO - 146th iteration +2023-08-23,17:47:52.221 - INFO - average ll reward: 0.2294470894 +2023-08-23,17:47:52.221 - INFO - ---------------------------------------------------- + +2023-08-23,17:47:52.495 - INFO - updating finished +2023-08-23,17:47:57.037 - INFO - ---------------------------------------------------- +2023-08-23,17:47:57.037 - INFO - 147th iteration +2023-08-23,17:47:57.037 - INFO - average ll reward: 0.2089141163 +2023-08-23,17:47:57.037 - INFO - ---------------------------------------------------- + +2023-08-23,17:47:57.395 - INFO - updating finished +2023-08-23,17:48:01.953 - INFO - ---------------------------------------------------- +2023-08-23,17:48:01.954 - INFO - 148th iteration +2023-08-23,17:48:01.955 - INFO - average ll reward: 0.2572771208 +2023-08-23,17:48:01.955 - INFO - ---------------------------------------------------- + +2023-08-23,17:48:02.291 - INFO - updating finished +2023-08-23,17:48:06.910 - INFO - ---------------------------------------------------- +2023-08-23,17:48:06.910 - INFO - 149th iteration +2023-08-23,17:48:06.910 - INFO - average ll reward: 0.2070472387 +2023-08-23,17:48:06.911 - INFO - ---------------------------------------------------- + +2023-08-23,17:48:07.184 - INFO - updating finished +2023-08-23,17:48:11.850 - INFO - ---------------------------------------------------- +2023-08-23,17:48:11.850 - INFO - 150th iteration +2023-08-23,17:48:11.850 - INFO - average ll reward: 0.2072736090 +2023-08-23,17:48:11.850 - INFO - ---------------------------------------------------- + +2023-08-23,17:48:12.090 - INFO - updating finished +2023-08-23,17:48:16.670 - INFO - ---------------------------------------------------- +2023-08-23,17:48:16.670 - INFO - 151th iteration +2023-08-23,17:48:16.670 - INFO - average ll reward: 0.2030178778 +2023-08-23,17:48:16.670 - INFO - ---------------------------------------------------- + +2023-08-23,17:48:16.985 - INFO - updating finished +2023-08-23,17:48:21.392 - INFO - ---------------------------------------------------- +2023-08-23,17:48:21.393 - INFO - 152th iteration +2023-08-23,17:48:21.393 - INFO - average ll reward: 0.2093375586 +2023-08-23,17:48:21.393 - INFO - ---------------------------------------------------- + +2023-08-23,17:48:21.851 - INFO - updating finished +2023-08-23,17:48:26.470 - INFO - ---------------------------------------------------- +2023-08-23,17:48:26.470 - INFO - 153th iteration +2023-08-23,17:48:26.470 - INFO - average ll reward: 0.2133988789 +2023-08-23,17:48:26.470 - INFO - ---------------------------------------------------- + +2023-08-23,17:48:26.775 - INFO - updating finished +2023-08-23,17:48:31.369 - INFO - ---------------------------------------------------- +2023-08-23,17:48:31.369 - INFO - 154th iteration +2023-08-23,17:48:31.369 - INFO - average ll reward: 0.2290076644 +2023-08-23,17:48:31.369 - INFO - ---------------------------------------------------- + +2023-08-23,17:48:31.704 - INFO - updating finished +2023-08-23,17:48:36.256 - INFO - ---------------------------------------------------- +2023-08-23,17:48:36.257 - INFO - 155th iteration +2023-08-23,17:48:36.257 - INFO - average ll reward: 0.2223976990 +2023-08-23,17:48:36.257 - INFO - ---------------------------------------------------- + +2023-08-23,17:48:36.593 - INFO - updating finished +2023-08-23,17:48:41.167 - INFO - ---------------------------------------------------- +2023-08-23,17:48:41.167 - INFO - 156th iteration +2023-08-23,17:48:41.167 - INFO - average ll reward: 0.2302007606 +2023-08-23,17:48:41.167 - INFO - ---------------------------------------------------- + +2023-08-23,17:48:41.512 - INFO - updating finished +2023-08-23,17:48:46.112 - INFO - ---------------------------------------------------- +2023-08-23,17:48:46.112 - INFO - 157th iteration +2023-08-23,17:48:46.112 - INFO - average ll reward: 0.1870761949 +2023-08-23,17:48:46.112 - INFO - ---------------------------------------------------- + +2023-08-23,17:48:46.431 - INFO - updating finished +2023-08-23,17:48:51.070 - INFO - ---------------------------------------------------- +2023-08-23,17:48:51.070 - INFO - 158th iteration +2023-08-23,17:48:51.070 - INFO - average ll reward: 0.2034519744 +2023-08-23,17:48:51.070 - INFO - ---------------------------------------------------- + +2023-08-23,17:48:51.359 - INFO - updating finished +2023-08-23,17:48:56.045 - INFO - ---------------------------------------------------- +2023-08-23,17:48:56.046 - INFO - 159th iteration +2023-08-23,17:48:56.046 - INFO - average ll reward: 0.2316468585 +2023-08-23,17:48:56.046 - INFO - ---------------------------------------------------- + +2023-08-23,17:48:56.326 - INFO - updating finished +2023-08-23,17:49:00.975 - INFO - ---------------------------------------------------- +2023-08-23,17:49:00.975 - INFO - 160th iteration +2023-08-23,17:49:00.975 - INFO - average ll reward: 0.2582651526 +2023-08-23,17:49:00.975 - INFO - ---------------------------------------------------- + +2023-08-23,17:49:01.321 - INFO - updating finished +2023-08-23,17:49:05.922 - INFO - ---------------------------------------------------- +2023-08-23,17:49:05.923 - INFO - 161th iteration +2023-08-23,17:49:05.923 - INFO - average ll reward: 0.2188903206 +2023-08-23,17:49:05.923 - INFO - ---------------------------------------------------- + +2023-08-23,17:49:06.286 - INFO - updating finished +2023-08-23,17:49:10.904 - INFO - ---------------------------------------------------- +2023-08-23,17:49:10.904 - INFO - 162th iteration +2023-08-23,17:49:10.904 - INFO - average ll reward: 0.2406297023 +2023-08-23,17:49:10.904 - INFO - ---------------------------------------------------- + +2023-08-23,17:49:11.245 - INFO - updating finished +2023-08-23,17:49:15.849 - INFO - ---------------------------------------------------- +2023-08-23,17:49:15.849 - INFO - 163th iteration +2023-08-23,17:49:15.854 - INFO - average ll reward: 0.2558736338 +2023-08-23,17:49:15.855 - INFO - ---------------------------------------------------- + +2023-08-23,17:49:16.171 - INFO - updating finished +2023-08-23,17:49:20.720 - INFO - ---------------------------------------------------- +2023-08-23,17:49:20.720 - INFO - 164th iteration +2023-08-23,17:49:20.720 - INFO - average ll reward: 0.1954545012 +2023-08-23,17:49:20.721 - INFO - ---------------------------------------------------- + +2023-08-23,17:49:21.035 - INFO - updating finished +2023-08-23,17:49:25.645 - INFO - ---------------------------------------------------- +2023-08-23,17:49:25.645 - INFO - 165th iteration +2023-08-23,17:49:25.645 - INFO - average ll reward: 0.1700372918 +2023-08-23,17:49:25.645 - INFO - ---------------------------------------------------- + +2023-08-23,17:49:25.975 - INFO - updating finished +2023-08-23,17:49:30.619 - INFO - ---------------------------------------------------- +2023-08-23,17:49:30.619 - INFO - 166th iteration +2023-08-23,17:49:30.619 - INFO - average ll reward: 0.2260781898 +2023-08-23,17:49:30.619 - INFO - ---------------------------------------------------- + +2023-08-23,17:49:30.895 - INFO - updating finished +2023-08-23,17:49:35.507 - INFO - ---------------------------------------------------- +2023-08-23,17:49:35.507 - INFO - 167th iteration +2023-08-23,17:49:35.507 - INFO - average ll reward: 0.2413727226 +2023-08-23,17:49:35.507 - INFO - ---------------------------------------------------- + +2023-08-23,17:49:35.786 - INFO - updating finished +2023-08-23,17:49:40.389 - INFO - ---------------------------------------------------- +2023-08-23,17:49:40.389 - INFO - 168th iteration +2023-08-23,17:49:40.389 - INFO - average ll reward: 0.2051803675 +2023-08-23,17:49:40.389 - INFO - ---------------------------------------------------- + +2023-08-23,17:49:40.687 - INFO - updating finished +2023-08-23,17:49:45.275 - INFO - ---------------------------------------------------- +2023-08-23,17:49:45.276 - INFO - 169th iteration +2023-08-23,17:49:45.276 - INFO - average ll reward: 0.2326615231 +2023-08-23,17:49:45.276 - INFO - ---------------------------------------------------- + +2023-08-23,17:49:45.593 - INFO - updating finished +2023-08-23,17:49:50.167 - INFO - ---------------------------------------------------- +2023-08-23,17:49:50.167 - INFO - 170th iteration +2023-08-23,17:49:50.167 - INFO - average ll reward: 0.2614795919 +2023-08-23,17:49:50.167 - INFO - ---------------------------------------------------- + +2023-08-23,17:49:50.490 - INFO - updating finished +2023-08-23,17:49:55.083 - INFO - ---------------------------------------------------- +2023-08-23,17:49:55.083 - INFO - 171th iteration +2023-08-23,17:49:55.083 - INFO - average ll reward: 0.2123549228 +2023-08-23,17:49:55.083 - INFO - ---------------------------------------------------- + +2023-08-23,17:49:55.368 - INFO - updating finished +2023-08-23,17:50:00.021 - INFO - ---------------------------------------------------- +2023-08-23,17:50:00.022 - INFO - 172th iteration +2023-08-23,17:50:00.022 - INFO - average ll reward: 0.1625458228 +2023-08-23,17:50:00.022 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:00.259 - INFO - updating finished +2023-08-23,17:50:04.843 - INFO - ---------------------------------------------------- +2023-08-23,17:50:04.843 - INFO - 173th iteration +2023-08-23,17:50:04.843 - INFO - average ll reward: 0.1482606250 +2023-08-23,17:50:04.843 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:05.168 - INFO - updating finished +2023-08-23,17:50:09.777 - INFO - ---------------------------------------------------- +2023-08-23,17:50:09.777 - INFO - 174th iteration +2023-08-23,17:50:09.777 - INFO - average ll reward: 0.2660735414 +2023-08-23,17:50:09.777 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:10.066 - INFO - updating finished +2023-08-23,17:50:14.695 - INFO - ---------------------------------------------------- +2023-08-23,17:50:14.695 - INFO - 175th iteration +2023-08-23,17:50:14.695 - INFO - average ll reward: 0.2552371400 +2023-08-23,17:50:14.695 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:14.981 - INFO - updating finished +2023-08-23,17:50:19.578 - INFO - ---------------------------------------------------- +2023-08-23,17:50:19.579 - INFO - 176th iteration +2023-08-23,17:50:19.579 - INFO - average ll reward: 0.2019659288 +2023-08-23,17:50:19.579 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:19.891 - INFO - updating finished +2023-08-23,17:50:24.523 - INFO - ---------------------------------------------------- +2023-08-23,17:50:24.523 - INFO - 177th iteration +2023-08-23,17:50:24.523 - INFO - average ll reward: 0.1793450411 +2023-08-23,17:50:24.523 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:24.786 - INFO - updating finished +2023-08-23,17:50:29.403 - INFO - ---------------------------------------------------- +2023-08-23,17:50:29.403 - INFO - 178th iteration +2023-08-23,17:50:29.403 - INFO - average ll reward: 0.2540200730 +2023-08-23,17:50:29.403 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:29.718 - INFO - updating finished +2023-08-23,17:50:34.139 - INFO - ---------------------------------------------------- +2023-08-23,17:50:34.139 - INFO - 179th iteration +2023-08-23,17:50:34.139 - INFO - average ll reward: 0.2445578624 +2023-08-23,17:50:34.139 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:34.649 - INFO - updating finished +2023-08-23,17:50:39.216 - INFO - ---------------------------------------------------- +2023-08-23,17:50:39.216 - INFO - 180th iteration +2023-08-23,17:50:39.216 - INFO - average ll reward: 0.2493062802 +2023-08-23,17:50:39.216 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:39.556 - INFO - updating finished +2023-08-23,17:50:44.175 - INFO - ---------------------------------------------------- +2023-08-23,17:50:44.175 - INFO - 181th iteration +2023-08-23,17:50:44.175 - INFO - average ll reward: 0.2404352908 +2023-08-23,17:50:44.175 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:44.468 - INFO - updating finished +2023-08-23,17:50:49.103 - INFO - ---------------------------------------------------- +2023-08-23,17:50:49.103 - INFO - 182th iteration +2023-08-23,17:50:49.103 - INFO - average ll reward: 0.2651520879 +2023-08-23,17:50:49.103 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:49.390 - INFO - updating finished +2023-08-23,17:50:53.968 - INFO - ---------------------------------------------------- +2023-08-23,17:50:53.968 - INFO - 183th iteration +2023-08-23,17:50:53.968 - INFO - average ll reward: 0.2319850826 +2023-08-23,17:50:53.968 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:54.297 - INFO - updating finished +2023-08-23,17:50:58.912 - INFO - ---------------------------------------------------- +2023-08-23,17:50:58.912 - INFO - 184th iteration +2023-08-23,17:50:58.912 - INFO - average ll reward: 0.2597352186 +2023-08-23,17:50:58.913 - INFO - ---------------------------------------------------- + +2023-08-23,17:50:59.201 - INFO - updating finished +2023-08-23,17:51:03.816 - INFO - ---------------------------------------------------- +2023-08-23,17:51:03.816 - INFO - 185th iteration +2023-08-23,17:51:03.816 - INFO - average ll reward: 0.2492317101 +2023-08-23,17:51:03.816 - INFO - ---------------------------------------------------- + +2023-08-23,17:51:04.122 - INFO - updating finished +2023-08-23,17:51:08.700 - INFO - ---------------------------------------------------- +2023-08-23,17:51:08.701 - INFO - 186th iteration +2023-08-23,17:51:08.701 - INFO - average ll reward: 0.2469653596 +2023-08-23,17:51:08.701 - INFO - ---------------------------------------------------- + +2023-08-23,17:51:09.029 - INFO - updating finished +2023-08-23,17:51:13.661 - INFO - ---------------------------------------------------- +2023-08-23,17:51:13.661 - INFO - 187th iteration +2023-08-23,17:51:13.661 - INFO - average ll reward: 0.2383819921 +2023-08-23,17:51:13.661 - INFO - ---------------------------------------------------- + +2023-08-23,17:51:13.951 - INFO - updating finished +2023-08-23,17:51:18.598 - INFO - ---------------------------------------------------- +2023-08-23,17:51:18.598 - INFO - 188th iteration +2023-08-23,17:51:18.598 - INFO - average ll reward: 0.2526831681 +2023-08-23,17:51:18.598 - INFO - ---------------------------------------------------- + +2023-08-23,17:51:18.880 - INFO - updating finished +2023-08-23,17:51:23.518 - INFO - ---------------------------------------------------- +2023-08-23,17:51:23.518 - INFO - 189th iteration +2023-08-23,17:51:23.518 - INFO - average ll reward: 0.2636607178 +2023-08-23,17:51:23.518 - INFO - ---------------------------------------------------- + +2023-08-23,17:51:23.801 - INFO - updating finished +2023-08-23,17:51:28.387 - INFO - ---------------------------------------------------- +2023-08-23,17:51:28.387 - INFO - 190th iteration +2023-08-23,17:51:28.387 - INFO - average ll reward: 0.2625368626 +2023-08-23,17:51:28.387 - INFO - ---------------------------------------------------- + +2023-08-23,17:51:28.716 - INFO - updating finished +2023-08-23,17:51:33.373 - INFO - ---------------------------------------------------- +2023-08-23,17:51:33.373 - INFO - 191th iteration +2023-08-23,17:51:33.373 - INFO - average ll reward: 0.1761439220 +2023-08-23,17:51:33.373 - INFO - ---------------------------------------------------- + +2023-08-23,17:51:33.596 - INFO - updating finished +2023-08-23,17:51:38.247 - INFO - ---------------------------------------------------- +2023-08-23,17:51:38.247 - INFO - 192th iteration +2023-08-23,17:51:38.247 - INFO - average ll reward: 0.2464140893 +2023-08-23,17:51:38.247 - INFO - ---------------------------------------------------- + +2023-08-23,17:51:38.512 - INFO - updating finished +2023-08-23,17:51:43.106 - INFO - ---------------------------------------------------- +2023-08-23,17:51:43.106 - INFO - 193th iteration +2023-08-23,17:51:43.106 - INFO - average ll reward: 0.2369199175 +2023-08-23,17:51:43.107 - INFO - ---------------------------------------------------- + +2023-08-23,17:51:43.448 - INFO - updating finished +2023-08-23,17:51:48.081 - INFO - ---------------------------------------------------- +2023-08-23,17:51:48.082 - INFO - 194th iteration +2023-08-23,17:51:48.082 - INFO - average ll reward: 0.2513968611 +2023-08-23,17:51:48.082 - INFO - ---------------------------------------------------- + +2023-08-23,17:51:48.340 - INFO - updating finished +2023-08-23,17:51:52.928 - INFO - ---------------------------------------------------- +2023-08-23,17:51:52.929 - INFO - 195th iteration +2023-08-23,17:51:52.929 - INFO - average ll reward: 0.2537670746 +2023-08-23,17:51:52.929 - INFO - ---------------------------------------------------- + +2023-08-23,17:51:53.241 - INFO - updating finished +2023-08-23,17:51:57.815 - INFO - ---------------------------------------------------- +2023-08-23,17:51:57.816 - INFO - 196th iteration +2023-08-23,17:51:57.816 - INFO - average ll reward: 0.1782371658 +2023-08-23,17:51:57.816 - INFO - ---------------------------------------------------- + +2023-08-23,17:51:58.152 - INFO - updating finished +2023-08-23,17:52:02.707 - INFO - ---------------------------------------------------- +2023-08-23,17:52:02.707 - INFO - 197th iteration +2023-08-23,17:52:02.707 - INFO - average ll reward: 0.2440438722 +2023-08-23,17:52:02.707 - INFO - ---------------------------------------------------- + +2023-08-23,17:52:03.039 - INFO - updating finished +2023-08-23,17:52:07.717 - INFO - ---------------------------------------------------- +2023-08-23,17:52:07.717 - INFO - 198th iteration +2023-08-23,17:52:07.722 - INFO - average ll reward: 0.2562624567 +2023-08-23,17:52:07.723 - INFO - ---------------------------------------------------- + +2023-08-23,17:52:07.955 - INFO - updating finished +2023-08-23,17:52:12.498 - INFO - ---------------------------------------------------- +2023-08-23,17:52:12.498 - INFO - 199th iteration +2023-08-23,17:52:12.498 - INFO - average ll reward: 0.2542784000 +2023-08-23,17:52:12.498 - INFO - ---------------------------------------------------- + +2023-08-23,17:52:12.836 - INFO - updating finished +2023-08-23,17:52:17.431 - INFO - ---------------------------------------------------- +2023-08-23,17:52:17.431 - INFO - 200th iteration +2023-08-23,17:52:17.431 - INFO - average ll reward: 0.2656500987 +2023-08-23,17:52:17.431 - INFO - ---------------------------------------------------- + +2023-08-23,17:52:17.726 - INFO - updating finished +2023-08-23,17:52:22.305 - INFO - ---------------------------------------------------- +2023-08-23,17:52:22.305 - INFO - 201th iteration +2023-08-23,17:52:22.305 - INFO - average ll reward: 0.1876274717 +2023-08-23,17:52:22.305 - INFO - ---------------------------------------------------- + +2023-08-23,17:52:22.624 - INFO - updating finished +2023-08-23,17:52:27.198 - INFO - ---------------------------------------------------- +2023-08-23,17:52:27.199 - INFO - 202th iteration +2023-08-23,17:52:27.199 - INFO - average ll reward: 0.2796077258 +2023-08-23,17:52:27.199 - INFO - ---------------------------------------------------- + +2023-08-23,17:52:27.517 - INFO - updating finished +2023-08-23,17:52:32.034 - INFO - ---------------------------------------------------- +2023-08-23,17:52:32.034 - INFO - 203th iteration +2023-08-23,17:52:32.034 - INFO - average ll reward: 0.2843747837 +2023-08-23,17:52:32.034 - INFO - ---------------------------------------------------- + +2023-08-23,17:52:32.522 - INFO - updating finished +2023-08-23,17:52:37.164 - INFO - ---------------------------------------------------- +2023-08-23,17:52:37.164 - INFO - 204th iteration +2023-08-23,17:52:37.164 - INFO - average ll reward: 0.2116278781 +2023-08-23,17:52:37.164 - INFO - ---------------------------------------------------- + +2023-08-23,17:52:37.434 - INFO - updating finished +2023-08-23,17:52:42.034 - INFO - ---------------------------------------------------- +2023-08-23,17:52:42.034 - INFO - 205th iteration +2023-08-23,17:52:42.034 - INFO - average ll reward: 0.2706488523 +2023-08-23,17:52:42.034 - INFO - ---------------------------------------------------- + +2023-08-23,17:52:42.341 - INFO - updating finished +2023-08-23,17:52:46.968 - INFO - ---------------------------------------------------- +2023-08-23,17:52:46.968 - INFO - 206th iteration +2023-08-23,17:52:46.968 - INFO - average ll reward: 0.2818580969 +2023-08-23,17:52:46.968 - INFO - ---------------------------------------------------- + +2023-08-23,17:52:47.274 - INFO - updating finished +2023-08-23,17:52:51.906 - INFO - ---------------------------------------------------- +2023-08-23,17:52:51.906 - INFO - 207th iteration +2023-08-23,17:52:51.906 - INFO - average ll reward: 0.2611040827 +2023-08-23,17:52:51.906 - INFO - ---------------------------------------------------- + +2023-08-23,17:52:52.187 - INFO - updating finished +2023-08-23,17:52:56.757 - INFO - ---------------------------------------------------- +2023-08-23,17:52:56.758 - INFO - 208th iteration +2023-08-23,17:52:56.758 - INFO - average ll reward: 0.1787911038 +2023-08-23,17:52:56.758 - INFO - ---------------------------------------------------- + +2023-08-23,17:52:57.085 - INFO - updating finished +2023-08-23,17:53:01.671 - INFO - ---------------------------------------------------- +2023-08-23,17:53:01.671 - INFO - 209th iteration +2023-08-23,17:53:01.676 - INFO - average ll reward: 0.1712916423 +2023-08-23,17:53:01.676 - INFO - ---------------------------------------------------- + +2023-08-23,17:53:02.012 - INFO - updating finished +2023-08-23,17:53:06.616 - INFO - ---------------------------------------------------- +2023-08-23,17:53:06.616 - INFO - 210th iteration +2023-08-23,17:53:06.616 - INFO - average ll reward: 0.1731052552 +2023-08-23,17:53:06.616 - INFO - ---------------------------------------------------- + +2023-08-23,17:53:06.920 - INFO - updating finished +2023-08-23,17:53:11.511 - INFO - ---------------------------------------------------- +2023-08-23,17:53:11.511 - INFO - 211th iteration +2023-08-23,17:53:11.511 - INFO - average ll reward: 0.2500066929 +2023-08-23,17:53:11.511 - INFO - ---------------------------------------------------- + +2023-08-23,17:53:11.836 - INFO - updating finished +2023-08-23,17:53:16.461 - INFO - ---------------------------------------------------- +2023-08-23,17:53:16.461 - INFO - 212th iteration +2023-08-23,17:53:16.461 - INFO - average ll reward: 0.2684943575 +2023-08-23,17:53:16.462 - INFO - ---------------------------------------------------- + +2023-08-23,17:53:16.780 - INFO - updating finished +2023-08-23,17:53:21.433 - INFO - ---------------------------------------------------- +2023-08-23,17:53:21.433 - INFO - 213th iteration +2023-08-23,17:53:21.434 - INFO - average ll reward: 0.1727084427 +2023-08-23,17:53:21.434 - INFO - ---------------------------------------------------- + +2023-08-23,17:53:21.718 - INFO - updating finished +2023-08-23,17:53:26.327 - INFO - ---------------------------------------------------- +2023-08-23,17:53:26.327 - INFO - 214th iteration +2023-08-23,17:53:26.327 - INFO - average ll reward: 0.2567844369 +2023-08-23,17:53:26.327 - INFO - ---------------------------------------------------- + +2023-08-23,17:53:26.632 - INFO - updating finished +2023-08-23,17:53:31.233 - INFO - ---------------------------------------------------- +2023-08-23,17:53:31.233 - INFO - 215th iteration +2023-08-23,17:53:31.233 - INFO - average ll reward: 0.2498282598 +2023-08-23,17:53:31.233 - INFO - ---------------------------------------------------- + +2023-08-23,17:53:31.556 - INFO - updating finished +2023-08-23,17:53:35.944 - INFO - ---------------------------------------------------- +2023-08-23,17:53:35.945 - INFO - 216th iteration +2023-08-23,17:53:35.945 - INFO - average ll reward: 0.2421769982 +2023-08-23,17:53:35.945 - INFO - ---------------------------------------------------- + +2023-08-23,17:53:36.445 - INFO - updating finished +2023-08-23,17:53:41.042 - INFO - ---------------------------------------------------- +2023-08-23,17:53:41.042 - INFO - 217th iteration +2023-08-23,17:53:41.042 - INFO - average ll reward: 0.2694317891 +2023-08-23,17:53:41.042 - INFO - ---------------------------------------------------- + +2023-08-23,17:53:41.357 - INFO - updating finished +2023-08-23,17:53:45.956 - INFO - ---------------------------------------------------- +2023-08-23,17:53:45.956 - INFO - 218th iteration +2023-08-23,17:53:45.956 - INFO - average ll reward: 0.2664304029 +2023-08-23,17:53:45.956 - INFO - ---------------------------------------------------- + +2023-08-23,17:53:46.266 - INFO - updating finished +2023-08-23,17:53:50.894 - INFO - ---------------------------------------------------- +2023-08-23,17:53:50.894 - INFO - 219th iteration +2023-08-23,17:53:50.894 - INFO - average ll reward: 0.2512930004 +2023-08-23,17:53:50.894 - INFO - ---------------------------------------------------- + +2023-08-23,17:53:51.182 - INFO - updating finished +2023-08-23,17:53:55.690 - INFO - ---------------------------------------------------- +2023-08-23,17:53:55.690 - INFO - 220th iteration +2023-08-23,17:53:55.690 - INFO - average ll reward: 0.2643957504 +2023-08-23,17:53:55.690 - INFO - ---------------------------------------------------- + +2023-08-23,17:53:56.111 - INFO - updating finished +2023-08-23,17:54:00.735 - INFO - ---------------------------------------------------- +2023-08-23,17:54:00.735 - INFO - 221th iteration +2023-08-23,17:54:00.735 - INFO - average ll reward: 0.2473408674 +2023-08-23,17:54:00.735 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:01.042 - INFO - updating finished +2023-08-23,17:54:05.629 - INFO - ---------------------------------------------------- +2023-08-23,17:54:05.629 - INFO - 222th iteration +2023-08-23,17:54:05.630 - INFO - average ll reward: 0.2749951288 +2023-08-23,17:54:05.630 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:05.954 - INFO - updating finished +2023-08-23,17:54:10.596 - INFO - ---------------------------------------------------- +2023-08-23,17:54:10.596 - INFO - 223th iteration +2023-08-23,17:54:10.596 - INFO - average ll reward: 0.2704038403 +2023-08-23,17:54:10.596 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:10.879 - INFO - updating finished +2023-08-23,17:54:15.473 - INFO - ---------------------------------------------------- +2023-08-23,17:54:15.473 - INFO - 224th iteration +2023-08-23,17:54:15.473 - INFO - average ll reward: 0.2740070964 +2023-08-23,17:54:15.473 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:15.774 - INFO - updating finished +2023-08-23,17:54:20.412 - INFO - ---------------------------------------------------- +2023-08-23,17:54:20.412 - INFO - 225th iteration +2023-08-23,17:54:20.412 - INFO - average ll reward: 0.2259237244 +2023-08-23,17:54:20.412 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:20.674 - INFO - updating finished +2023-08-23,17:54:25.060 - INFO - ---------------------------------------------------- +2023-08-23,17:54:25.061 - INFO - 226th iteration +2023-08-23,17:54:25.061 - INFO - average ll reward: 0.2368852963 +2023-08-23,17:54:25.061 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:25.569 - INFO - updating finished +2023-08-23,17:54:30.205 - INFO - ---------------------------------------------------- +2023-08-23,17:54:30.205 - INFO - 227th iteration +2023-08-23,17:54:30.205 - INFO - average ll reward: 0.2715463382 +2023-08-23,17:54:30.205 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:30.501 - INFO - updating finished +2023-08-23,17:54:35.157 - INFO - ---------------------------------------------------- +2023-08-23,17:54:35.157 - INFO - 228th iteration +2023-08-23,17:54:35.157 - INFO - average ll reward: 0.1897979485 +2023-08-23,17:54:35.157 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:35.427 - INFO - updating finished +2023-08-23,17:54:40.060 - INFO - ---------------------------------------------------- +2023-08-23,17:54:40.060 - INFO - 229th iteration +2023-08-23,17:54:40.065 - INFO - average ll reward: 0.1866261213 +2023-08-23,17:54:40.066 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:40.367 - INFO - updating finished +2023-08-23,17:54:44.753 - INFO - ---------------------------------------------------- +2023-08-23,17:54:44.753 - INFO - 230th iteration +2023-08-23,17:54:44.753 - INFO - average ll reward: 0.1876541040 +2023-08-23,17:54:44.753 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:45.271 - INFO - updating finished +2023-08-23,17:54:49.842 - INFO - ---------------------------------------------------- +2023-08-23,17:54:49.842 - INFO - 231th iteration +2023-08-23,17:54:49.842 - INFO - average ll reward: 0.3045056174 +2023-08-23,17:54:49.842 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:50.186 - INFO - updating finished +2023-08-23,17:54:54.765 - INFO - ---------------------------------------------------- +2023-08-23,17:54:54.765 - INFO - 232th iteration +2023-08-23,17:54:54.765 - INFO - average ll reward: 0.2592292180 +2023-08-23,17:54:54.765 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:55.081 - INFO - updating finished +2023-08-23,17:54:59.680 - INFO - ---------------------------------------------------- +2023-08-23,17:54:59.680 - INFO - 233th iteration +2023-08-23,17:54:59.680 - INFO - average ll reward: 0.2650162686 +2023-08-23,17:54:59.680 - INFO - ---------------------------------------------------- + +2023-08-23,17:54:59.962 - INFO - updating finished +2023-08-23,17:55:04.355 - INFO - ---------------------------------------------------- +2023-08-23,17:55:04.356 - INFO - 234th iteration +2023-08-23,17:55:04.356 - INFO - average ll reward: 0.1877632944 +2023-08-23,17:55:04.356 - INFO - ---------------------------------------------------- + +2023-08-23,17:55:04.871 - INFO - updating finished +2023-08-23,17:55:09.388 - INFO - ---------------------------------------------------- +2023-08-23,17:55:09.388 - INFO - 235th iteration +2023-08-23,17:55:09.388 - INFO - average ll reward: 0.1965330804 +2023-08-23,17:55:09.388 - INFO - ---------------------------------------------------- + +2023-08-23,17:55:09.773 - INFO - updating finished +2023-08-23,17:55:14.378 - INFO - ---------------------------------------------------- +2023-08-23,17:55:14.378 - INFO - 236th iteration +2023-08-23,17:55:14.378 - INFO - average ll reward: 0.2917970113 +2023-08-23,17:55:14.378 - INFO - ---------------------------------------------------- + +2023-08-23,17:55:14.679 - INFO - updating finished +2023-08-23,17:55:19.248 - INFO - ---------------------------------------------------- +2023-08-23,17:55:19.248 - INFO - 237th iteration +2023-08-23,17:55:19.248 - INFO - average ll reward: 0.2824866010 +2023-08-23,17:55:19.248 - INFO - ---------------------------------------------------- + +2023-08-23,17:55:19.566 - INFO - updating finished +2023-08-23,17:55:24.183 - INFO - ---------------------------------------------------- +2023-08-23,17:55:24.183 - INFO - 238th iteration +2023-08-23,17:55:24.184 - INFO - average ll reward: 0.2660415834 +2023-08-23,17:55:24.184 - INFO - ---------------------------------------------------- + +2023-08-23,17:55:24.478 - INFO - updating finished +2023-08-23,17:55:29.057 - INFO - ---------------------------------------------------- +2023-08-23,17:55:29.058 - INFO - 239th iteration +2023-08-23,17:55:29.058 - INFO - average ll reward: 0.2894640828 +2023-08-23,17:55:29.058 - INFO - ---------------------------------------------------- + +2023-08-23,17:55:29.394 - INFO - updating finished +2023-08-23,17:55:34.036 - INFO - ---------------------------------------------------- +2023-08-23,17:55:34.037 - INFO - 240th iteration +2023-08-23,17:55:34.037 - INFO - average ll reward: 0.2519747662 +2023-08-23,17:55:34.037 - INFO - ---------------------------------------------------- + +2023-08-23,17:55:34.286 - INFO - updating finished +2023-08-23,17:55:38.892 - INFO - ---------------------------------------------------- +2023-08-23,17:55:38.892 - INFO - 241th iteration +2023-08-23,17:55:38.892 - INFO - average ll reward: 0.2566060037 +2023-08-23,17:55:38.892 - INFO - ---------------------------------------------------- + +2023-08-23,17:55:39.177 - INFO - updating finished +2023-08-23,17:55:43.781 - INFO - ---------------------------------------------------- +2023-08-23,17:55:43.781 - INFO - 242th iteration +2023-08-23,17:55:43.781 - INFO - average ll reward: 0.2961219858 +2023-08-23,17:55:43.781 - INFO - ---------------------------------------------------- + +2023-08-23,17:55:44.075 - INFO - updating finished +2023-08-23,17:55:48.651 - INFO - ---------------------------------------------------- +2023-08-23,17:55:48.652 - INFO - 243th iteration +2023-08-23,17:55:48.652 - INFO - average ll reward: 0.2372980855 +2023-08-23,17:55:48.652 - INFO - ---------------------------------------------------- + +2023-08-23,17:55:48.960 - INFO - updating finished +2023-08-23,17:55:53.380 - INFO - ---------------------------------------------------- +2023-08-23,17:55:53.380 - INFO - 244th iteration +2023-08-23,17:55:53.380 - INFO - average ll reward: 0.2759725104 +2023-08-23,17:55:53.380 - INFO - ---------------------------------------------------- + +2023-08-23,17:55:53.866 - INFO - updating finished +2023-08-23,17:55:58.443 - INFO - ---------------------------------------------------- +2023-08-23,17:55:58.443 - INFO - 245th iteration +2023-08-23,17:55:58.443 - INFO - average ll reward: 0.2839859627 +2023-08-23,17:55:58.443 - INFO - ---------------------------------------------------- + +2023-08-23,17:55:58.775 - INFO - updating finished +2023-08-23,17:56:03.444 - INFO - ---------------------------------------------------- +2023-08-23,17:56:03.444 - INFO - 246th iteration +2023-08-23,17:56:03.444 - INFO - average ll reward: 0.2832695702 +2023-08-23,17:56:03.445 - INFO - ---------------------------------------------------- + +2023-08-23,17:56:03.706 - INFO - updating finished +2023-08-23,17:56:08.128 - INFO - ---------------------------------------------------- +2023-08-23,17:56:08.128 - INFO - 247th iteration +2023-08-23,17:56:08.128 - INFO - average ll reward: 0.2938556362 +2023-08-23,17:56:08.128 - INFO - ---------------------------------------------------- + +2023-08-23,17:56:08.658 - INFO - updating finished +2023-08-23,17:56:13.283 - INFO - ---------------------------------------------------- +2023-08-23,17:56:13.283 - INFO - 248th iteration +2023-08-23,17:56:13.283 - INFO - average ll reward: 0.2768699961 +2023-08-23,17:56:13.283 - INFO - ---------------------------------------------------- + +2023-08-23,17:56:13.608 - INFO - updating finished +2023-08-23,17:56:18.337 - INFO - ---------------------------------------------------- +2023-08-23,17:56:18.338 - INFO - 249th iteration +2023-08-23,17:56:18.338 - INFO - average ll reward: 0.2912830229 +2023-08-23,17:56:18.338 - INFO - ---------------------------------------------------- + +2023-08-23,17:56:18.575 - INFO - updating finished +2023-08-23,17:56:23.165 - INFO - ---------------------------------------------------- +2023-08-23,17:56:23.165 - INFO - 250th iteration +2023-08-23,17:56:23.165 - INFO - average ll reward: 0.2845425623 +2023-08-23,17:56:23.165 - INFO - ---------------------------------------------------- + +2023-08-23,17:56:23.493 - INFO - updating finished +2023-08-23,17:56:28.122 - INFO - ---------------------------------------------------- +2023-08-23,17:56:28.122 - INFO - 251th iteration +2023-08-23,17:56:28.122 - INFO - average ll reward: 0.2945480579 +2023-08-23,17:56:28.122 - INFO - ---------------------------------------------------- + +2023-08-23,17:56:28.416 - INFO - updating finished +2023-08-23,17:56:33.028 - INFO - ---------------------------------------------------- +2023-08-23,17:56:33.028 - INFO - 252th iteration +2023-08-23,17:56:33.029 - INFO - average ll reward: 0.2780843983 +2023-08-23,17:56:33.029 - INFO - ---------------------------------------------------- + +2023-08-23,17:56:33.336 - INFO - updating finished +2023-08-23,17:56:37.914 - INFO - ---------------------------------------------------- +2023-08-23,17:56:37.914 - INFO - 253th iteration +2023-08-23,17:56:37.914 - INFO - average ll reward: 0.2699324620 +2023-08-23,17:56:37.914 - INFO - ---------------------------------------------------- + +2023-08-23,17:56:38.269 - INFO - updating finished +2023-08-23,17:56:42.900 - INFO - ---------------------------------------------------- +2023-08-23,17:56:42.900 - INFO - 254th iteration +2023-08-23,17:56:42.901 - INFO - average ll reward: 0.2402968052 +2023-08-23,17:56:42.901 - INFO - ---------------------------------------------------- + +2023-08-23,17:56:43.191 - INFO - updating finished +2023-08-23,17:56:47.830 - INFO - ---------------------------------------------------- +2023-08-23,17:56:47.830 - INFO - 255th iteration +2023-08-23,17:56:47.830 - INFO - average ll reward: 0.2105599513 +2023-08-23,17:56:47.830 - INFO - ---------------------------------------------------- + +2023-08-23,17:56:48.118 - INFO - updating finished +2023-08-23,17:56:52.750 - INFO - ---------------------------------------------------- +2023-08-23,17:56:52.750 - INFO - 256th iteration +2023-08-23,17:56:52.750 - INFO - average ll reward: 0.3051208062 +2023-08-23,17:56:52.750 - INFO - ---------------------------------------------------- + +2023-08-23,17:56:53.044 - INFO - updating finished +2023-08-23,17:56:57.620 - INFO - ---------------------------------------------------- +2023-08-23,17:56:57.620 - INFO - 257th iteration +2023-08-23,17:56:57.620 - INFO - average ll reward: 0.2853468359 +2023-08-23,17:56:57.620 - INFO - ---------------------------------------------------- + +2023-08-23,17:56:57.969 - INFO - updating finished +2023-08-23,17:57:02.665 - INFO - ---------------------------------------------------- +2023-08-23,17:57:02.666 - INFO - 258th iteration +2023-08-23,17:57:02.666 - INFO - average ll reward: 0.2267945786 +2023-08-23,17:57:02.666 - INFO - ---------------------------------------------------- + +2023-08-23,17:57:02.911 - INFO - updating finished +2023-08-23,17:57:07.485 - INFO - ---------------------------------------------------- +2023-08-23,17:57:07.486 - INFO - 259th iteration +2023-08-23,17:57:07.486 - INFO - average ll reward: 0.2409066685 +2023-08-23,17:57:07.486 - INFO - ---------------------------------------------------- + +2023-08-23,17:57:07.814 - INFO - updating finished +2023-08-23,17:57:12.343 - INFO - ---------------------------------------------------- +2023-08-23,17:57:12.344 - INFO - 260th iteration +2023-08-23,17:57:12.344 - INFO - average ll reward: 0.2761855609 +2023-08-23,17:57:12.344 - INFO - ---------------------------------------------------- + +2023-08-23,17:57:12.706 - INFO - updating finished +2023-08-23,17:57:17.343 - INFO - ---------------------------------------------------- +2023-08-23,17:57:17.343 - INFO - 261th iteration +2023-08-23,17:57:17.343 - INFO - average ll reward: 0.2911898124 +2023-08-23,17:57:17.344 - INFO - ---------------------------------------------------- + +2023-08-23,17:57:17.633 - INFO - updating finished +2023-08-23,17:57:22.240 - INFO - ---------------------------------------------------- +2023-08-23,17:57:22.240 - INFO - 262th iteration +2023-08-23,17:57:22.240 - INFO - average ll reward: 0.2950913394 +2023-08-23,17:57:22.240 - INFO - ---------------------------------------------------- + +2023-08-23,17:57:22.573 - INFO - updating finished +2023-08-23,17:57:27.166 - INFO - ---------------------------------------------------- +2023-08-23,17:57:27.166 - INFO - 263th iteration +2023-08-23,17:57:27.166 - INFO - average ll reward: 0.2778766703 +2023-08-23,17:57:27.167 - INFO - ---------------------------------------------------- + +2023-08-23,17:57:27.484 - INFO - updating finished +2023-08-23,17:57:32.116 - INFO - ---------------------------------------------------- +2023-08-23,17:57:32.116 - INFO - 264th iteration +2023-08-23,17:57:32.116 - INFO - average ll reward: 0.2948942686 +2023-08-23,17:57:32.118 - INFO - ---------------------------------------------------- + +2023-08-23,17:57:32.402 - INFO - updating finished +2023-08-23,17:57:36.825 - INFO - ---------------------------------------------------- +2023-08-23,17:57:36.825 - INFO - 265th iteration +2023-08-23,17:57:36.825 - INFO - average ll reward: 0.3088092843 +2023-08-23,17:57:36.825 - INFO - ---------------------------------------------------- + +2023-08-23,17:57:37.316 - INFO - updating finished +2023-08-23,17:57:41.956 - INFO - ---------------------------------------------------- +2023-08-23,17:57:41.956 - INFO - 266th iteration +2023-08-23,17:57:41.956 - INFO - average ll reward: 0.2923669284 +2023-08-23,17:57:41.956 - INFO - ---------------------------------------------------- + +2023-08-23,17:57:42.217 - INFO - updating finished +2023-08-23,17:57:46.894 - INFO - ---------------------------------------------------- +2023-08-23,17:57:46.894 - INFO - 267th iteration +2023-08-23,17:57:46.894 - INFO - average ll reward: 0.2816184120 +2023-08-23,17:57:46.894 - INFO - ---------------------------------------------------- + +2023-08-23,17:57:47.150 - INFO - updating finished +2023-08-23,17:57:51.737 - INFO - ---------------------------------------------------- +2023-08-23,17:57:51.737 - INFO - 268th iteration +2023-08-23,17:57:51.737 - INFO - average ll reward: 0.2872589863 +2023-08-23,17:57:51.737 - INFO - ---------------------------------------------------- + +2023-08-23,17:57:52.065 - INFO - updating finished +2023-08-23,17:57:56.679 - INFO - ---------------------------------------------------- +2023-08-23,17:57:56.680 - INFO - 269th iteration +2023-08-23,17:57:56.680 - INFO - average ll reward: 0.2208450788 +2023-08-23,17:57:56.680 - INFO - ---------------------------------------------------- + +2023-08-23,17:57:56.985 - INFO - updating finished +2023-08-23,17:58:01.537 - INFO - ---------------------------------------------------- +2023-08-23,17:58:01.537 - INFO - 270th iteration +2023-08-23,17:58:01.543 - INFO - average ll reward: 0.2057689235 +2023-08-23,17:58:01.543 - INFO - ---------------------------------------------------- + +2023-08-23,17:58:01.854 - INFO - updating finished +2023-08-23,17:58:06.441 - INFO - ---------------------------------------------------- +2023-08-23,17:58:06.442 - INFO - 271th iteration +2023-08-23,17:58:06.442 - INFO - average ll reward: 0.2655835197 +2023-08-23,17:58:06.442 - INFO - ---------------------------------------------------- + +2023-08-23,17:58:06.772 - INFO - updating finished +2023-08-23,17:58:11.412 - INFO - ---------------------------------------------------- +2023-08-23,17:58:11.412 - INFO - 272th iteration +2023-08-23,17:58:11.412 - INFO - average ll reward: 0.2952751003 +2023-08-23,17:58:11.412 - INFO - ---------------------------------------------------- + +2023-08-23,17:58:11.686 - INFO - updating finished +2023-08-23,17:58:16.315 - INFO - ---------------------------------------------------- +2023-08-23,17:58:16.315 - INFO - 273th iteration +2023-08-23,17:58:16.315 - INFO - average ll reward: 0.3009263270 +2023-08-23,17:58:16.315 - INFO - ---------------------------------------------------- + +2023-08-23,17:58:16.591 - INFO - updating finished +2023-08-23,17:58:21.226 - INFO - ---------------------------------------------------- +2023-08-23,17:58:21.227 - INFO - 274th iteration +2023-08-23,17:58:21.227 - INFO - average ll reward: 0.3070862169 +2023-08-23,17:58:21.227 - INFO - ---------------------------------------------------- + +2023-08-23,17:58:21.491 - INFO - updating finished +2023-08-23,17:58:26.127 - INFO - ---------------------------------------------------- +2023-08-23,17:58:26.127 - INFO - 275th iteration +2023-08-23,17:58:26.127 - INFO - average ll reward: 0.2153616264 +2023-08-23,17:58:26.127 - INFO - ---------------------------------------------------- + +2023-08-23,17:58:26.417 - INFO - updating finished +2023-08-23,17:58:31.071 - INFO - ---------------------------------------------------- +2023-08-23,17:58:31.071 - INFO - 276th iteration +2023-08-23,17:58:31.071 - INFO - average ll reward: 0.3156429538 +2023-08-23,17:58:31.071 - INFO - ---------------------------------------------------- + +2023-08-23,17:58:31.333 - INFO - updating finished +2023-08-23,17:58:35.885 - INFO - ---------------------------------------------------- +2023-08-23,17:58:35.886 - INFO - 277th iteration +2023-08-23,17:58:35.886 - INFO - average ll reward: 0.2892377137 +2023-08-23,17:58:35.886 - INFO - ---------------------------------------------------- + +2023-08-23,17:58:36.262 - INFO - updating finished +2023-08-23,17:58:40.929 - INFO - ---------------------------------------------------- +2023-08-23,17:58:40.929 - INFO - 278th iteration +2023-08-23,17:58:40.929 - INFO - average ll reward: 0.2871924072 +2023-08-23,17:58:40.930 - INFO - ---------------------------------------------------- + +2023-08-23,17:58:41.213 - INFO - updating finished +2023-08-23,17:58:45.788 - INFO - ---------------------------------------------------- +2023-08-23,17:58:45.788 - INFO - 279th iteration +2023-08-23,17:58:45.788 - INFO - average ll reward: 0.2728832422 +2023-08-23,17:58:45.788 - INFO - ---------------------------------------------------- + +2023-08-23,17:58:46.132 - INFO - updating finished +2023-08-23,17:58:50.732 - INFO - ---------------------------------------------------- +2023-08-23,17:58:50.732 - INFO - 280th iteration +2023-08-23,17:58:50.732 - INFO - average ll reward: 0.2055345670 +2023-08-23,17:58:50.732 - INFO - ---------------------------------------------------- + +2023-08-23,17:58:51.043 - INFO - updating finished +2023-08-23,17:58:55.713 - INFO - ---------------------------------------------------- +2023-08-23,17:58:55.714 - INFO - 281th iteration +2023-08-23,17:58:55.719 - INFO - average ll reward: 0.2799965454 +2023-08-23,17:58:55.720 - INFO - ---------------------------------------------------- + +2023-08-23,17:58:55.978 - INFO - updating finished +2023-08-23,17:59:00.649 - INFO - ---------------------------------------------------- +2023-08-23,17:59:00.649 - INFO - 282th iteration +2023-08-23,17:59:00.649 - INFO - average ll reward: 0.2581186785 +2023-08-23,17:59:00.649 - INFO - ---------------------------------------------------- + +2023-08-23,17:59:00.912 - INFO - updating finished +2023-08-23,17:59:05.535 - INFO - ---------------------------------------------------- +2023-08-23,17:59:05.535 - INFO - 283th iteration +2023-08-23,17:59:05.535 - INFO - average ll reward: 0.2361289588 +2023-08-23,17:59:05.535 - INFO - ---------------------------------------------------- + +2023-08-23,17:59:05.833 - INFO - updating finished +2023-08-23,17:59:10.415 - INFO - ---------------------------------------------------- +2023-08-23,17:59:10.415 - INFO - 284th iteration +2023-08-23,17:59:10.415 - INFO - average ll reward: 0.3108812238 +2023-08-23,17:59:10.415 - INFO - ---------------------------------------------------- + +2023-08-23,17:59:10.704 - INFO - updating finished +2023-08-23,17:59:15.348 - INFO - ---------------------------------------------------- +2023-08-23,17:59:15.348 - INFO - 285th iteration +2023-08-23,17:59:15.348 - INFO - average ll reward: 0.2908915356 +2023-08-23,17:59:15.348 - INFO - ---------------------------------------------------- + +2023-08-23,17:59:15.623 - INFO - updating finished +2023-08-23,17:59:20.284 - INFO - ---------------------------------------------------- +2023-08-23,17:59:20.284 - INFO - 286th iteration +2023-08-23,17:59:20.284 - INFO - average ll reward: 0.2647606028 +2023-08-23,17:59:20.284 - INFO - ---------------------------------------------------- + +2023-08-23,17:59:20.557 - INFO - updating finished +2023-08-23,17:59:25.215 - INFO - ---------------------------------------------------- +2023-08-23,17:59:25.215 - INFO - 287th iteration +2023-08-23,17:59:25.216 - INFO - average ll reward: 0.2824386636 +2023-08-23,17:59:25.216 - INFO - ---------------------------------------------------- + +2023-08-23,17:59:25.480 - INFO - updating finished +2023-08-23,17:59:30.126 - INFO - ---------------------------------------------------- +2023-08-23,17:59:30.126 - INFO - 288th iteration +2023-08-23,17:59:30.127 - INFO - average ll reward: 0.2449679890 +2023-08-23,17:59:30.127 - INFO - ---------------------------------------------------- + +2023-08-23,17:59:30.405 - INFO - updating finished +2023-08-23,17:59:35.032 - INFO - ---------------------------------------------------- +2023-08-23,17:59:35.033 - INFO - 289th iteration +2023-08-23,17:59:35.033 - INFO - average ll reward: 0.2870619113 +2023-08-23,17:59:35.033 - INFO - ---------------------------------------------------- + +2023-08-23,17:59:35.321 - INFO - updating finished +2023-08-23,17:59:39.932 - INFO - ---------------------------------------------------- +2023-08-23,17:59:39.933 - INFO - 290th iteration +2023-08-23,17:59:39.933 - INFO - average ll reward: 0.2899567661 +2023-08-23,17:59:39.933 - INFO - ---------------------------------------------------- + +2023-08-23,17:59:40.257 - INFO - updating finished +2023-08-23,17:59:44.908 - INFO - ---------------------------------------------------- +2023-08-23,17:59:44.908 - INFO - 291th iteration +2023-08-23,17:59:44.908 - INFO - average ll reward: 0.2229329977 +2023-08-23,17:59:44.908 - INFO - ---------------------------------------------------- + +2023-08-23,17:59:45.191 - INFO - updating finished +2023-08-23,17:59:49.828 - INFO - ---------------------------------------------------- +2023-08-23,17:59:49.828 - INFO - 292th iteration +2023-08-23,17:59:49.828 - INFO - average ll reward: 0.2301102155 +2023-08-23,17:59:49.828 - INFO - ---------------------------------------------------- + +2023-08-23,17:59:50.129 - INFO - updating finished +2023-08-23,17:59:54.777 - INFO - ---------------------------------------------------- +2023-08-23,17:59:54.777 - INFO - 293th iteration +2023-08-23,17:59:54.777 - INFO - average ll reward: 0.2324617889 +2023-08-23,17:59:54.777 - INFO - ---------------------------------------------------- + +2023-08-23,17:59:55.072 - INFO - updating finished +2023-08-23,17:59:59.744 - INFO - ---------------------------------------------------- +2023-08-23,17:59:59.744 - INFO - 294th iteration +2023-08-23,17:59:59.744 - INFO - average ll reward: 0.2300596169 +2023-08-23,17:59:59.744 - INFO - ---------------------------------------------------- + +2023-08-23,18:00:00.006 - INFO - updating finished +2023-08-23,18:00:04.616 - INFO - ---------------------------------------------------- +2023-08-23,18:00:04.616 - INFO - 295th iteration +2023-08-23,18:00:04.616 - INFO - average ll reward: 0.2079873361 +2023-08-23,18:00:04.616 - INFO - ---------------------------------------------------- + +2023-08-23,18:00:04.935 - INFO - updating finished +2023-08-23,18:00:09.536 - INFO - ---------------------------------------------------- +2023-08-23,18:00:09.537 - INFO - 296th iteration +2023-08-23,18:00:09.537 - INFO - average ll reward: 0.2248158529 +2023-08-23,18:00:09.537 - INFO - ---------------------------------------------------- + +2023-08-23,18:00:09.838 - INFO - updating finished +2023-08-23,18:00:14.413 - INFO - ---------------------------------------------------- +2023-08-23,18:00:14.413 - INFO - 297th iteration +2023-08-23,18:00:14.413 - INFO - average ll reward: 0.2176253174 +2023-08-23,18:00:14.413 - INFO - ---------------------------------------------------- + +2023-08-23,18:00:14.757 - INFO - updating finished +2023-08-23,18:00:19.338 - INFO - ---------------------------------------------------- +2023-08-23,18:00:19.338 - INFO - 298th iteration +2023-08-23,18:00:19.338 - INFO - average ll reward: 0.2979222807 +2023-08-23,18:00:19.338 - INFO - ---------------------------------------------------- + +2023-08-23,18:00:19.662 - INFO - updating finished +2023-08-23,18:00:24.289 - INFO - ---------------------------------------------------- +2023-08-23,18:00:24.289 - INFO - 299th iteration +2023-08-23,18:00:24.289 - INFO - average ll reward: 0.2856317927 +2023-08-23,18:00:24.289 - INFO - ---------------------------------------------------- + +2023-08-23,18:00:24.569 - INFO - updating finished +2023-08-23,18:00:24.571 - INFO - biggest:0,rate = 0 diff --git a/raisimGymTorch/raisimGymTorch/deploy_log/csv_saver.py b/raisimGymTorch/raisimGymTorch/deploy_log/csv_saver.py new file mode 100644 index 000000000..b0650466e --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_log/csv_saver.py @@ -0,0 +1,26 @@ +import pandas as pd +import numpy as np + +class CSV_saver: + def __init__(self, name, path=None): + self.name = name + self.path = name+'.csv' if path == None else path+name+'.csv' + self.csv_list = [] + + def add_list(self, l): + self.csv_list.append(l.copy()) + + def save(self): + now = np.stack(self.csv_list) + now = now.transpose() + + now = pd.DataFrame(now) + now.to_csv(self.path) + print(f"{self.name} has been saved to {self.path}") + +if __name__ == "__main__": + obs = CSV_saver('real_obs') + for i in range(133): + obs.add_list(np.array([x for x in range(17)])) + + obs.save() diff --git a/raisimGymTorch/raisimGymTorch/deploy_log/draw_map.py b/raisimGymTorch/raisimGymTorch/deploy_log/draw_map.py new file mode 100644 index 000000000..5f45de0bf --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_log/draw_map.py @@ -0,0 +1,84 @@ +import random + +import matplotlib.pyplot as plt +import numpy as np +import time +map_mapping = [] +class Drawer: + def __init__(self, name, path=None): + self.name = name + self.path = name+'.png' if path == None else path+name+'.png' + self.draw_list = [] + + def add_map_list(self, l): + self.draw_list.append(l.copy()) + + def draw(self, lege=None): + plt.figure(figsize=(10,10)) + print(self.draw_list) + now = np.stack(self.draw_list) + now = now.transpose() + if lege is not None: + assert len(lege) == now.shape[0] + + le = now.shape[1] + color = plt.cm.rainbow(np.linspace(0, 1, now.shape[0])) + x = [i for i in range(le)] + print(le, now.shape) + print(now) + for i, c in enumerate(color): + plt.plot(x, now[i], c=c) + # if lege is not None: + # plt.legend() + plt.legend(lege) + plt.savefig(self.name) + + plt.show() + +class DynDrawer: + def __init__(self): + plt.ion() + plt.figure(1) + self.cnt = 0 + + def append_data(self,data): + plt.plot(self.cnt, data, '.') + self.cnt+=1 + plt.pause(0.01) + + def end(self): + plt.savefig('./test.png') + + + + +if __name__ == "__main__": + + import matplotlib.pyplot as plt + import numpy as np + import time + from math import * + + # plt.ion() # 开启interactive mode 成功的关键函数 + # plt.figure(1) + # t = [0] + # t_now = 0 + # m = [sin(t_now)] + # mm = [0] + # for i in range(200): + # # plt.clf() # 清空画布上的所有内容。此处不能调用此函数,不然之前画出的点,将会被清空。 + # t_now = i * 0.1 + # """ + # 由于第次只画一个点,所以此处有两种方式,第一种plot函数中的样式选 + # 为点'.'、'o'、'*'都可以,就是不能为线段'-'。因为一条线段需要两 + # 个点才能确定。第二种方法是scatter函数,也即画点。 + # """ + # plt.plot(t_now, sin(t_now), '.') # 第次对画布添加一个点,覆盖式的。 + # + # plt.plot(t_now, cos(t_now), 'o') + # + # plt.pause(0.01) + # plt.savefig('test.png') + dyn = DynDrawer() + for i in range(100): + dyn.append_data(0.01) \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/angle_utils.py b/raisimGymTorch/raisimGymTorch/deploy_utils/angle_utils.py new file mode 100644 index 000000000..e5021ef50 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/angle_utils.py @@ -0,0 +1,58 @@ +from math import sin,pi +import numpy as np +# from onnx_deploy import rad_deg, deg_rad +from raisimGymTorch.deploy_log.draw_map import Drawer +def deg_rad(x): + if isinstance(x, list): + return [deg_rad(a) for a in x] + else: + return x / 180 * pi + +def rad_deg(x): + if isinstance(x, list): + return [rad_deg(a) for a in x] + else: + return x / pi * 180 + + +low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] +upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] +low = deg_rad(low) +upp = deg_rad(upp) +bund = [upp[i] - low[i] for i in range(12)] +def transfer(act_gen, sine, k, history_act = None) ->np.array: + """ + clip, lerp, generate the final action + params: act_gen: [12 * (-1, 1)] np.array + params: sine: [12 * rad_target] np.array + """ + act_gen = act_gen * bund # - + + act_gen = np.clip(act_gen, low, upp) + if history_act is not None: + kk = 0.9 + act_gen = act_gen * (1-kk) + history_act * kk + act_gen = np.clip(act_gen, low, upp) + if act_gen.shape[0] == 1: + act_gen = act_gen[0] + action = act_gen * k + sine + # print(np.abs(act_gen).max(), sine.max()) + action = np.clip(action, low, upp) + return action + + +def get_last_position(obs): + if isinstance(obs, list): + x = [obs[-2 * i] for i in range(1, 13)] + x.reverse() + return x + elif isinstance(obs, np.ndarray): + x = [] + for i in range(1, 13): + x.append(obs[:, -2*i]) + x.reverse() + return np.stack(x, axis=1) + +if __name__=='__main__': + a = np.random.rand(2,30) + print(a) + print(get_last_position(a).shape) diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/data/Environment.hpp b/raisimGymTorch/raisimGymTorch/deploy_utils/data/Environment.hpp new file mode 100644 index 000000000..7e9f5b5c4 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/data/Environment.hpp @@ -0,0 +1,387 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#define PI 3.1415926 + +double cal(double low, double upp, double now){ + return (now + 1)/2 * (upp- low) + low; +} + +void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); +// std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } +// std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} + +void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +{ +// std::cout<< "size is "<< angle_list.size() << std::endl; + double base1= 0.82, base3=0.0; + double base2 = -2 * base1; + double ang = abs(sin( float(idx) / T * PI)) * rate; + + int idx_base = 0; +// std::cout<(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + /// add objects + anymal_ = world_->addArticulatedSystem(resourceDir_+"/a1/urdf/a1.urdf"); + anymal_->setName("dog"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); + nJoints_ = gvDim_ - 6; + + /// initialize containers + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + /// this is nominal configuration of anymal +// gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// anymal_1->setGeneralizedCoordinate(gc_init_); + gc_init_<< 0, 0, 0.30, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; + +// jointNominalConfig.tail(12).setZero(); + Eigen::VectorXd tmp(12); + tmp.setZero(); + angle_generator(tmp, 0, 80.f); + gc_init_.tail(12) = tmp; + + /// set pd gains + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(120.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(3); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + + /// MUST BE DONE FOR ALL ENVIRONMENTS + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + +// READ_YAML(); + actionStd_.setConstant(action_std); + + join_limit = anymal_->getJointLimits(); + /// Reward coefficients + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + /// indices of links that should not make contact with ground + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + void init() final { } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + /// action scaling + COUNT ++; +// std::cout<setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = 0; quat[1] = 0; quat[2] = 0; quat[3] = 0; +// raisim::quatToRotMat(quat, rot); +// anymal_->setBaseOrientation(rot); +// raisim::Vec<4> quat(4); +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// anymal_->setBaseOrientation(quat); +// pTarget_.tail(nJoints_) = angle_list; +// anymal_->setPdTarget(pTarget_, vTarget_); + } + // angle_list *= 0.3; +// angle_list.setZero(); + Eigen::VectorXd idx1(8), idx2(4); + idx1.setZero();idx2.setZero(); + idx1<<1, 2, 4, 5, 7,8,10,11; + idx2<<0, 3, 6, 9; + + pTarget12_ = action.cast(); + Eigen::VectorXd ttmp =action.cast(); + map_from_origin_to_limit(join_limit, pTarget12_,ttmp); + // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); +// pTarget12_ += actionMean_; +// pTarget12_ = angle_list; + + + angle_mulit(pTarget12_, idx1, action_std); + angle_mulit(pTarget12_, idx2, action_std); + + + angle_list_for_work = angle_list * for_work_rate; + + + + + pTarget12_ = angle_list_for_work + pTarget12_; +// pTarget12_[11] = pTarget12_[10] *-2; +// pTarget12_[8] = pTarget12_[7] * -2; +// pTarget12_[1] = -pTarget12_[10]; +// pTarget12_[2] = -pTarget12_[11]; +// pTarget12_[4] = -pTarget12_[7]; +// pTarget12_[5] = -pTarget12_[8]; +// pTarget12_[9] = -0.03; +// pTarget12_[0] = -pTarget12_[9]; +// pTarget12_[6] = 0.03; +// pTarget12_[3] = -pTarget12_[6]; + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } +// rrr *= float(COUNT )/ schedule_T); +// for(int i=0; i<=1; i++) +// { +// rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; +// } +// rrr += abs(gc_[5] - gc_init_[5]) * 2 * stable_reward_rate; +// if(COUNT != 0) +// { +// rrr += (gc_ - gc_init_).norm() * reference_rate *0.1; +// } + + +// rrr +=(gc_init_.head(7) - gc_.head(7)).norm() * stable_reward_rate; + rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; +// rrr += abs(bodyLinearVel_[1]); +// rrr += abs(bodyLinearVel_[2]); +// rrr += abs(bodyLinearVel_[0]); + +// rrr += abs(gc_[2] - gc_init_[2]) ; + +// rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::mi); + rewards_.record("Stable", 1 - rrr, false); + rewards_.record("forwardVel", bodyLinearVel_[0], false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// std::cout<< rot.e().row(2).transpose().size() << " " < ob) final { + /// convert it to float + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + +// / if the contact body is not feet + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// std::cout<<"terminate "<0.3 ) +// { +// return true; +// } +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) +// return true; + +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8 || ) +// return true; + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} + +//int main() +//{ +// raisim::ENVIRONMENT a("../rsc/","/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml", +// true); +//} \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/data/full_152.pt b/raisimGymTorch/raisimGymTorch/deploy_utils/data/full_152.pt new file mode 100644 index 000000000..2b22c8b00 Binary files /dev/null and b/raisimGymTorch/raisimGymTorch/deploy_utils/data/full_152.pt differ diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/data/mean152.csv b/raisimGymTorch/raisimGymTorch/deploy_utils/data/mean152.csv new file mode 100644 index 000000000..f0c635e53 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/data/mean152.csv @@ -0,0 +1,34 @@ +9.999681472778320312e+00 +-2.086427994072437286e-02 +1.569278188981115818e-03 +9.964596629142761230e-01 +8.982931263744831085e-03 +-4.897405160591006279e-04 +2.308465773239731789e-03 +6.522973999381065369e-03 +9.803665801882743835e-03 +-1.113907247781753540e-02 +-1.380026526749134064e-02 +9.374054670333862305e-01 +-1.863876342773437500e+00 +1.235901284962892532e-02 +9.295865297317504883e-01 +-1.863713383674621582e+00 +-9.648405015468597412e-03 +9.092029333114624023e-01 +-1.881086468696594238e+00 +9.312106296420097351e-03 +9.098838567733764648e-01 +-1.880328059196472168e+00 +0.000000000000000000e+00 +0.000000000000000000e+00 +0.000000000000000000e+00 +0.000000000000000000e+00 +0.000000000000000000e+00 +0.000000000000000000e+00 +0.000000000000000000e+00 +0.000000000000000000e+00 +0.000000000000000000e+00 +0.000000000000000000e+00 +0.000000000000000000e+00 +0.000000000000000000e+00 diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/onnx_deploy.py b/raisimGymTorch/raisimGymTorch/deploy_utils/onnx_deploy.py new file mode 100644 index 000000000..62849eff3 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/onnx_deploy.py @@ -0,0 +1,387 @@ +import time + +import onnxruntime as ort +# import onnx_file +# from mlprodict.onnxrt import OnnxInference +from math import cos,pi +import numpy as np +from raisimGymTorch.deploy_utils.angle_utils import deg_rad, rad_deg +from raisimGymTorch.deploy_log.draw_map import Drawer +# 加载模型 + + + +def ang_trans(lower, upper, x): + """ + trans the rate x to the angle + """ + if isinstance(lower, list): + return [ang_trans(lower[i], upper[i], x[i]) for i in range(len(lower))] + else: + x = (x+1)/2 #todo for test + return x * upper + (1-x) * lower + +def norm(lower, upper, x): + # print(lower, upper, x) + # assert abs((x - lower) / (upper - lower) ) <= 1, f"{abs((x - lower) / (upper - lower) )} {x, upper, lower} " + return (x - lower) / (upper - lower) + +def rad_normalize(lower, upper,x): + if isinstance(lower, list): + ans = [] + for a,b,c in zip(lower, upper, x): + ans.append(rad_normalize(a,b,c)) + return ans + else: + ang1 = x * 180 / pi + ang1 = norm(lower, upper, ang1) + return 2*ang1 - 1 + +def deg_normalize(lower, upper, x): + """ + make angle to rate from -1 -- 1 + """ + if isinstance(lower, list): + ans = [] + for a,b,c in zip(lower, upper, x): + ans.append(deg_normalize(a,b,c)) + return ans + else: + return 2 * norm(lower, upper, x) - 1 #todo for test + # return 1 - 2* norm(lower, upper,x) + + +low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] +upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] +tha1,tha2 = 60, 30 +u0 = [0, tha2, -2*tha2, 0 ,tha1, -tha1 * 2, 0 , tha2, -2*tha2, 0, tha1,-2*tha1] + +low_np = np.array(low) +upp_np = np.array(upp) +# u0_rad = deg_rad(u0) +# u0 = [0] * 12 # todo sure ? u0 = 0 +# low_rad = deg_rad(low) +# upp_rad = deg_rad(upp) +u0 = deg_normalize(low, upp, u0) +u0_ang = ang_trans(low, upp, u0) +# u0_rad = rad_normalize(low_rad, upp_rad, u0_rad) +# u0 = [-deg_normalize(low, upp, u0)[i] if deg_normalize(low, upp, u0)[i]!=0 else 0 for i in range(12)] +# print(u0) +history_u = [0] * 12 +# history_u_rad = [0] * 12/ +# history_u = u0.copy() +model = ort.InferenceSession('/env/deploy_utils/onnx_file/2203.onnx') + +idx_local = 0 + +# 准备输入 +input_name = model.get_inputs()[0].name +# print(model.get_outputs()) +output_name = model.get_outputs()[2].name +print(input_name, output_name) +# input_data = np.random.rand(1, 34).astype(np.float32) + +# def sine_gene_test_qua(idx, T): +# angle_list = [0 for i in range(12)] +# if idx >= 2 * T: +# idx = 0 +# dh = 1.2 # todo for test +# if idx >= 0 and idx <= T: +# tp0 =idx - 0 +# y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 +# y2 = 0 +# elif idx>T and idx<=2*T: +# tp0 =idx - T +# y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 +# y1 = 0 +# +# +# angle_list[0] = 0 +# angle_list[1] = y1 +# angle_list[2] = -2 * y1 +# angle_list[3] = 0 +# angle_list[4] = y2 +# angle_list[5] = -2 * y2 +# angle_list[6] = 0 +# angle_list[7] = y1 +# angle_list[8] = -2 * y1 +# angle_list[9] = 0 +# angle_list[10] = y2 +# angle_list[11] = -2 * y2 +# angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + ang_trans(low[i], upp[i], u0[i])) for i in range(12)] +# return angle_list + + +def sine_gene(idx, T): + # print(idx) + if isinstance(idx, np.ndarray) or isinstance(idx, list): + mat = np.zeros((len(idx), 12)) + i_set = set(idx) + idd = {} + for i in i_set: + idd[i] = sine_gene(i, 40) + for i in range(len(idx)): + mat[i] = idd[idx[i]] + return mat + if not isinstance(idx, list): + angle_list = [0 for i in range(12)] + if idx >= 2 * T: + idx = 0 + dh = 1.6 # todo for test + + if idx >= 0 and idx <= T: + tp0 =idx - 0 + y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y2 = 0 + y2 = y1 + elif idx>T and idx<=2*T: + tp0 =idx - T + y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y1 = 0 + y1 = y2 + + + angle_list[0] = 0 + angle_list[1] = y1 + angle_list[2] = -2 * y1 + angle_list[3] = 0 + angle_list[4] = y2 + angle_list[5] = -2 * y2 + angle_list[6] = 0 + angle_list[7] = y2 + angle_list[8] = -2 * y2 + angle_list[9] = 0 + angle_list[10] = y1 + angle_list[11] = -2 * y1 + # print("ang_list ", angle_list) + angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + ang_trans(low[i], upp[i], u0[i]) ) for i in range(12)] + # print("ang_list ", angle_list) + return angle_list + else: + ans = [] + for i in idx: + ans.append(sine_gene(i, T)) + return ans + +def sine_gene_pt(idx, T): + # print(idx) + if isinstance(idx, np.ndarray) or isinstance(idx, list): + mat = np.zeros((len(idx), 12)) + i_set = set(idx) + idd = {} + for i in i_set: + idd[i] = sine_gene_pt(i, 40) + for i in range(len(idx)): + mat[i] = idd[idx[i]] + return mat + if not isinstance(idx, list): + angle_list = [0 for i in range(12)] + if idx >= 2 * T: + idx = 0 + dh =-0.5#:w + + + # if idx >= 0 and idx <= T: + # tp0 =idx - 0 + # y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + # y2 = 0 + # # y2 = y1 + # elif idx>T and idx<=2*T: + # tp0 =idx - T + # y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + # y1 = 0 + # y1 = y2 + idx = idx % T + y1 = dh * 10 * (-cos(pi * 2 *idx /T) + 1) + y2 = deg_rad(60) + angle_list[0] = 0 + angle_list[1] = y1 + angle_list[2] = -2 * y1 + angle_list[3] = 0 + angle_list[4] = y2 + angle_list[5] = -2 * y2 + angle_list[6] = 0 + angle_list[7] = y1 + angle_list[8] = -2 * y1 + angle_list[9] = 0 + angle_list[10] = y2 + angle_list[11] = -2 * y2 + + angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + u0_ang[i]) for i in range(12)] + + return angle_list + else: + ans = [] + for i in idx: + ans.append(sine_gene_pt(i, T)) + return ans + + +def rate_to_act(lower, upper, rate): + if isinstance(lower, list): + return [rate_to_act(a,b,c) for a,b,c in zip(lower,upper, rate)] + else: + norm_for_act = lambda a: (a+1)*0.5 + lerp = lambda a, b, c: a*(1-c) + b * c + # print("11111 ", lower, upper, rate, lerp(lower, upper, norm_for_act(rate))) + + return lerp(lower, upper, norm_for_act(rate)) + +def clip(a,b,c): + if isinstance(a, np.ndarray): + return np.clip(a,b,c) + + if a <= b : + a = b + if a >= c: + a = c + return a + +def add_list(act_gen, sine, history=None): + if isinstance(act_gen, np.ndarray): + assert act_gen.shape[0] == 12 + else: + assert len(act_gen) == 12 + kk = 0.9 + kf = 1 + kb = 0.4 + if history is None: + global history_u + + # print(history_u, act_gen) + history_u = [history_u[i] * kk + (1-kk) * act_gen[i] for i in range(12)] # todo the act_gen[i] is to big + # print("11111", history_u, act_gen) + + ans = [rate_to_act(low[i], upp[i], clip(kb * history_u[i] + kf * sine[i], -1, 1)) for i in range(12)] + ans = [deg_rad(x) for x in ans] + return ans + else: + history = [history[i] * kk + (1-kk) * act_gen[i] for i in range(12)] # todo the act_gen[i] is to big + ans = [rate_to_act(low[i], upp[i], clip(kb * history[i] + kf * sine[i], -1, 1)) for i in range(12)] + ans = [deg_rad(x) for x in ans] + return ans, history + +def lerp_np(a, b, c): + return a* (1-c) + b*c + +def add_list_np(act_gen, sine, history): + kk = 0.9 + kf = 1 + kb = 0.2 + history = history*kk + (1-kk) * act_gen + ans = np.clip(kb*history + kf * sine, -1, 1) + ans = (ans + 1) /2 # 100 * 12 + ans = lerp_np(low_np, upp_np, ans) + + return ans, history + + +def run_model_with_pt_input_modify(act_gen, idx, T, history): + act_gen = np.clip(act_gen- 1, -1, 1) + if isinstance(idx, list): + idx = np.array(idx) + idx = idx%(2*T) + else: + idx = idx % (2 * T) + + sine = sine_gene_pt(idx, T) + ans, history = add_list_np(act_gen, sine, history) + ans = ans / 180 * 3.14 + + return ans.astype(np.float32), history.astype(np.float32) + + + +def list_pt(act_gen, idx, T): + ans = [] + for i in range(act_gen.shape[0]): + ans.append(run_model_with_pt_input(act_gen[i, :], idx[i], T)) + ans = np.vstack(ans).astype(np.float32) + return ans + +def run_model(observation, idx, T, save_gen=None): + # todo idx should return 0 when fall + idx = idx % (2 * T) + # print(observation.shape) + # obs = rad_deg(observation) + observation[:, [0,1]] = observation[:, [1,0]] + observation[:, [1]] = - observation[:, [1]] + + # observation[:,[2,3,4]] = rad_deg(observation[:, [2,3,4]]) + # observation[:,[2,3,4]] = observation[:, [2,3,4]] + observation[:,[2,3,4]] = observation[:, [3,4,2]] + # observation[:,[2,3,4]] = rad_deg(observation[:, [3,4,2]]) + observation[:, [3, 4]] = - observation[:, [3, 4]] + # observation[:, [4] + if observation.shape[1] == 29: + offset = 0 + elif observation.shape[1] == 26: + offset = 3 + else: + offset = 5 + # print('offset' ,offset) + be_obe =[5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28] + aft_obs = [23,24,25,26,27,28,17,18,19,20,21,22,11,12,13,14,15,16,5,6,7,8,9,10] + be_obe = [i -offset for i in be_obe] + aft_obs=[i -offset for i in aft_obs] + # print(be_obe, aft_obs) + observation[: ,be_obe]=\ + observation[: ,aft_obs] + + + act_gen = model.run([output_name], input_feed={input_name: observation}) + act_gen = act_gen[0] + + # minu = np.array([0, 0, deg_rad(30), 0, deg_rad(-60), 0] * 4) # 6 + # observation[:, -24:] -= minu + + act_gen = np.zeros((1,12)) + if save_gen is not None: + save_gen.add_list(act_gen[0]) + + sine = sine_gene(idx, T) + ans = [] + for act in act_gen: + ans.append(add_list(act, sine)) + ans = np.array(ans).astype(np.float32) + ans[:, [0,1,2,3,4,5,6,7,8,9,10,11]] = \ + ans[:, [9,10,11,6,7,8,3,4,5,0,1,2]] + ans = [ans] + + return ans, observation + + +def run_model1(observation): + return model.run([output_name], input_feed={input_name: observation}) + +if __name__=="__main__": + + z = [] + minn = 100 + minnn =[] + for i in range(100): + # x = run_model(np.zeros((1,26)).astype(np.float32), i, 40)[0][0][0] + x = add_list(np.zeros((12)), sine_gene(i, 40)) + if i == 0: + print(x) + if x[1] <= minn: + print(x[1], minn) + minn = x[1] + minnn =x + z.append(x) + z = np.vstack(z) + print(minnn) + x= [i for i in range(z.shape[0])] + import matplotlib.pyplot as plt + plt.plot(x, z) + plt.show() + + + +def test_run_model(): + ans = run_model(np.zeros((1, 34)).astype(np.float32), 10, 50) + ans1 = run_model1(np.zeros((1, 34)).astype(np.float32)) + assert ans1[0] == ans[0] + +def test_norm(): + assert deg_normalize(-10, 10, -10) == -1 \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py b/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py new file mode 100644 index 000000000..f33cbf617 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py @@ -0,0 +1,318 @@ +import math + +import numpy as np +from math import cos,pi +def lerp_np(a, b, c): + return a* (1-c) + b*c +def add_list_np(act_gen, sine, history,kb): + kk = 0.95 + kf = 1 + # kb = np.array([0.15 ,0., 0.] * 4) + # print(act_gen) + # kb = np.array([0.2,0.1, 0.1] * 4 ) + kb = np.array([0.2] *12 ) + history = history*kk + (1-kk) * act_gen + ans = np.clip(kb*history + kf * sine, -1, 1) + ans = (ans + 1) /2 # 100 * 12 + ans = lerp_np(low_np, upp_np, ans) + + return ans, history +def ang_trans(lower, upper, x): + """ + trans the rate x to the angle + """ + if isinstance(lower, list): + return [ang_trans(lower[i], upper[i], x[i]) for i in range(len(lower))] + else: + x = (x+1)/2 + return x * upper + (1-x) * lower +def norm(lower, upper, x): + # print(lower, upper, x) + # assert abs((x - lower) / (upper - lower) ) <= 1, f"{abs((x - lower) / (upper - lower) )} {x, upper, lower} " + return (x - lower) / (upper - lower) +def deg_rad(x): + if isinstance(x, list): + return [deg_rad(a) for a in x] + else: + return x / 180 * pi + +def rad_deg(x): + if isinstance(x, list): + return [rad_deg(a) for a in x] + else: + return x * 180 / pi +def deg_normalize(lower, upper, x): + """ + make angle to rate from -1 -- 1 + """ + if isinstance(lower, list): + ans = [] + for a,b,c in zip(lower, upper, x): + ans.append(deg_normalize(a,b,c)) + return ans + else: + return 2 * norm(lower, upper, x) - 1 + +def rad_normalize(lower, upper, x): + if isinstance(lower, list): + ans = [] + for a,b,c in zip(lower, upper, x): + ans.append(deg_normalize(a,b,c)) + return ans + else: + return 2 * norm(lower, upper, x) - 1 + + # return 1 - 2* norm(lower, upper,x) +low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] +upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] +abss = 8 +tha1,tha2 = 41 + abss , 41 + abss +for_r = 0 +u0 = [0, tha2, -2*tha2 +2 * abss , 0 ,tha1, -tha1 * 2 +2*abss , 0 , tha2 + for_r , -2*tha2 - 2 * for_r +2*abss, 0, tha1 + for_r ,-2*tha1 -2 * for_r +2*abss] + +low_np = np.array(low) +upp_np = np.array(upp) +u0_rad = deg_rad(u0) + +low_rad = low_np / 180 * 3.14 +upp_rad = upp_np / 180 * 3.14 + +u0 = deg_normalize(low, upp, u0) +u0_ang = ang_trans(low, upp, u0) + + +def sine_gene_pt(idx, T, rate): + # print(idx) + if isinstance(idx, np.ndarray) or isinstance(idx, list): + mat = np.zeros((len(idx), 12)) + i_set = set(idx) + idd = {} + for i in i_set: + idd[i] = sine_gene_pt(i, T, rate) + for i in range(len(idx)): + mat[i] = idd[idx[i]] + return mat + if not isinstance(idx, list): + angle_list = [0 for i in range(12)] + if idx >= 2 * T: + idx = 0 + dh = rate #:w + # assert dh == 0.6 + ds = 0. + H = 0.3 + # print(idx) + if idx >= 0 and idx <= T: + tp0 =idx - 0 + y1 = dh * 0.05 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y2 = 0 + x1 =ds * (-0.05 + 0.1 * tp0 /T) + x2 = ds * (0.05 - 0.1 * tp0 / T) + # y11 = 0 + + elif idx>T and idx<=2*T: + tp0 =idx - T + y2 = dh * 0.05 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y1 = 0 + x1 =ds * (0.05 - 0.1 * tp0 /T) + x2 = ds * (-0.05 + 0.1 * tp0 / T) + # y1 = y2 /2 + # y1 = -y2 + # y1 = y2 + # idx = idx % T + # y1 = dh * 10 * (-cos(pi * 2 *idx /T) + 1) + # y2 = deg_rad(60) + # y1 = 2 * y1 + # y2 = 2 * y2 + + # ct0 = math.atan(- x1 / (H-y1)) + # L0 = math.sqrt((H-y1) **2 + x1 ** 2 ) + # ct1 = math.acos(L0 / 0.4) + # + # c1 = ct0 + ct1 + # c2 = -2 * ct1 + # + # act0 = math.atan(-x2/(H-y2)) + # aL0 = math.sqrt((H-y2) ** 2 + x2 **2 ) + # act1 = math.acos(aL0 / 0.4 ) + # + # ac1 = act0 + act1 + # ac2 = -2 * act1 + # + # + # angle_list[0] = 0 + # angle_list[1] = c1 + # angle_list[2] = c2 + # angle_list[3] = 0 + # angle_list[4] = ac1 + # angle_list[5] = ac2 + # angle_list[6] = 0 + # angle_list[7] = ac1 + # angle_list[8] = ac2 + # angle_list[9] = 0 + # angle_list[10] = c1 + # angle_list[11] = c2 + + + + ct0 = math.atan(-x1 / (H - y1)) + L0 = math.sqrt((H - y1) * (H - y1) + x1 * x1) + ct1 = math.acos(L0 / 0.4) + c1 = ct0 + ct1 + c2 = -2 * ct1 + + act0 = math.atan(-x2 / (H - y2)) + aL0 = math.sqrt((H - y2) * (H - y2) + x2 * x2) + act1 = math.acos(aL0 / 0.4) + ac1 = act0 + act1 + ac2 = -2 * act1 + abss = 8 + angle_list[0] = 0 + angle_list[1] = ac1 + deg_rad(abss) + angle_list[2] = ac2 + angle_list[3] = 0 + angle_list[4] = c1 + deg_rad(abss) + angle_list[5] = c2 + angle_list[6] = 0 + angle_list[7] = ac1 + deg_rad(abss) + angle_list[8] = ac2 + angle_list[9] = 0 + angle_list[10] = c1 + deg_rad(abss) + angle_list[11] = c2 + + + angle_list = rad_deg(angle_list) + # print(angle_list) + angle_list = [deg_normalize(low[i], upp[i], angle_list[i] ) for i in range(12)] + # angle_list = [rad_normalize(low_rad[i] , upp_rad[i], angle_list[i] + u0_rad[i]) for i in range(12)] + return angle_list + else: + ans = [] + for i in idx: + ans.append(sine_gene_pt(i, T, rate)) + return ans + +def sine_gene_pt_step(idx, T, rate): + # print(idx) + if isinstance(idx, np.ndarray) or isinstance(idx, list): + mat = np.zeros((len(idx), 12)) + i_set = set(idx) + idd = {} + for i in i_set: + idd[i] = sine_gene_pt_step(i, T, rate) + for i in range(len(idx)): + mat[i] = idd[idx[i]] + return mat + if not isinstance(idx, list): + angle_list = [0 for i in range(12)] + if idx >= 2 * T: + idx = 0 + dh = 0.6 #:w + + + if idx >= 0 and idx <= T: + tp0 =idx - 0 + y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + # y11 = 0.7 * dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + # y11 = 0 + + y2 = 0 + # y22 = -y11 * 0.5 + # y2 = y1 /2 + # y2 = -y1 + # y2 = y1 + # y1 = 1.5 * y1 + elif idx>T and idx<=2*T: + tp0 =idx - T + y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + # y22 = 0.7 * dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + # y11 = 0 + + y1=0 + # y11 = -y2 * 0.5 + # y1 = y2 /2 + # y1 = -y2 + # y1 = y2 + # idx = idx % T + # y1 = dh * 10 * (-cos(pi * 2 *idx /T) + 1) + # y2 = deg_rad(60) + # y1 = 2 * y1 + # y2 = 2 * y2 + angle_list[0] = 0 + angle_list[1] = y1 + angle_list[2] = -2 * y1 + angle_list[3] = 0 + angle_list[4] = y2 + angle_list[5] = -2 * y2 + angle_list[6] = 0 + angle_list[7] = y2 + angle_list[8] = -2 * y2 + angle_list[9] = 0 + angle_list[10] = y1 + angle_list[11] = -2 * y1 + + angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + u0_ang[i]) for i in range(12)] + + return angle_list + else: + ans = [] + for i in idx: + ans.append(sine_gene_pt_step(i, T, rate)) + return ans +def list_pt(act_gen, idx, T): + ans = [] + for i in range(act_gen.shape[0]): + ans.append(run_model_with_pt_input(act_gen[i, :], idx[i], T)) + ans = np.vstack(ans).astype(np.float32) + return ans + +def step_reset(act_gen, idx, T, history, kb, rate): + # act_gen = np.clip(act_gen- 1, -1, 1) + if isinstance(idx, list): + idx = np.array(idx) + idx = idx % (2 * T) + else: + idx = idx % (2 * T) + act_gen = np.zeros_like(act_gen) + # print(act_gen.mean()) + sine = sine_gene_pt_step(idx, T, rate) + ans, history = add_list_np(act_gen, sine, history, kb) + ans = ans / 180 * 3.14 + # ans = np.array([0] + ans.tolist()[0]) + return ans.astype(np.float32), history.astype(np.float32) + + +def run_model_with_pt_input_modify(act_gen, idx, T, history, kb, rate): + # act_gen = np.clip(act_gen- 1, -1, 1) + # qq = 1 if (idx // (10 * T)) % 2 == 0 else -1 + # print(qq) + if isinstance(idx, list): + idx = np.array(idx) + idx = idx%(2*T) + else: + idx = idx % (2 * T) + # + act_gen[:, 0] = act_gen[:, 6+0] + act_gen[:, 1] = act_gen[:, 6+1] + act_gen[:, 2] = act_gen[:, 6+2] + act_gen[:, 3] = act_gen[:, 6+3] + act_gen[:, 4] = act_gen[:, 6+4] + act_gen[:, 5] = act_gen[:, 6+5] + # act_gen[:, 10] = act_gen[:, 3+1] + # act_gen[:, 11] = act_gen[:, 3+2] + # act_gen[:, 7] = act_gen[:, 3+1] + # act_gen[:, 8] = act_gen[:, 3+2] + + # act_gen = np.zeros_like(act_gen) + # print(act_gen.mean()) + sine = sine_gene_pt(idx, T, rate) + ans, history = add_list_np(act_gen, sine, history, kb) + ans = ans / 180 * 3.14 + # ans = np.array([qq] + ans.tolist()[0]) + # print(ans.astype(np.float32)) + return ans.astype(np.float32), history.astype(np.float32) + +if __name__=='__main__': + # print(run_model_with_pt_input_modify(np.zeros((1,12)), 0, 30, np.zeros((1,12)), 0.15, 0.6)) + # print(step_reset(np.zeros((1,12)), 0, 30, np.zeros((1,12)), 0.15, 0.6)) + for i in range(100): + print(run_model_with_pt_input_modify(np.zeros((1,12)), i ,30, np.zeros((1,12)),0.15,0.6)) \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/thread_protect.py b/raisimGymTorch/raisimGymTorch/deploy_utils/thread_protect.py new file mode 100644 index 000000000..8c5760b51 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/thread_protect.py @@ -0,0 +1,29 @@ +import concurrent.futures +import threading +import time +import numpy as np +from raisimGymTorch.deploy_log.csv_saver import CSV_saver +def cal(): + print('calculating model') + time.sleep(0.1) + + +def save(saver:CSV_saver, data): + # print('add data') + saver.add_list(data) + print(len(saver.csv_list)) + saver.save() + + +if __name__=='__main__': + print('start') + + csv = CSV_saver('./test') + + for i in range(100): + data = np.zeros((1000,10)) + cal() + # print(data) + with concurrent.futures.ThreadPoolExecutor(max_workers=1) as exec: + exec.submit(save, data) + print('running robot') \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/RaisimGymEnv.hpp b/raisimGymTorch/raisimGymTorch/env/RaisimGymEnv.hpp index f1c4914cf..343069354 100755 --- a/raisimGymTorch/raisimGymTorch/env/RaisimGymEnv.hpp +++ b/raisimGymTorch/raisimGymTorch/env/RaisimGymEnv.hpp @@ -28,6 +28,7 @@ class RaisimGymEnv { /////// implement these methods ///////// virtual void init() = 0; + virtual void init_position(const Eigen::Ref& posi) = 0; virtual void reset() = 0; virtual void observe(Eigen::Ref ob) = 0; virtual float step(const Eigen::Ref& action) = 0; @@ -48,6 +49,7 @@ class RaisimGymEnv { double getSimulationTimeStep() { return simulation_dt_; } raisim::World* getWorld() { return world_.get(); } void turnOffVisualization() { server_->hibernate(); } +// void init_position() {} void turnOnVisualization() { server_->wakeup(); } void startRecordingVideo(const std::string& videoName ) { server_->startRecordingVideo(videoName); } void stopRecordingVideo() { server_->stopRecordingVideo(); } diff --git a/raisimGymTorch/raisimGymTorch/env/RaisimGymVecEnv.py b/raisimGymTorch/raisimGymTorch/env/RaisimGymVecEnv.py index 882d84873..bec722c02 100755 --- a/raisimGymTorch/raisimGymTorch/env/RaisimGymVecEnv.py +++ b/raisimGymTorch/raisimGymTorch/env/RaisimGymVecEnv.py @@ -32,6 +32,9 @@ def __init__(self, impl, normalize_ob=True, seed=0, clip_obs=10.): def seed(self, seed=None): self.wrapper.setSeed(seed) + def init_position(self, position): + self.wrapper.init_position(position) + def turn_on_visualization(self): self.wrapper.turnOnVisualization() @@ -45,6 +48,10 @@ def stop_video_recording(self): self.wrapper.stopRecordingVideo() def step(self, action): + # print(action.size) + # print(type(action)) + # print(action.shape) + # print(action.max(), action.min()) self.wrapper.step(action, self._reward, self._done) return self._reward.copy(), self._done.copy() diff --git a/raisimGymTorch/raisimGymTorch/env/RewardAnalyzer.py b/raisimGymTorch/raisimGymTorch/env/RewardAnalyzer.py index a486fd083..217b1c9fc 100644 --- a/raisimGymTorch/raisimGymTorch/env/RewardAnalyzer.py +++ b/raisimGymTorch/raisimGymTorch/env/RewardAnalyzer.py @@ -13,33 +13,33 @@ def __init__(self, env, writer): self.data_tags = list(reward_info[0].keys()) self.data_size = 0 self.data_mean = np.zeros(shape=(len(self.data_tags), 1), dtype=np.double) - self.data_square_sum = np.zeros(shape=(len(self.data_tags), 1), dtype=np.double) - self.data_min = np.inf * np.ones(shape=(len(self.data_tags), 1), dtype=np.double) - self.data_max = -np.inf * np.ones(shape=(len(self.data_tags), 1), dtype=np.double) + # self.data_square_sum = np.zeros(shape=(len(self.data_tags), 1), dtype=np.double) + # self.data_min = np.inf * np.ones(shape=(len(self.data_tags), 1), dtype=np.double) + # self.data_max = -np.inf * np.ones(shape=(len(self.data_tags), 1), dtype=np.double) def add_reward_info(self, info): self.data_size += len(info) for i in range(len(self.data_tags)): for j in range(len(info)): - self.data_square_sum[i] += info[j][self.data_tags[i]]*info[j][self.data_tags[i]] + # self.data_square_sum[i] += info[j][self.data_tags[i]]*info[j][self.data_tags[i]] self.data_mean[i] += info[j][self.data_tags[i]] - self.data_min[i] = min(self.data_min[i], info[j][self.data_tags[i]]) - self.data_max[i] = max(self.data_max[i], info[j][self.data_tags[i]]) + # self.data_min[i] = min(self.data_min[i], info[j][self.data_tags[i]]) + # self.data_max[i] = max(self.data_max[i], info[j][self.data_tags[i]]) def analyze_and_plot(self, step): self.data_mean /= self.data_size - data_std = np.sqrt((self.data_square_sum - self.data_size * self.data_mean * self.data_mean) / (self.data_size - 1 + 1e-16)) + # data_std = np.sqrt((self.data_square_sum - self.data_size * self.data_mean * self.data_mean) / (self.data_size - 1 + 1e-16)) for data_id in range(len(self.data_tags)): self.writer.add_scalar(self.data_tags[data_id]+'/mean', self.data_mean[data_id], global_step=step) - self.writer.add_scalar(self.data_tags[data_id]+'/std', data_std[data_id], global_step=step) - self.writer.add_scalar(self.data_tags[data_id]+'/min', self.data_min[data_id], global_step=step) - self.writer.add_scalar(self.data_tags[data_id]+'/max', self.data_max[data_id], global_step=step) + # self.writer.add_scalar(self.data_tags[data_id]+'/std', data_std[data_id], global_step=step) + # self.writer.add_scalar(self.data_tags[data_id]+'/min', self.data_min[data_id], global_step=step) + # self.writer.add_scalar(self.data_tags[data_id]+'/max', self.data_max[data_id], global_step=step) self.data_size = 0 self.data_mean = np.zeros(shape=(len(self.data_tags), 1), dtype=np.double) - self.data_square_sum = np.zeros(shape=(len(self.data_tags), 1), dtype=np.double) - self.data_min = np.inf * np.ones(shape=(len(self.data_tags), 1), dtype=np.double) - self.data_max = -np.inf * np.ones(shape=(len(self.data_tags), 1), dtype=np.double) + # self.data_square_sum = np.zeros(shape=(len(self.data_tags), 1), dtype=np.double) + # self.data_min = np.inf * np.ones(shape=(len(self.data_tags), 1), dtype=np.double) + # self.data_max = -np.inf * np.ones(shape=(len(self.data_tags), 1), dtype=np.double) diff --git a/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp b/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp index 6da980fdd..8e4583230 100755 --- a/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp +++ b/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp @@ -8,6 +8,7 @@ #include "RaisimGymEnv.hpp" #include "omp.h" +#include #include "Yaml.hpp" namespace raisim { @@ -78,6 +79,13 @@ class VectorizedEnvironment { env->reset(); } + void init_position(Eigen::Ref &posi) + { +#pragma omp parallel for schedule(auto) + for(int i = 0; i < num_envs_; i++) + environments_[i]->init_position(posi.row(i)); + } + void observe(Eigen::Ref &ob, bool updateStatistics) { #pragma omp parallel for schedule(auto) for (int i = 0; i < num_envs_; i++) @@ -174,14 +182,15 @@ class VectorizedEnvironment { Eigen::Ref &reward, Eigen::Ref &done) { reward[agentId] = environments_[agentId]->step(action.row(agentId)); - rewardInformation_[agentId] = environments_[agentId]->getRewards().getStdMap(); float terminalReward = 0; done[agentId] = environments_[agentId]->isTerminalState(terminalReward); + rewardInformation_[agentId] = environments_[agentId]->getRewards().getStdMap(); if (done[agentId]) { environments_[agentId]->reset(); reward[agentId] += terminalReward; +// std::cout<<"agentid "<< agentId <<" reward " << reward[agentId] << std::endl; } } @@ -228,7 +237,7 @@ class NormalSampler { } void seed(int seed) { - // this ensures that every thread gets a different seed + // this ensures that every thread gets a different see #pragma omp parallel for schedule(static, 1) for (int i = 0; i < THREAD_COUNT; i++) normal_[0].seed(i + seed); diff --git a/raisimGymTorch/raisimGymTorch/env/auto_runner.py b/raisimGymTorch/raisimGymTorch/env/auto_runner.py new file mode 100644 index 000000000..5cf11d923 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/auto_runner.py @@ -0,0 +1,26 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +import os + +# file = open('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml') +def change_data(path, flag, data): + y = YAML().load(open(path, 'r')) + for a,b in zip(flag, data): + y['environment'][a] = b + # wr = yaml.dump(y) + print(y) + with open(path, 'w') as f : + dump(y, f, Dumper=RoundTripDumper) + +test_list = [x/100 for x in range(4,20,4)] +test_T = [40] +# print(test_list) +length = 500 +for j in test_T: + for i in test_list: + change_data('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml',['action_std','schedule'], [i, j]) + if i == 0: + continue + else: + os.system(f'python /home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py -u {length} |grep biggest' ) + +# os.system('python /home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner_util.py -u 3 |grep biggest' ) diff --git a/raisimGymTorch/raisimGymTorch/env/debug_app.cpp b/raisimGymTorch/raisimGymTorch/env/debug_app.cpp index 88fd18fb1..58410fe12 100755 --- a/raisimGymTorch/raisimGymTorch/env/debug_app.cpp +++ b/raisimGymTorch/raisimGymTorch/env/debug_app.cpp @@ -9,6 +9,59 @@ int THREAD_COUNT = 1; using namespace raisim; +#define PI 3.1415926 +//void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +//{ +//// std::cout<< "size is "<< angle_list.size() << std::endl; +// double base1= 0.4, base2 = -0.8, base3=0.03; +// double ang = abs(sin( float(idx) / T * PI)) * rate; +// +// int idx_base = 0; +//// std::cout<(), 1); EigenBoolVec dones(config["num_envs"].template As(), 1); action.setZero(); +// for(auto i:action.rows()) + std::cout< ob_ref(observation), action_ref(action); Eigen::Ref reward_ref(reward); Eigen::Ref dones_ref(dones); +// std::cout< +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#define PI 3.1415926 + +double cal(double low, double upp, double now){ + return (now + 1)/2 * (upp- low) + low; +} +void swap(Eigen::VectorXd &ob, int a, int b) +{ + double tmp = ob[a]; + ob[a] = ob[b]; + ob[b] = ob[a]; +} + +double rad_deg(double rad) +{ + return rad / PI * 180; +} + +void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); +// std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } +// std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} + +//void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +//{ +//// std::cout<< "size is "<< angle_list.size() << std::endl; +// double base1= 0.82, base3=0.0; +// double base2 = -2 * base1; +// double ang = abs(sin( float(idx) / T * PI)) * rate; +// +// int idx_base = 0; +//// std::cout<(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + /// add objects + anymal_ = world_->addArticulatedSystem(resourceDir_+"/a1_description/urdf/a1.urdf"); + anymal_->setName("dog"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); + nJoints_ = gvDim_ - 6; + + /// initialize containers + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + /// this is nominal configuration of anymal +// gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// anymal_1->setGeneralizedCoordinate(gc_init_); + gc_init_<< 0, 0, 0.41, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; + +// jointNominalConfig.tail(12).setZero(); +// Eigen::VectorXd tmp(12); +// tmp.setZero(); +// angle_generator(tmp, 0, 80.f); +// gc_init_.tail(12) = tmp; + + /// set pd gains + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(2000.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(100); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + + /// MUST BE DONE FOR ALL ENVIRONMENTS + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + +// READ_YAML(); + actionStd_.setConstant(action_std); + + join_limit = anymal_->getJointLimits(); + /// Reward coefficients + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + /// indices of links that should not make contact with ground + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + void init() final { } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + /// action scaling +// COUNT ++; +// std::cout<setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = 0; quat[1] = 0; quat[2] = 0; quat[3] = 0; +// raisim::quatToRotMat(quat, rot); +// anymal_->setBaseOrientation(rot); +// raisim::Vec<4> quat(4); +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// anymal_->setBaseOrientation(quat); +// pTarget_.tail(nJoints_) = angle_list; +// anymal_->setPdTarget(pTarget_, vTarget_); + } + // angle_list *= 0.3; +// angle_list.setZero(); +// Eigen::VectorXd idx1(8), idx2(4); +// idx1.setZero();idx2.setZero(); +// idx1<<1, 2, 4, 5, 7,8,10,11; +// idx2<<0, 3, 6, 9; + + pTarget12_ = action.cast(); +// Eigen::VectorXd ttmp =action.cast(); +// map_from_origin_to_limit(join_limit, pTarget12_,ttmp); + // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); +// pTarget12_ += actionMean_; +// pTarget12_ = angle_list; + + +// angle_mulit(pTarget12_, idx1, action_std); +// angle_mulit(pTarget12_, idx2, action_std); +// +// +// angle_list_for_work = angle_list * for_work_rate; + + + + +// pTarget12_ = angle_list_for_work + pTarget12_; + + + +// pTarget12_[11] = pTarget12_[10] *-2; +// pTarget12_[8] = pTarget12_[7] * -2; +// pTarget12_[1] = -pTarget12_[10]; +// pTarget12_[2] = -pTarget12_[11]; +// pTarget12_[4] = -pTarget12_[7]; +// pTarget12_[5] = -pTarget12_[8]; +// pTarget12_[9] = -0.03; +// pTarget12_[0] = -pTarget12_[9]; +// pTarget12_[6] = 0.03; +// pTarget12_[3] = -pTarget12_[6]; + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } +// rrr *= float(COUNT )/ schedule_T); +// for(int i=0; i<=1; i++) +// { +// rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; +// } +// rrr += abs(gc_[5] - gc_init_[5]) * 2 * stable_reward_rate; +// if(COUNT != 0) +// { +// rrr += (gc_ - gc_init_).norm() * reference_rate *0.1; +// } + + +// rrr +=(gc_init_.head(7) - gc_.head(7)).norm() * stable_reward_rate; + rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; +// rrr += abs(bodyLinearVel_[1]); +// rrr += abs(bodyLinearVel_[2]); +// rrr += abs(bodyLinearVel_[0]); + +// rrr += abs(gc_[2] - gc_init_[2]) ; + +// rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::mi); + rewards_.record("Stable", 1 - rrr, false); + rewards_.record("forwardVel", bodyLinearVel_[0], false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// std::cout<< rot.e().row(2).transpose().size() << " " < ob) final { + /// convert it to float + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + +// / if the contact body is not feet + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// std::cout<<"terminate "<0.3 ) +// { +// return true; +// } +// if(abs(gc_[4]-gc_init_[4]) >0.2 ) +// { +// return true; +// } +// if(abs(gc_[6]-gc_init_[6]) >0.2 ) +// { +// return true; +// } +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) +// return true; + +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8 || ) +// return true; + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} + +//int main() +//{ +// raisim::ENVIRONMENT a("../rsc/","/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml", +// true); +//} \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_skate.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_skate.hpp new file mode 100644 index 000000000..6fa5d0d06 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_skate.hpp @@ -0,0 +1,316 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#include +#define PI 3.1415926 + +namespace raisim { + + auto ToEulerAngles(Eigen::Quaterniond q) { + Eigen::Vector3d angles; + + // roll (x-axis rotation) + double sinr_cosp = 2 * (q.w() * q.x() + q.y() * q.z()); + double cosr_cosp = 1 - 2 * (q.x ()* q.x() + q.y() * q.y()); + angles[0] = std::atan2(sinr_cosp, cosr_cosp); + + // pitch (y-axis rotation) + double sinp = std::sqrt(1 + 2 * (q.w ()* q.y ()- q.x() * q.z())); + double cosp = std::sqrt(1 - 2 * (q.w ()* q.y() - q.x() * q.z())); + angles[1] = 2 * std::atan2(sinp, cosp) - M_PI / 2; + + // yaw (z-axis rotation) + double siny_cosp = 2 * (q.w() * q.z() + q.x() * q.y()); + double cosy_cosp = 1 - 2 * (q.y() * q.y() + q.z() * q.z()); + angles[2] = std::atan2(siny_cosp, cosy_cosp); + + return angles; + } + + class ENVIRONMENT : public RaisimGymEnv { + + public: + + explicit ENVIRONMENT(const std::string& resourceDir, const Yaml::Node& cfg, bool visualizable) : + RaisimGymEnv(resourceDir, cfg), visualizable_(visualizable), normDist_(0, 1) { + /// create world + world_ = std::make_unique(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + READ_YAML(std::string, urdf_path, cfg_["urdf_path"]); + READ_YAML(double, p_gain, cfg_["p_gain"]); + READ_YAML(double, d_gain, cfg_["d_gain"]); + anymal_ = world_->addArticulatedSystem(urdf_path); + skate = world_ ->addArticulatedSystem("/home/lr-2002/code/raisimLib/rsc/skate/skate.urdf"); + anymal_->setName("model"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(0,"land"); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); // 19 + gvDim_ = anymal_->getDOF(); // 18 + nJoints_ = gvDim_ - 6; + skate_posi_init.setZero(9); + skate_vel_init.setZero(8); + skate_posi_init << 0, 0.15, 0.11, 0.707, 0., 0, 0.707, 0 , 0; + skate ->setGeneralizedCoordinate(skate_posi_init); + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + euler_angle.setZero();euler_angle_old.setZero(); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + acc_.setZero();//1 + ang_vel_.setZero(); + skate_vel_.setZero(8); + skate_posi_.setZero(9); +// init_position(); +double aa = 0.5233 , bb = double(60) /180*PI; + gc_init_<< 0, 0, 0.35, 1.0, 0.0, 0.0, 0.0, 0.0, aa, -2*aa, 0.0, bb, -2*bb, 0.0,aa,-2*aa, 0.0, bb, -2*bb; +// gc_init_<< 0, 0, 0.37, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; + init(); + + obDim_ = 29; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + + actionStd_.setConstant(action_std); + + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + for(auto n : anymal_->getCollisionBodies()) + { + auto name = n.colObj->name; + anymal_->getCollisionBody(name).setMaterial("steel"); + } + + skate->getCollisionBody("base/0").setMaterial("sandpaper"); + skate->getCollisionBody("rotater_r/0").setMaterial("rubber"); + skate->getCollisionBody("rotater_f/0").setMaterial("rubber"); + anymal_->getCollisionBody("FL_foot/0").setMaterial("rubber"); + anymal_->getCollisionBody("FR_foot/0").setMaterial("rubber"); + anymal_->getCollisionBody("RR_foot/0").setMaterial("rubber"); + anymal_->getCollisionBody("RL_foot/0").setMaterial("rubber"); + world_->setMaterialPairProp("steel", "rubber", 0.8, 0.15, 0.001); + world_->setMaterialPairProp("rubber", "sandpaper", 0.99, 0.15, 0.001); + world_->setMaterialPairProp("land", "rubber", 0.8, 0.1,0.001); + world_->setMaterialPairProp("sandpaper", "land", 0.4, 0.15,0.001); + world_->setMaterialPairProp("steel","land", 0.1, 0.05,0.001); + + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + + + void init() final { + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); + jointPgain.tail(nJoints_).setConstant(p_gain); + jointDgain.setZero(); + jointDgain.tail(nJoints_).setConstant(d_gain); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(urdf_path); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + } + + void init_position(const Eigen::Ref& posi) final + { + gc_init_ = posi.cast(); + init(); + } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + skate->setState(skate_posi_init, skate_vel_init); + rewards_.setZero(); + COUNT=0; +// euler_angle_old.setZero(); + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + if (show_ref) + { + Eigen::Vector3d po(3, 3 ,10); + anymal_1->setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + } + COUNT ++; + pTarget12_ = action.cast(); + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + updateObservation(); + double rrr =0; + rrr = abs(euler_angle[0]) + abs(euler_angle[1]) + abs(euler_angle[2]); + rrr += 0.1 * ( abs(ang_vel_[0]) + abs(ang_vel_[1]) +abs(ang_vel_[2])); + rrr += abs(gc_[0] - skate_posi_[0]) + abs(gc_[1] - (skate_posi_[1] - 0.15)); + bool accu = false; + rewards_.record("Stable",-rrr, accu); + rewards_.record("Live", 1, accu); + rewards_.record("forwardVel", skate_vel_[0], accu); + rewards_.record("height", 0.45- abs(gc_[2] - 0.45) - abs(gc_[0] ) - abs(gc_[1]) , accu); +// rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); +// rewards_.record("Wheel", euler_angle[2] * double(COUNT) / 400, accu); +// rewards_.record("Wheel", 0.5 - abs(ang_vel_[2]- 0.5), accu); + rewards_.record("torque",anymal_->getGeneralizedForce().squaredNorm() ); + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); + skate -> getState(skate_posi_, skate_vel_); + + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + quat /= quat.norm(); + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); + anymal_->getAngularVelocity(anymal_->getBodyIdx("base"), ang_vel_); + Eigen::Quaterniond qua(gc_[3], gc_[4], gc_[5], gc_[6]); + euler_angle = ToEulerAngles(qua); + Eigen::VectorXd gcc = gc_.tail(12); + Eigen::VectorXd gvv = gv_.tail(12); + Eigen::VectorXd c_v(24); + c_v.setZero(24); + for(auto i = 0; i <12 ; i++ ) + { + c_v[i*2] = gcc[i]; + c_v[i*2 + 1] = gvv[i]; + } + + obDouble_ << + euler_angle[0], + euler_angle[1],// quaternion + ang_vel_[0], + ang_vel_[1], + ang_vel_[2], + c_v; + + } + + void observe(Eigen::Ref ob) final { + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + bool accu = true; +// for(auto& contact: anymal_->getContacts()) +// if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) +// {// if there is any contact body was not in the footIndices the over +// rewards_.record("Live", terminalReward, accu); +// std::cout<<"foot done " << std::endl; +// return true;} + if(gc_[2] - gc_init_[2] > 0.3){ +// std::cout<<"z done" << std::endl; +// rewards_.record("Live", terminalReward, accu); + return true; + } + + if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.3) + { +// std::cout<<"y angle done" <<" " << euler_angle[1]<< std::endl; +// rewards_.record("Live", terminalReward, accu); + + return true; + } + if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.3) + { +// std::cout<<"x angle done " << euler_angle[0] << std::endl; +// rewards_.record("Live", terminalReward, accu); +// + return true; + } + if(abs(gc_[0] - skate_posi_[0]) >0.2) + { + return true; + } + if(abs(gc_[1] - (skate_posi_[1] - 0.15)) >0.1) + { + return true; + } + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1, *skate; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Vec<3> acc_, ang_vel_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + double p_gain,d_gain; + std::string urdf_path; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + Eigen::Vector3d euler_angle, euler_angle_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + Eigen::VectorXd skate_vel_, skate_posi_,skate_posi_init, skate_vel_init; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp new file mode 100644 index 000000000..d12ddf40a --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp @@ -0,0 +1,374 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#include +#define PI 3.1415926 + +namespace raisim { + + auto ToEulerAngles(Eigen::Quaterniond q) { + Eigen::Vector3d angles; + + // roll (x-axis rotation) + double sinr_cosp = 2 * (q.w() * q.x() + q.y() * q.z()); + double cosr_cosp = 1 - 2 * (q.x ()* q.x() + q.y() * q.y()); + angles[0] = std::atan2(sinr_cosp, cosr_cosp); + + // pitch (y-axis rotation) + double sinp = std::sqrt(1 + 2 * (q.w ()* q.y ()- q.x() * q.z())); + double cosp = std::sqrt(1 - 2 * (q.w ()* q.y() - q.x() * q.z())); + angles[1] = 2 * std::atan2(sinp, cosp) - M_PI / 2; + + // yaw (z-axis rotation) + double siny_cosp = 2 * (q.w() * q.z() + q.x() * q.y()); + double cosy_cosp = 1 - 2 * (q.y() * q.y() + q.z() * q.z()); + angles[2] = std::atan2(siny_cosp, cosy_cosp); + + return angles; + } + + class ENVIRONMENT : public RaisimGymEnv { + + public: + + explicit ENVIRONMENT(const std::string& resourceDir, const Yaml::Node& cfg, bool visualizable) : + RaisimGymEnv(resourceDir, cfg), visualizable_(visualizable), normDist_(0, 1) { + /// create world + world_ = std::make_unique(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + READ_YAML(std::string, urdf_path, cfg_["urdf_path"]); + READ_YAML(double, p_gain, cfg_["p_gain"]); + READ_YAML(double, d_gain, cfg_["d_gain"]); + anymal_ = world_->addArticulatedSystem(urdf_path); +// skate = world_ ->addArticulatedSystem("/home/lr-2002/code/raisimLib/rsc/skate/skate.urdf"); + anymal_->setName("model"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(0,"land"); +//world_->addGround(); + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); // 19 + gvDim_ = anymal_->getDOF(); // 18 + nJoints_ = gvDim_ - 6; +// skate_posi_init.setZero(9); +// skate_vel_init.setZero(8); +// skate_posi_init << 0, 0.15, 0.11, 0.707, 0., 0, 0.707, 0 , 0; +// skate ->setGeneralizedCoordinate(skate_posi_init); + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + euler_angle.setZero();euler_angle_old.setZero(); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + acc_.setZero();//1 + ang_vel_.setZero(); +// skate_vel_.setZero(8); +// skate_posi_.setZero(9); +// init_position(); +double aa = double(49)/ 180 * PI , bb = double(49) /180*PI; + double for_r = double(0) / 180 * PI ; + double abss = double(8) / 180 * PI; + gc_init_<< 0, 0, 0.31, 1.0, 0.0, 0.0, 0.0, 0.0, aa, -2*aa + 2 *abss, 0.0, bb, -2*bb+ 2 *abss, 0.0,aa +for_r ,-2*aa -2 * for_r+ 2 *abss , 0.0, bb + for_r, -2*bb -2 * for_r+ 2 *abss; +// gc_init_<< 0, 0, 0.37, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; + init(); + + obDim_ = 29; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + + actionStd_.setConstant(action_std); + + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + +// for(auto n : anymal_->getCollisionBodies()) +// { +// auto name = n.colObj->name; +// anymal_->getCollisionBody(name).setMaterial("steel"); +// } + +// skate->getCollisionBody("base/0").setMaterial("sandpaper"); +// skate->getCollisionBody("rotater_r/0").setMaterial("rubber"); +// skate->getCollisionBody("rotater_f/0").setMaterial("rubber"); + anymal_->getCollisionBody("FL_foot/0").setMaterial("rubber"); + anymal_->getCollisionBody("FR_foot/0").setMaterial("rubber"); + anymal_->getCollisionBody("RR_foot/0").setMaterial("rubber"); + anymal_->getCollisionBody("RL_foot/0").setMaterial("rubber"); +// world_->setMaterialPairProp("steel", "rubber", 0.8, 0.15, 0.001); +// world_->setMaterialPairProp("rubber", "sandpaper", 0.99, 0.15, 0.001); + world_->setMaterialPairProp("land", "rubber", 0.8, 0.1,0.001); +// world_->setMaterialPairProp("sandpaper", "land", 0.4, 0.15,0.001); +// world_->setMaterialPairProp("steel","land", 0.1, 0.05,0.001); + + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + + + void init() final { + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); + jointPgain.tail(nJoints_).setConstant(p_gain); + jointDgain.setZero(); + jointDgain.tail(nJoints_).setConstant(d_gain); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(urdf_path); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + } + + void init_position(const Eigen::Ref& posi) final + { + gc_init_ = posi.cast(); + init(); + } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); +// skate->setState(skate_posi_init, skate_vel_init); + rewards_.setZero(); + COUNT=0; + limit_flag = false; +// euler_angle_old.setZero(); + updateObservation(); + } + + float step(const Eigen::Ref& action) final { +// std::cout<<"mt 19937 " << gen_() << std::endl; + std::uniform_int_distribution rnddd(1, 100); + rnd_cnt = rnddd(gen_); + if (show_ref) + { + Eigen::Vector3d po(3, 3 ,10); + anymal_1->setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + } + + COUNT ++; + pTarget12_ = action.cast(); + + for (auto i = 0;i <12; i++) + { + if(abs( p_gain * (pTarget12_[i] - gc_[7 + i ]) + d_gain * (gv_[7+i])) > 50) + { + limit_flag = false; + } + } + ori = pTarget12_[0]; + pTarget12_ = pTarget12_.tail(nJoints_); + + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + /// apply random force +// raisim::Vec<3> force_ = {gen_() % 10, }; +if (rnd_cnt <=2){ + std::uniform_real_distribution force_dist(-30,30); +// std::uniform_int_distribution idx_dist(0, 13); + raisim::Vec<3> force_ = {force_dist(gen_), force_dist(gen_), force_dist(gen_)}; +// std::cout << " force gened " << force_ << std::endl; +// int iddx = + anymal_->setExternalForce(0, force_); +// anymal_->printOutMovableJointNamesInOrder(); +} + + + updateObservation(); + double rrr =0; + rrr = abs(euler_angle[0]) + abs(euler_angle[1]) +abs(euler_angle[2]); + rrr = rrr * 0.1; + rrr += 0.1 * ( abs(ang_vel_[0]) + abs(ang_vel_[1]) +abs(ang_vel_[2])); +// rrr += abs(gc_[0] - skate_posi_[0]) + abs(gc_[1] - (skate_posi_[1] - 0.15)); + bool accu = false; +// std::cout << "body: " << bodyLinearVel_ << "\n get_vel " << line_vel_ << std:: endl ; + rewards_.record("Stable",-rrr, accu); + rewards_.record("Live", 1, accu); +// std::cout << "minus is " << bodyLinearVel_[0] << " " << line_vel_[0] << std::endl; +// rewards_.record("forwardVel",bodyLinearVel_[0], accu); + rewards_.record("forwardVel",line_vel_[0], accu); +// rewards_.record("height", 0.45- abs(gc_[2] - 0.45) - abs(gc_[0] ) - abs(gc_[1]) , accu); +// rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); +// rewards_.record("Wheel", euler_angle[2] * double(COUNT) / 400, accu); + rewards_.record("Wheel", ang_vel_[2], accu); +// rewards_.record("torque",anymal_->getGeneralizedForce().squaredNorm() ); + return rewards_.sum(); + } + + void updateObservation() { +// raisim::Vec<3> acc_w; + +// std::cout<< "acc? " <getFrameAcceleration("base",acc_w); + anymal_->getState(gc_, gv_); +// skate -> getState(skate_posi_, skate_vel_); + + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + quat /= quat.norm(); + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); + anymal_->getAngularVelocity(anymal_->getBodyIdx("base"), ang_vel_); + anymal_->getFrameVelocity(anymal_->getBodyIdx("base"), line_vel_); + Eigen::Quaterniond qua(gc_[3], gc_[4], gc_[5], gc_[6]); + euler_angle = ToEulerAngles(qua); + Eigen::VectorXd gcc = gc_.tail(12); + Eigen::VectorXd gvv = gv_.tail(12); + Eigen::VectorXd c_v(24); + c_v.setZero(24); + for(auto i = 0; i <12 ; i++ ) + { + c_v[i*2] = gcc[i]; + c_v[i*2 + 1] = gvv[i]; + } + + obDouble_ << + euler_angle[0], + euler_angle[1],// quaternion +// ori, + ang_vel_[0], + ang_vel_[1], + ang_vel_[2], +// line_vel_[0], +// line_vel_[1], + c_v; +// gcc; + + } + + void observe(Eigen::Ref ob) final { + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + bool accu = true; + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over + rewards_.record("Live", terminalReward, accu); +// std::cout<<"foot done " << std::endl; + return true;} + +// if(gc_[2] - gc_init_[2] > 0.3){ +//// std::cout<<"z done" << std::endl; +// rewards_.record("Live", terminalReward, accu); +// return true; +// } + + if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.17) + { +// std::cout<<"y angle done" <<" " << euler_angle[1]<< std::endl; + rewards_.record("Live", terminalReward, accu); + + return true; + } + if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.4) + { +// std::cout<<"x angle done " << euler_angle[0] << std::endl; + rewards_.record("Live", terminalReward, accu); + + return true; + } + if(limit_flag) + { +// std::cout<<"limit done" << std::endl; + rewards_.record("Live", terminalReward, accu); + return true; + } +// if(abs(gc_[0] - skate_posi_[0]) >0.2) +// { +// return true; +// } +// if(abs(gc_[1] - (skate_posi_[1] - 0.15)) >0.1) +// { +// return true; +// } + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -60.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Vec<3> acc_, ang_vel_, line_vel_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + double p_gain,d_gain; + std::string urdf_path; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double ori = 1.0; + double limit_flag = false; + double action_std, angle_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + Eigen::Vector3d euler_angle, euler_angle_old; + + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; +// Eigen::VectorXd skate_vel_, skate_posi_,skate_posi_init, skate_vel_init; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; + int rnd_cnt = 0; +// static std::uniform_real_distribution dist_(-10,10); +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml new file mode 100644 index 000000000..f9c1fa1fa --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -0,0 +1,46 @@ +seed: 1 +record_video: true + +environment: + render: true +# just testing commenting + num_envs: 20 + eval_every_n: 20 + num_threads: 20 + simulation_dt: 0.0025 + control_dt: 0.01 + max_time: 8 + action_std: 0.5 +# action_std: 0 + show_ref: false + angle_rate: 0.21 + schedule: 40 +# for_work: 1 + float_base: false + learnning_rate: 5e-4 + p_gain: 100 + d_gain: 3 + urdf_path: /home/lr-2002/code/raisimLib/rsc/a1_description/urdf/a1.urdf + reward: + forwardVel: + coeff: 1 + torque: + coeff: -4e-5 + Stable: + coeff: 15 + height: + coeff: 0. + Live: + coeff: 1 + Wheel: + coeff: 0 + Mimic: + coeff: 0. + +architecture: + policy_net: [128, 128] + value_net: [128, 128] + +on_policy: + rate: 1. # for sine A + kb: 0.15 # act_gen * kb diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/fake_a1.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/fake_a1.py new file mode 100644 index 000000000..cc35b8a8f --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/fake_a1.py @@ -0,0 +1,34 @@ +import numpy as np +class Robot: + def __init__(self): + self.ob_dims = 29 + self.act_dims = 12 + self.position = [0, 0.5233, -1.0466] * 4 + + + + def observe(self): + return np.array( + [[0. , 0. , 0. , 0. , 0. , 0., + 0. , 0.5233 , 0., - 1.0466 , 0. , 0., + 0. , 0.5235988, 0., - 1.0471976 , 0. , 0., + 0. , 0.5233 , 0., - 1.0466 , 0. , 0., + 0. , 0.5235988, 0., - 1.0471976 , 0.]] + ).astype(np.float32) + + def ob_dim(self): + return self.ob_dims + + def act_dim(self): + return self.act_dims + + def take_action(self,action): + pass + + def init_motor(self,act): + pass + +def init_position(a,b): + pass + +a1 = Robot() \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py new file mode 100755 index 000000000..5a100ee49 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py @@ -0,0 +1,241 @@ +import concurrent.futures +import threading + +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger +from raisimGymTorch.env.bin.rsg import NormalSampler +from raisimGymTorch.env.bin.rsg import RaisimGymEnv +from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO +from raisimGymTorch.deploy_utils.angle_utils import get_last_position +from raisimGymTorch.deploy_utils.runner_util import run_model_with_pt_input_modify, list_pt, step_reset +import os +import math +import time +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse +import faulthandler +faulthandler.enable() +from unitree_utils.Waiter import Waiter +from raisimGymTorch.deploy_log.draw_map import Drawer +from raisimGymTorch.deploy_log.csv_saver import CSV_saver + +# task specification +task_name = "rsg_test" + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=300) +parser.add_argument('-p', '--cfg_path', help='where to find the path', type=str, default=None) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +mode = args.mode +weight_path = args.weight +cfg_path = args.cfg_path +# load_best = args.load_best +# check if gpu is available +# device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') +device = torch.device('cpu') +print(device) +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +if cfg_path is not None: + cfg = YAML().load(open(cfg_path, 'r')) +else: + cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) +print(cfg['environment']) + +# create environment from the configuration file +env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts +num_threads = cfg['environment']['num_threads'] +max_time = cfg['environment']['max_time'] + +# Training +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * env.num_envs + +avg_rewards = [] +print(env.num_envs) +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + env.num_envs, + 1, + NormalSampler(act_dim), + cfg['seed']), + device) +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + +saver = ConfigurationSaver(log_dir=home_path + "/raisimGymTorch/data/"+task_name, + save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) +logger = RaisimLogger(saver.data_dir+"/train.log") + +def updating(): + obs = env.observe(False) + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 2 == 0, update=update) + average_ll_performance = reward_sum / total_steps + + + if update % cfg['environment']['eval_every_n'] == 0: + biggest_iter = update + biggest_reward = average_ll_performance + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir + "/full_" + str(update) + '.pt') + env.save_scaling(saver.data_dir, str(update)) + save_act.save() + save_observe.save() + avg_rewards.append(average_ll_performance) + + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + print('----------------------------------------------------\n') +last_c = [0] * 4 +def cal_reward(qq, now): + """ + + :param qq: 1 / -1 + :param now: 12 + :param last: 12 + :return: reward + """ + global last_c + c = [0] * 4 + c[0] = now[3 * 0 + 1] + now[3 * 0 + 2]/2 + c[1] = now[3 * 1 + 1] + now[3 * 1 + 2]/2 + c[2] = now[3 * 2 + 1] + now[3 * 2 + 2]/2 + c[3] = now[3 * 3 + 1] + now[3 * 3 + 2]/2 + d = [0] * 4 + d[0] = c[0] - last_c[0] + d[1] = c[1] - last_c[1] + d[2] = c[2] - last_c[2] + d[3] = c[3] - last_c[3] + last_c = c + return np.array([-qq * (d[0] + d[3] - d[1] - d[2])]) + +if mode =='train' or mode == 'retrain': + tensorboard_launcher(saver.data_dir+"/..") # press refresh (F5) after the first ppo update +num_envs = cfg['environment']['num_envs'] +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps *5, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=16, + device=device, + log_dir=saver.data_dir, + shuffle_batch=False, + ) + +reward_analyzer = RewardAnalyzer(env, ppo.writer) +biggest_reward = 0 +biggest_iter = 0 +if mode == 'retrain': + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + +save_observe = CSV_saver('./observation_saver') +save_act = CSV_saver('./act_saver') +print = logger.info + + +on_p_rate =cfg['on_policy']['rate'] +on_p_kb = cfg['on_policy']['kb'] +mode == 'train' +his_util = [0] * 12 +history_act = np.array([his_util] * num_envs) +total_update = args.update +if mode =='train' or mode == 'retrain': + env.turn_on_visualization() + schedule = cfg['environment']['schedule'] + envs_idx = 0 + waiter = Waiter(0.01) + waiter.update_start() + for update in range(total_update): + reward_sum = 0 + q = 0 + for step in range(n_steps): + qq = 1 if (envs_idx // schedule) % 2 == 0 else -1 + # print(f"{envs_idx} {qq}") + # if step>=200: + # time.sleep(5) + waiter.wait() + obs = env.observe(False) + position = get_last_position(obs) + # print(position) + action = ppo.act(obs) + # action = np.zeros_like(action) + action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act, kb=on_p_kb, rate=on_p_rate) + reward, _ = env.step(action) + # print(len(last_c)) + # print(len(position)) + + # position = position[0] + # if envs_idx == 0 : + # last_c[0] = position[3 * 0 + 1] + position[3 * 0 + 2] / 2 + # last_c[1] = position[3 * 1 + 1] + position[3 * 1 + 2] / 2 + # last_c[2] = position[3 * 2 + 1] + position[3 * 2 + 2] / 2 + # last_c[3] = position[3 * 3 + 1] + position[3 * 3 + 2] / 2 + # reward = np.array([0]) + # else: + # reward = cal_reward(qq, position) + # print(f"reward {reward} ") + envs_idx +=1 + ppo.step(value_obs=obs, rews=reward, dones=_) + + save_observe.add_list(obs[0]) + save_act.add_list(action[0]) + + reward_sum = reward_sum + np.sum(reward) + reward_analyzer.add_reward_info(env.get_reward_info()) + reward_analyzer.analyze_and_plot(update) + # take st step to get value obs + update_thread = threading.Thread(target=updating) + update_thread.start() + + # cnt = 0 + for i in range(4 * schedule): + # print('running optimize position ') + waiter.wait() + acc, history_act =step_reset(action, envs_idx, schedule, history_act, kb=on_p_kb, rate=on_p_rate) + env.step(acc) + envs_idx +=1 + for i in range(2 * schedule): + # print('running optimize position ') + waiter.wait() + # acc, history_act =run_model_with_pt_input_modify(action, cnt, schedule, history_act, kb=on_p_kb, rate=on_p_rate) + env.step(acc) + # envs_idx +=1 + while update_thread.is_alive(): + waiter.wait() + # print('threading running') + env.step(acc) + history_act=np.array([his_util] * num_envs) + print('updating finished') + env.turn_off_visualization() +print(f'biggest:{biggest_reward},rate = {biggest_iter}') + + diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/real_on_policy_train.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/real_on_policy_train.py new file mode 100755 index 000000000..62f1595c7 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/real_on_policy_train.py @@ -0,0 +1,396 @@ +import concurrent.futures +import threading + +import asn1crypto.cms +import asn1crypto.core +from raisimGymTorch.env.bin.rsg import NormalSampler +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.env.bin.rsg import RaisimGymEnv +from raisimGymTorch.deploy_utils.angle_utils import get_last_position +from raisimGymTorch.deploy_utils.runner_util import run_model_with_pt_input_modify, list_pt, u0_rad, step_reset +import os +import math +import faulthandler +faulthandler.enable() +import time +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse +import signal +from raisimGymTorch.deploy_log.draw_map import Drawer +from raisimGymTorch.deploy_log.csv_saver import CSV_saver +# task specification +# from fake_a1 import * +from robot_utils import * + +task_name = "real_time_train_test" + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=300) +parser.add_argument('-p', '--cfg_path', help='where to find the path', type=str, default=None) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +mode = args.mode +weight_path = args.weight +cfg_path = args.cfg_path +# load_best = args.load_best +# check if gpu is available +# device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') +device = torch.device('cpu') +print(device) +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +if cfg_path is not None: + cfg = YAML().load(open(cfg_path, 'r')) +else: + cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# shortcuts + + +env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +ob_dim = a1.ob_dim() +act_dim = a1.act_dim() + +# Training +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * 1 + +avg_rewards = [] +num_envs=1 +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + +saver = ConfigurationSaver(log_dir=home_path + "/raisimGymTorch/data/"+task_name, + save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) +logger = RaisimLogger(saver.data_dir+"/train.log") + + + +def real_handler(signal, frame): + print('You pressed Ctrl+C!') + a1.quit_robot() + # debug_draw_gry.draw() + draw_reward.draw() + save_reward.save() + save_act.save() + save_observe.save() + sys.exit(0) + +signal.signal(signal.SIGINT, real_handler) + +init_e_x = 0 +init_e_y = 0 + + +def load_pretrain(weight_path): + checkpoint = torch.load(weight_path) + actor.architecture.load_state_dict(checkpoint['actor_architecture_state_dict']) + actor.distribution.load_state_dict(checkpoint['actor_distribution_state_dict']) + critic.architecture.load_state_dict(checkpoint['critic_architecture_state_dict']) + ppo.optimizer.load_state_dict(checkpoint['optimizer_state_dict']) +# init_v_x = 0 +# # init_v_y = 0 +# def cal_reward(robot): +# """ +# +# :param robot: a1 +# :return: reward number +# """ +# global init_e_x +# global init_e_y +# # global init_v_x +# # global init_v_y +# obs = robot.observe()[0] +# reward = 0 +# # reward -= (abs(obs[0] - init_e_x )+ abs(obs[1] - init_e_y)) +# # reward -= (abs(obs[2]) + abs(obs[3])) * 0.1 +# # reward = reward * 0.4#stable +# # reward += 1 +# # reward = reward + (0.5 - abs(obs[4] + 0.5)) * 2 # wheel +# # reward = reward + obs[4]# wheel +# # print(f'vel {a1.est_vel[0]} ang: {a1.gyroscope[2]}') +# # reward = reward+a1.est_vel[0] - 0.00* abs(a1.gyroscope[2]) # the velo of x is hard to get nevagate so we use this one to minus +# reward = -1 * ( abs(a1.gyroscope[2])) # the velo of x is hard to get nevagate so we use this one to minus +# print(f"est vel {a1.est_vel} vel reward {max(0,a1.est_vel[0]) , -0.00 * abs(a1.gyroscope[2])} ") +# return np.array([reward]) + + + +last_c = [0] * 4 +def cal_reward(qq, now): + """ + + :param qq: 1 / -1 + :param now: 12 + :param last: 12 + :return: reward + """ + global last_c + c = [0] * 4 + c[0] = now[3 * 0 + 1] + now[3 * 0 + 2]/2 + c[1] = now[3 * 1 + 1] + now[3 * 1 + 2]/2 + c[2] = now[3 * 2 + 1] + now[3 * 2 + 2]/2 + c[3] = now[3 * 3 + 1] + now[3 * 3 + 2]/2 + d = [0] * 4 + d[0] = c[0] - last_c[0] + d[1] = c[1] - last_c[1] + d[2] = c[2] - last_c[2] + d[3] = c[3] - last_c[3] + last_c = c + print(last_c) + return np.array([-qq * 10 * (d[0] + d[3] - d[1] - d[2])]) + # a1.observe() + # reward = a1.gyroscope[2] + # return np.array([reward]).astype(np.float32) + +def updating(obs, update): + print('thread updating ') + # obs = a1.observe() + # print(obs.shape) + # print(obs) + # input('go on ?') + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 2 == 0, update=update) + average_ll_performance = reward_sum / total_steps + + + if update % cfg['environment']['eval_every_n'] == 0: + biggest_iter = update + biggest_reward = average_ll_performance + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir + "/full_" + str(update) + '.pt') + + + # draw_reward.draw() + + avg_rewards.append(average_ll_performance) + draw_reward.add_map_list([average_ll_performance]) + save_reward.add_list([average_ll_performance]) + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + print('----------------------------------------------------\n') + + + +num_envs = cfg['environment']['num_envs'] +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps * 5, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=16, + device=device, + log_dir=saver.data_dir, + ) + + +if mode =="retrain": + print(f'you are going to use the model of {weight_path} ') + # load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + load_pretrain(weight_path) + # load_param(weight_path.) + + + +biggest_reward = 0 +biggest_iter = 0 + +save_observe = CSV_saver('./observation_saver') +save_act = CSV_saver('./act_saver') +save_reward = CSV_saver('./reward_saver') +draw_reward = Drawer('./draw_reward') +print = logger.info + + + +on_p_rate =cfg['on_policy']['rate'] +on_p_kb = cfg['on_policy']['kb'] +mode == 'retrain' +his_util = [0] * 12 +history_act = np.array([his_util] * num_envs) +total_update = args.update + +obs = a1.observe() +a1.torque_limit =35 +ppo.act(obs) +act = a1.position +a1.kp=[100] * 12 +# a1.kd = [1,2,2] * 4 +a1.kd = [4] * 12 +envs_idx = 0 +schedule = cfg['environment']['schedule'] + +action, _ = step_reset(np.zeros((1,12)), 0, schedule, history_act, kb=on_p_kb, + rate=on_p_rate) + +a1.stand_up(300,action[0].tolist()) + +# a1.init_motor(act) +# init_position(action[0].tolist(), 250) +# a1.observe() +# print(f'actural position {a1.position}') +# for i in range(500): +# if i >30 and i <=40: +# obs = a1.observe() +# init_e_x += obs[0][0] +# init_e_y += obs[0][1] +# if i==40: +# init_e_y /= 10 +# init_e_x /= 10 +# a1.hold_on() +# # print(a1.position) +# # obs = a1.observe() + +# print(f'actual zero angle : {init_e_x, init_e_y}') + +# obb = obs.copy() +# ppo_act = threading.Thread(target=ppo.act(obs)) +# ppo_act.start() +# while ppo_act.is_alive(): +# a1.hold_on() +# print('holding') +# print('finished hold /on ') +envs_idx = 0 +# for i in range(4 * schedule): +# # print('running optimize position ') +# acc, history_act = step_reset(np.zeros_like(action), envs_idx, schedule, history_act, kb=on_p_kb, +# rate=on_p_rate) +# act = acc[0] +# cnt += 1 +# a1.take_action(act.tolist()) +# a1.reset_esti() +# print(f"est vel {a1.est_vel} vel reward {max(0, a1.est_vel[0]), -0.00 * abs(a1.gyroscope[2])} ") + +history_act = np.array([his_util] * num_envs) + + +print('fini?') + +for update in range(total_update): + reward_sum = 0 + if update==0: + a1.hold_on() + # print('1') + x_posi = 0 + y_posi = 0 + # if holding.is_alive(): + # time.sleep(0.005) + print('finished holding') + a1.reset_esti() + envs_idx=0 + for step in range(n_steps): + # waiter.wait() + + qq = 1 if (envs_idx // schedule) % 2 == 0 else -1 + + obs = a1.observe() + # print('before cal') + action = ppo.act(obs) + # print('after cal') + + # action = np.zeros_like(action) + + # action=np.clip(action-1, -1, 1) + # print(4) + action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act, kb=on_p_kb, rate=on_p_rate) + # action, history_act = step_reset(action, envs_idx, schedule, history_act, kb=on_p_kb, rate=on_p_rate) + action=action[0] + if step==0 and update ==0: + print(f"pre take action the first time ") + # print('take action ') + if step == 0: + a1.go_position(action.tolist(), 30) + + a1.take_action(action.tolist()) + # reward = cal_reward(a1) + # x_posi +=a1.est_vel[0] * a1.dt + # y_posi +=a1.est_vel[1] * a1.dt + envs_idx +=1 + + position = a1.position + if envs_idx == 0: + last_c[0] = position[3 * 0 + 1] + position[3 * 0 + 2] / 2 + last_c[1] = position[3 * 1 + 1] + position[3 * 1 + 2] / 2 + last_c[2] = position[3 * 2 + 1] + position[3 * 2 + 2] / 2 + last_c[3] = position[3 * 3 + 1] + position[3 * 3 + 2] / 2 + reward = np.array([0]) + else: + reward = cal_reward(qq, position) + # reward=cal_reward(qq, position) + ppo.step(value_obs=obs, rews=reward, dones=np.array([False])) + + save_observe.add_list(obs[0]) + save_act.add_list(action[0]) + + reward_sum = reward_sum + np.sum(reward) + + # take st step to get value obs + obs = a1.observe() + update_thread = threading.Thread(target=updating,args=(obs,update)) + update_thread.start() + # print(f'a1 has move {x_posi}' ) + # print(f'a1 yyyy has move {y_posi}' ) + # print(f'def posi is {np.sqrt(x_posi**2 + y_posi**2)}') + for i in range(4 * schedule): + # print('running optimize position ') + acc, history_act = step_reset(np.zeros_like(action), envs_idx, schedule, history_act, kb=on_p_kb, + rate=on_p_rate) + act = acc[0] + if i == 0 : + print(f'going to {act.tolist()}') + a1.go_position(act.tolist(), 100) + envs_idx +=1 + print(act.tolist()) + a1.take_action(act.tolist()) + # a1.reset_esti() + # print(f"est vel {a1.est_vel} vel reward {max(0,a1.est_vel[0]) , -0.00 * abs(a1.gyroscope[2])} ") + + # for i in range(2 * schedule): + # a1.take_action(act.tolist()) + # cnt += 1 + print(f'stop posi {act}') + update_thread.join() + while update_thread.is_alive(): + # print('threading running') + a1.take_action(act.tolist()) + # print(f"est vel {a1.est_vel} vel reward {max(0,a1.est_vel[0]) , -0.00 * abs(a1.gyroscope[2])} ") + + history_act = np.array([his_util] * num_envs) + # print('reset vel') + a1.reset_esti() + print('updating finished') +print(f'biggest:{biggest_reward},rate = {biggest_iter}') +signal_handler(0,0) + + diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py new file mode 100644 index 000000000..4ce308a58 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py @@ -0,0 +1,40 @@ +from unitree_api import robot as rbt +from unitree_deploy.angle_utils import sine_generator +# from raisimGymTorch.deploy_log.draw_map import draw +import signal +import sys +a1 = rbt.Robot() + +# todo test this after sleep +def init_position(position, timing = 100): + a1.go_position(position, timing) + a1.observe() + +def quit_robot(robot): + robot.back_safe() + print('Task finished') + # draw() + sys.exit(0) + +def signal_handler(signal, frame): + print('You pressed Ctrl+C!') + quit_robot(a1) + +signal.signal(signal.SIGINT, signal_handler) +def init_robot(dt): + a1.dt = dt + print(a1.observe()) + + act = a1.position + # print(act) + a1.init_motor(act) + + +if __name__=='__main__': + init_robot(0.01) + print(a1.observe()) + init_position(position=sine_generator(0, 40, 0.14).tolist()) + # + while True: + # print(a1.observe()) + a1.hold_on() diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py new file mode 100755 index 000000000..7bf30d8d9 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -0,0 +1,229 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger +from raisimGymTorch.env.bin.rsg import NormalSampler +from raisimGymTorch.env.bin.rsg import RaisimGymEnv +from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO +from raisimGymTorch.deploy_utils.angle_utils import get_last_position +from raisimGymTorch.deploy_utils.runner_util import run_model_with_pt_input_modify, list_pt +import os +import math +import time +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse + +from unitree_utils.Waiter import Waiter +from raisimGymTorch.deploy_log.draw_map import Drawer + + + +# task specification +task_name = "rsg_test" + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=300) +parser.add_argument('-p', '--cfg_path', help='where to find the path', type=str, default=None) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +mode = args.mode +weight_path = args.weight +cfg_path = args.cfg_path +# load_best = args.load_best +# check if gpu is available +device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') +# device = torch.device('cpu') +print(device) +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +if cfg_path is not None: + cfg = YAML().load(open(cfg_path, 'r')) +else: + cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) +print(cfg['environment']) + +# create environment from the configuration file +env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts +num_threads = cfg['environment']['num_threads'] + +# Training +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * env.num_envs + +avg_rewards = [] + +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + env.num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + +saver = ConfigurationSaver(log_dir=home_path + "/raisimGymTorch/data/"+task_name, + save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) +logger = RaisimLogger(saver.data_dir+"/train.log") + +if mode =='train' or mode == 'retrain': + tensorboard_launcher(saver.data_dir+"/..") # press refresh (F5) after the first ppo update +num_envs = cfg['environment']['num_envs'] +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps * 5, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=16, + # learning_rate_schedule='', + device=device, + log_dir=saver.data_dir, + shuffle_batch=False, + # learning_rate=cfg['environment']['learnning_rate'] + ) + +reward_analyzer = RewardAnalyzer(env, ppo.writer) +biggest_reward = 0 +biggest_iter = 0 +if mode == 'retrain': + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + +# his_util=[0, 0.523, -1.046] * 4 +his_util=[0] * 12 +check_done = lambda a, b: a + 1 if not b else 0 +check_history = lambda a, b: a if not b else his_util + + +print = logger.info +on_p_rate =cfg['on_policy']['rate'] +on_p_kb = cfg['on_policy']['kb'] +env_idx = np.zeros(num_envs) +mode == 'train' +history_act = np.array([his_util] * num_envs) +history_act_0 = np.array([his_util] * num_envs) +total_update = args.update +if mode =='train' or mode == 'retrain': + schedule = cfg['environment']['schedule'] + for update in range(total_update): + start = time.time() + env.reset() + reward_sum = 0 + envs_idx = env_idx + history_act=history_act_0 + done_sum = 0 + average_dones = 0. + + if update % cfg['environment']['eval_every_n'] == 0: + # draw_his = Drawer('history') + waiter = Waiter(0.01) + print("Visualizing and evaluating the current policy") + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + + env.turn_on_visualization() + env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') + envs_idx = env_idx + waiter.update_start() + for step in range(n_steps): + with torch.no_grad(): + waiter.wait() + frame_start = time.time() + + + obs = env.observe(False) + action = ppo.act(obs) + action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act, kb=on_p_kb, rate=on_p_rate) + reward, dones = env.step(action) + + + history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) + envs_idx = np.where(dones ==1, 0, envs_idx+1) + reward_analyzer.add_reward_info(env.get_reward_info()) + frame_end = time.time() + wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) + + env.stop_video_recording() + env.turn_off_visualization() + # history_act = np.array([his_util] * num_envs) + reward_analyzer.analyze_and_plot(update) + env.reset() + env.save_scaling(saver.data_dir, str(update)) + envs_idx = env_idx + history_act=history_act_0 + for step in range(n_steps): + obs = env.observe(False) + action = ppo.act(obs) + action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act, kb=on_p_kb, rate=on_p_rate) + reward, dones = env.step(action) + history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) + envs_idx = np.where(dones == 1, 0, envs_idx + 1) + ppo.step(value_obs=obs, rews=reward, dones=dones) + + + + done_sum = done_sum + np.sum(dones) + reward_sum = reward_sum + np.sum(reward) + reward_analyzer.add_reward_info(env.get_reward_info()) + reward_analyzer.analyze_and_plot(update) + # take st step to get value obs + obs = env.observe(False) + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 2 == 0, update=update) + average_ll_performance = reward_sum / total_steps + + + if average_ll_performance > biggest_reward: + biggest_iter = update + biggest_reward = average_ll_performance + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + env.save_scaling(saver.data_dir, str(update)) + average_dones = done_sum / total_steps + avg_rewards.append(average_ll_performance) + + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) + + # curriculum update. Implement it in Environment.hpp + env.curriculum_callback() + + end = time.time() + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + print('{:<40} {:>6}'.format("dones: ", '{:0.6f}'.format(average_dones))) + print('{:<40} {:>6}'.format("time elapsed in this iteration: ", '{:6.4f}'.format(end - start))) + print('{:<40} {:>6}'.format("fps: ", '{:6.0f}'.format(total_steps / (end - start)))) + print('{:<40} {:>6}'.format("real time factor: ", '{:6.0f}'.format(total_steps / (end - start) + * cfg['environment']['control_dt']))) + print('----------------------------------------------------\n') + + +print(f'biggest:{biggest_reward},rate = {biggest_iter}') + + diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py new file mode 100644 index 000000000..09b4b621d --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -0,0 +1,313 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger +from raisimGymTorch.env.bin.rsg import NormalSampler +from raisimGymTorch.env.bin.rsg import RaisimGymEnv +from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO +from raisimGymTorch.deploy_utils.angle_utils import transfer +from unitree_utils.Waiter import Waiter +from raisimGymTorch.deploy_utils.angle_utils import get_last_position +from raisimGymTorch.deploy_log.draw_map import Drawer +from raisimGymTorch.deploy_log.csv_saver import CSV_saver +import os +import math +import time +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse +# import pandas as pd +# from sine_generator import sine_generator +from unitree_deploy.angle_utils import sine_generator +from raisimGymTorch.deploy_utils.angle_utils import deg_rad, rad_deg +from raisimGymTorch.deploy_utils.runner_util import run_model_with_pt_input_modify, list_pt + + +# task specification +task_name = "sim2real" + + + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=120) +parser.add_argument('-p', '--cfg_path', help='where to find the path', type=str, default=None) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +mode = args.mode +weight_path = args.weight +cfg_path = args.cfg_path +device = torch.device('cpu') + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +if cfg_path is not None: + cfg = YAML().load(open(cfg_path, 'r')) +else: + cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) +print(cfg['environment']) + +# create environment from the configuration file +env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +dt = cfg['environment']['control_dt'] +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts +num_threads = cfg['environment']['num_threads'] + +# Training +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * env.num_envs + +avg_rewards = [] + +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + env.num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + +saver = ConfigurationSaver(log_dir=home_path + "/raisimGymTorch/data/"+task_name, + save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) +logger = RaisimLogger(saver.data_dir+"/train.log") + +num_envs = cfg['environment']['num_envs'] +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=4, + device=device, + log_dir=saver.data_dir, + shuffle_batch=False, + learning_rate=cfg['environment']['learnning_rate'] + ) + +reward_analyzer = RewardAnalyzer(env, ppo.writer) +biggest_reward = 0 +biggest_iter = 0 +if mode == 'retrain': + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + +check_done = lambda a, b: a + 1 if not b else 0 + +print = logger.info + + +total_update = args.update + +schedule = cfg['environment']['schedule'] +angle_rate = cfg['environment']['angle_rate'] +act_rate = cfg['environment']['action_std'] # how many action generated use for work +act_rate = float(act_rate) + +# act_rate = 0 + +input(f"Are you sure to execute the action in schedule: {schedule}, angle_rate: {angle_rate}, act_rate(how many action generated from NN used for work): {act_rate}") + + +moving_robot = False +onnx_flag = False +virtual = True +on_p_rate =cfg['on_policy']['rate'] +on_p_kb = cfg['on_policy']['kb'] +# his_util=[0, 0.523, -1.046] * 4 +his_util =[0] * 12 +# his_util=[0, 0.523, -1.046] * 4 +# check_done = lambda a, b: a + 1 if not b else 0 +check_history = lambda a, b: a if not b else his_util +history_act = np.array([his_util] * num_envs) +# init virtual part +if virtual: + waiter= Waiter(0.01) + env.reset() + start = time.time() + onnx_flag = False + if onnx_flag: + cnt_onnx = 0 + from raisimGymTorch.deploy_utils import onnx_deploy + else: + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + + envs_idx = [0] * num_envs + + +# NOTE : a1 init + + +if moving_robot: + history_obs = None + + if onnx_flag: + cnt_onnx = 0 + + from raisimGymTorch.deploy_utils import onnx_deploy + else: + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + + from robot_utils import * + a1.torque_limit = 50 + # init_robot(dt) + + # ori_posi = sine_generator(0, schedule, rate=angle_rate).tolist() # initial position + # a1.kp = cfg['environment']['kp'] + # ori_posi = a1.position + # init_position(ori_posi,250) + gen_action = ppo.act(a1.observe()) + a1.kp = [100] * 12 + a1.kd = [3] * 12 + # a1.init_k(a1.kp, a1.kd) + ori_posi,_ = run_model_with_pt_input_modify(np.zeros_like(gen_action), 0, schedule, history_act, kb=on_p_kb, + rate=on_p_rate) + a1.stand_up(200, ori_posi[0].tolist()) + print(f""" + now_posi: {a1.position}, + angle_rate : {angle_rate} + schedule: {schedule} + """) + real_idx = 0 + for i in range(schedule): + a1.hold_on() + + # history_obs = a1.observe()[ :5] +history_act = np.array([his_util] * num_envs) +for step in range(n_steps * 10): + #virtual bot part + if virtual: + # if step%1 ==0 : + # input() + if step == 0: + draw_vir_obs = Drawer('vir_obs') + draw_vir_action = Drawer('vir_sent_act') + draw_vir_recv_action = Drawer('vir_recv_act') + waiter.update_start() + # save_gen_act = CSV_saver('virtual_gen_act', './') + save_obs = CSV_saver('virtual_obs', './') + save_for_work = CSV_saver('virtual_sent', './') + save_recv = CSV_saver('virtual_recv', './') + obs = env.observe(False) + print('saving') + last_p = get_last_position(obs) + print(f'last{last_p}') + save_recv.add_list(last_p[0]) + draw_vir_recv_action.add_map_list(last_p[0]) + if onnx_flag: + # obs = rad_deg(obs) + # print(obs.shape) + action, obs = onnx_deploy.run_model(obs, cnt_onnx, 40) + action = np.array(action)[0] + cnt_onnx += 1 + else: + gen_action = ppo.act(obs) + action, history_act = run_model_with_pt_input_modify(gen_action, envs_idx, schedule, history_act, kb=on_p_kb, + rate=on_p_rate) + # sine = sine_generator(envs_idx, schedule, angle_rate) + # action = transfer(gen_action, sine, act_rate, history_act=history_act).astype(np.float32) + # history_act = + print(f"virtual_obs:{obs} \n virtual_action:{action}") + save_obs.add_list(obs[0]) + # draw_vir_recv_action.add_map_list(action[0]) + save_for_work.add_list(action[0]) + + + + + # real bot part + if moving_robot: + + if step ==0: + draw_real_obs = Drawer('real_obs') + draw_sent_action = Drawer('real_sent_act') + draw_recv_action = Drawer('real_a_recv_act') + real_history_act = np.array(his_util) + save_real_obs = CSV_saver('real_a_obs') + save_real_action = CSV_saver('real_a_action') + # print('b-observe') + # obbs = a1.observe() + # obbs[:5] -= history_obs + real_obs = a1.observe() + # real_obs = np.array([a1.observe()]) + # print(f"real_obs {real_obs}") + # input('now cancel it ') + # print() + # print('b-ppo') + + + if onnx_flag: + action, real_obs = onnx_deploy.run_model(real_obs, cnt_onnx, 40) + real_obs = real_obs[0] + real_action = np.array(action)[0] + cnt_onnx += 1 + + else: + gen_action = ppo.act(real_obs) + # print('b-sin') + # real_sine = sine_generator(real_idx, schedule, angle_rate) + # print('b-trans') + # real_action = transfer(gen_action, real_sine, act_rate, history_act=real_history_act) + # gen_action = ppo.act(obs) + action, history_act = run_model_with_pt_input_modify(gen_action, real_idx, schedule, history_act, kb=on_p_kb, + rate=on_p_rate) + + # real_action = real_action + # add_map_list(real_action) + draw_real_obs.add_map_list(real_obs[:5]) + save_real_obs.add_list(real_obs) + save_real_action.add_list(a1.position) + draw_recv_action.add_map_list(a1.position) + draw_sent_action.add_map_list(action[0]) + print(f"real_obs:{real_obs} \n for work_action:{action} ") + # waiter.wait() + if action.shape[0] == 1: + action = action[0] + a1.take_action(action.tolist()) + # real_history_act = real_sine + real_idx +=1 + + + # update virtual bot + if virtual: + waiter.wait() + reward, dones = env.step(action) + envs_idx = list(map(check_done, envs_idx, dones)) + + draw_vir_obs.add_map_list(obs[0][:5]) + draw_vir_action.add_map_list(action[0]) + history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) +# draw() +if virtual: + save_obs.save() + save_for_work.save() + draw_vir_obs.draw() + draw_vir_action.draw() + draw_vir_recv_action.draw() + save_recv.save() + # save_gen_act.save() +else: + a1.back_safe() + save_real_obs.save() + save_real_action.save() + draw_real_obs.draw() + draw_sent_action.draw() + draw_recv_action.draw() + +print(f'biggest:{biggest_reward},rate = {biggest_iter}') + + diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/tester.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/tester.py new file mode 100755 index 000000000..f54879d50 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/tester.py @@ -0,0 +1,77 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.bin import rsg +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +import raisimGymTorch.algo.ppo.module as ppo_module +import os +import math +import time +import torch +import argparse + + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-w', '--weight', help='trained weight path', type=str, default='') +args = parser.parse_args() + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# create environment from the configuration file +cfg['environment']['num_envs'] = 1 + +env = rsg.RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper)), cfg['environment'] +env.init_position([0] * 12) +print(env) +# # shortcuts +# ob_dim = env.num_obs +# act_dim = env.num_acts +# +# weight_path = args.weight +# iteration_number = weight_path.rsplit('/', 1)[1].split('_', 1)[1].rsplit('.', 1)[0] +# weight_dir = weight_path.rsplit('/', 1)[0] + '/' +# +# if weight_path == "": +# print("Can't find trained weight, please provide a trained weight with --weight switch\n") +# else: +# print("Loaded weight from {}\n".format(weight_path)) +# start = time.time() +# env.reset() +# reward_ll_sum = 0 +# done_sum = 0 +# average_dones = 0. +# n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +# total_steps = n_steps * 1 +# start_step_id = 0 +# +# print("Visualizing and evaluating the policy: ", weight_path) +# loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], torch.nn.LeakyReLU, ob_dim, act_dim) +# loaded_graph.load_state_dict(torch.load(weight_path)['actor_architecture_state_dict']) +# +# env.load_scaling(weight_dir, int(iteration_number)) +# env.turn_on_visualization() +# +# # max_steps = 1000000 +# max_steps = 1000 ## 10 secs +# +# for step in range(max_steps): +# time.sleep(0.01) +# obs = env.observe(False) +# action_ll = loaded_graph.architecture(torch.from_numpy(obs).cpu()) +# reward_ll, dones = env.step(action_ll.cpu().detach().numpy()) +# reward_ll_sum = reward_ll_sum + reward_ll[0] +# if dones or step == max_steps - 1: +# print('----------------------------------------------------') +# print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(reward_ll_sum / (step + 1 - start_step_id)))) +# print('{:<40} {:>6}'.format("time elapsed [sec]: ", '{:6.4f}'.format((step + 1 - start_step_id) * 0.01))) +# print('----------------------------------------------------\n') +# start_step_id = step + 1 +# reward_ll_sum = 0.0 +# +# env.turn_off_visualization() +# env.reset() +# print("Finished at the maximum visualization steps") diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal/Environment.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal/Environment.hpp index a4cbee3c1..ce3444171 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal/Environment.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal/Environment.hpp @@ -100,7 +100,7 @@ class ENVIRONMENT : public RaisimGymEnv { updateObservation(); rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); - rewards_.record("forwardVel", std::min(4.0, bodyLinearVel_[0])); + rewards_.record("forwardVel", -bodyLinearVel_[0]); return rewards_.sum(); } diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/Environment.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/Environment.hpp new file mode 100644 index 000000000..37e8cf921 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/Environment.hpp @@ -0,0 +1,380 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#define PI 3.1415926 + +double cal(double low, double upp, double now){ + return (now + 1)/2 * (upp- low) + low; +} + +void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); +// std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } +// std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} + +void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +{ +// std::cout<< "size is "<< angle_list.size() << std::endl; + double base1= 0.4, base2 = -0.8, base3=0.0; + double ang = abs(sin( float(idx) / T * PI)) * rate; + + int idx_base = 0; +// std::cout<(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + /// add objects + anymal_ = world_->addArticulatedSystem(resourceDir_+"/go1/go1.urdf"); + anymal_->setName("dog"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); + nJoints_ = gvDim_ - 6; + + /// initialize containers + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + /// this is nominal configuration of anymal +// gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// anymal_1->setGeneralizedCoordinate(gc_init_); + gc_init_ << 0, 0, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; + + /// set pd gains + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(200.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(4); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + + /// MUST BE DONE FOR ALL ENVIRONMENTS + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + +// READ_YAML(); + actionStd_.setConstant(action_std); + + join_limit = anymal_->getJointLimits(); + /// Reward coefficients + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + /// indices of links that should not make contact with ground + footIndices_.insert(anymal_->getBodyIdx("LF_SHANK")); + footIndices_.insert(anymal_->getBodyIdx("RF_SHANK")); + footIndices_.insert(anymal_->getBodyIdx("LH_SHANK")); + footIndices_.insert(anymal_->getBodyIdx("RH_SHANK")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + void init() final { } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + /// action scaling + COUNT ++; +// std::cout<setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = 0; quat[1] = 0; quat[2] = 0; quat[3] = 0; +// raisim::quatToRotMat(quat, rot); +// anymal_->setBaseOrientation(rot); +// raisim::Vec<4> quat(4); +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// anymal_->setBaseOrientation(quat); +// pTarget_.tail(nJoints_) = angle_list; +// anymal_->setPdTarget(pTarget_, vTarget_); + } + // angle_list *= 0.3; +// angle_list.setZero(); + Eigen::VectorXd idx1(8), idx2(4); + idx1.setZero();idx2.setZero(); + idx1<<1, 2, 4, 5, 7,8,10,11; + idx2<<0, 3, 6, 9; + + pTarget12_ = action.cast(); + Eigen::VectorXd ttmp =action.cast(); + map_from_origin_to_limit(join_limit, pTarget12_,ttmp); + // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); +// pTarget12_ += actionMean_; +// pTarget12_ = angle_list; + + + angle_mulit(pTarget12_, idx1, action_std); + angle_mulit(pTarget12_, idx2, action_std); + + + angle_list_for_work = angle_list * for_work_rate; + + + + + pTarget12_ = angle_list_for_work + pTarget12_; +// pTarget12_[11] = pTarget12_[10] *-2; +// pTarget12_[8] = pTarget12_[7] * -2; +// pTarget12_[1] = -pTarget12_[10]; +// pTarget12_[2] = -pTarget12_[11]; +// pTarget12_[4] = -pTarget12_[7]; +// pTarget12_[5] = -pTarget12_[8]; +// pTarget12_[9] = -0.03; +// pTarget12_[0] = -pTarget12_[9]; +// pTarget12_[6] = 0.03; +// pTarget12_[3] = -pTarget12_[6]; + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } + for(int i=0; i<=1; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } + rrr += abs(gc_[5] - gc_init_[5]) * 2 * stable_reward_rate; +// if(COUNT != 0) +// { +// rrr += (gc_ - gc_init_).norm() * reference_rate *0.1; +// } + + +// rrr +=(gc_init_.head(7) - gc_.head(7)).norm() * stable_reward_rate; + rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; +// rrr += abs(bodyLinearVel_[1]); +// rrr += abs(bodyLinearVel_[2]); +// rrr += abs(bodyLinearVel_[0]); + +// rrr += abs(gc_[2] - gc_init_[2]) ; + +// rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::mi); +rewards_.record("Stable", 1 - rrr, false); +rewards_.record("forwardVel", bodyLinearVel_[0], false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); + + obDouble_ << double(COUNT)/schedule_T, + rot.e().row(2).transpose(), /// body orientation + bodyLinearVel_, bodyAngularVel_, /// body linear&angular velocity + gc_.tail(12); /// joint angles + gv_.tail(12); /// joint velocity + } + + void observe(Eigen::Ref ob) final { + /// convert it to float + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + + /// if the contact body is not feet + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// std::cout<<"terminate "<0.3 ) + { + return true; + } +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) +// return true; + +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8 || ) +// return true; + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} + +//int main() +//{ +// raisim::ENVIRONMENT a("../rsc/","/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml", +// true); +//} \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml new file mode 100644 index 000000000..31b3a9919 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml @@ -0,0 +1,32 @@ +seed: 1 +record_video: False + +environment: + render: True +# just testing commenting + num_envs: 100 + eval_every_n: 40 + num_threads: 30 + simulation_dt: 0.0025 + control_dt: 0.01 + max_time: 4.0 + action_std: 0.0035 + show_ref: False + angle_rate: 0.4 + stable: 5 + reference : 0 + schedule: 40 + for_work: 1 + float_base: False + learnning_rate: 5e-4 + reward: + forwardVel: + coeff: 0.0 + torque: + coeff: -4e-5 + Stable: + coeff: 0.9 + +architecture: + policy_net: [128, 128] + value_net: [128, 128] diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/runner.py new file mode 100755 index 000000000..70f5637c0 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/runner.py @@ -0,0 +1,195 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger +from raisimGymTorch.env.bin.rsg_anymal_modified import NormalSampler +from raisimGymTorch.env.bin.rsg_anymal_modified import RaisimGymEnv +from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer +import os +import math +import time +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse + +# task specification +task_name = "anymal_locomotion" + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=120) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +mode = args.mode +weight_path = args.weight + +# load_best = args.load_best +# check if gpu is available +device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# create environment from the configuration file +env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts +num_threads = cfg['environment']['num_threads'] + +# Training +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * env.num_envs + +avg_rewards = [] + +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + env.num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + +saver = ConfigurationSaver(log_dir=home_path + "/raisimGymTorch/data/"+task_name, + save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) +logger = RaisimLogger(saver.data_dir+"/train.log") + +if mode =='train' or mode == 'retrain': + tensorboard_launcher(saver.data_dir+"/..") # press refresh (F5) after the first ppo update + +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=4, + device=device, + log_dir=saver.data_dir, + shuffle_batch=False, + learning_rate=cfg['environment']['learnning_rate'] + ) + +reward_analyzer = RewardAnalyzer(env, ppo.writer) +biggest_reward = 0 +biggest_iter = 0 +if mode == 'retrain': + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + +# if load_best == True: +# weight_path = "" +print = logger.info + +total_update = args.update +if mode =='train' or mode == 'retrain': + for update in range(total_update): + start = time.time() + env.reset() + reward_sum = 0 + done_sum = 0 + average_dones = 0. + + if update % cfg['environment']['eval_every_n'] == 0: + print("Visualizing and evaluating the current policy") + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + # we create another graph just to demonstrate the save/load method + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) + + env.turn_on_visualization() + env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') + + for step in range(n_steps): + with torch.no_grad(): + frame_start = time.time() + obs = env.observe(False) + # action = ppo.act(torch.from_numpy(obs).cpu()) + action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + # print(action.min()) + reward, dones = env.step(action.cpu().detach().numpy()) + reward_analyzer.add_reward_info(env.get_reward_info()) + frame_end = time.time() + wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) + if wait_time > 0.: + time.sleep(wait_time) + + env.stop_video_recording() + env.turn_off_visualization() + + reward_analyzer.analyze_and_plot(update) + env.reset() + env.save_scaling(saver.data_dir, str(update)) + + # actual training + for step in range(n_steps): + obs = env.observe() + action = ppo.act(obs) + reward, dones = env.step(action) + ppo.step(value_obs=obs, rews=reward, dones=dones) + done_sum = done_sum + np.sum(dones) + reward_sum = reward_sum + np.sum(reward) + # take st step to get value obs + obs = env.observe() + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 10 == 0, update=update) + average_ll_performance = reward_sum / total_steps + if average_ll_performance > biggest_reward: + biggest_iter = update + biggest_reward = average_ll_performance + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + env.save_scaling(saver.data_dir, str(update)) + average_dones = done_sum / total_steps + avg_rewards.append(average_ll_performance) + + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) + + # curriculum update. Implement it in Environment.hpp + env.curriculum_callback() + + end = time.time() + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + print('{:<40} {:>6}'.format("dones: ", '{:0.6f}'.format(average_dones))) + print('{:<40} {:>6}'.format("time elapsed in this iteration: ", '{:6.4f}'.format(end - start))) + print('{:<40} {:>6}'.format("fps: ", '{:6.0f}'.format(total_steps / (end - start)))) + print('{:<40} {:>6}'.format("real time factor: ", '{:6.0f}'.format(total_steps / (end - start) + * cfg['environment']['control_dt']))) + print('----------------------------------------------------\n') +else: + env.reset() + start = time.time() + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + for step in range(n_steps * 10): + time.sleep(0.01) + obs = env.observe() + action = ppo.act(obs) + reward, dones = env.step(action) + +print(f'biggest:{biggest_reward},rate = {biggest_iter}') \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/tester.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/tester.py new file mode 100755 index 000000000..bdea58d30 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/tester.py @@ -0,0 +1,76 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.bin import rsg_anymal +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +import raisimGymTorch.algo.ppo.module as ppo_module +import os +import math +import time +import torch +import argparse + + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-w', '--weight', help='trained weight path', type=str, default='') +args = parser.parse_args() + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# create environment from the configuration file +cfg['environment']['num_envs'] = 1 + +env = VecEnv(rsg_anymal.RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper)), cfg['environment']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts + +weight_path = args.weight +iteration_number = weight_path.rsplit('/', 1)[1].split('_', 1)[1].rsplit('.', 1)[0] +weight_dir = weight_path.rsplit('/', 1)[0] + '/' + +if weight_path == "": + print("Can't find trained weight, please provide a trained weight with --weight switch\n") +else: + print("Loaded weight from {}\n".format(weight_path)) + start = time.time() + env.reset() + reward_ll_sum = 0 + done_sum = 0 + average_dones = 0. + n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) + total_steps = n_steps * 1 + start_step_id = 0 + + print("Visualizing and evaluating the policy: ", weight_path) + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], torch.nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(weight_path)['actor_architecture_state_dict']) + + env.load_scaling(weight_dir, int(iteration_number)) + env.turn_on_visualization() + + # max_steps = 1000000 + max_steps = 1000 ## 10 secs + + for step in range(max_steps): + time.sleep(0.01) + obs = env.observe(False) + action_ll = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + reward_ll, dones = env.step(action_ll.cpu().detach().numpy()) + reward_ll_sum = reward_ll_sum + reward_ll[0] + if dones or step == max_steps - 1: + print('----------------------------------------------------') + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(reward_ll_sum / (step + 1 - start_step_id)))) + print('{:<40} {:>6}'.format("time elapsed [sec]: ", '{:6.4f}'.format((step + 1 - start_step_id) * 0.01))) + print('----------------------------------------------------\n') + start_step_id = step + 1 + reward_ll_sum = 0.0 + + env.turn_off_visualization() + env.reset() + print("Finished at the maximum visualization steps") diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment.hpp new file mode 100644 index 000000000..1667903c1 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment.hpp @@ -0,0 +1,524 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#define PI 3.1415926 + +double cal(double low, double upp, double now){ + return (now + 1)/2 * (upp- low) + low; +} +void swap(Eigen::VectorXd &ob, int a, int b) +{ + double tmp = ob[a]; + ob[a] = ob[b]; + ob[b] = tmp; +} + +double rad_deg(double rad) +{ + return rad / PI * 180; +} + +void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); +// std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } +// std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} + +//void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +//{ +//// std::cout<< "size is "<< angle_list.size() << std::endl; +// double base1= 0.82, base3=0.0; +// double base2 = -2 * base1; +// double ang = abs(sin( float(idx) / T * PI)) * rate; +// +// int idx_base = 0; +//// std::cout<(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + /// add objects + anymal_ = world_->addArticulatedSystem(resourceDir_+"/a1_description/urdf/a1.urdf"); + anymal_->setName("dog"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); + nJoints_ = gvDim_ - 6; + + /// initialize containers + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + /// this is nominal configuration of anymal +// gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// anymal_1->setGeneralizedCoordinate(gc_init_); +// gc_init_<< 0, 0, 0.41, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; + +// gc_init_ << 0, 0, 0.36, 1.0, 0.0, 0, 0, 0, -0.4, 0.8529411764705883, 0.0, -0.4, 0.8529411764705883, 0.0, -0.4, 0.8529411764705883, 0.0, -0.4, 0.8529411764705883; // todo implement in python using list + +// gc_init_ << 0, 0, 0.36, 1.0, 0.0, 0, 0, 0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883; // todo implement in python using list +// gc_init_<< 0, 0, 0.41, 1.0, 0.0, -0.4, 0.8529411764705883, 0.0, -0.4, 0.8529411764705883, 0.0, -0.4, 0.8529411764705883, 0.0, -0.4, 0.8529411764705883; // todo implement in python using list + + gc_init_<< 0, 0, 0.36, 1.0, 0.0, 0, 0, 0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976 ; // todo implement in python using list +// jointNominalConfig.tail(12).setZero(); +// Eigen::VectorXd tmp(12); +// tmp.setZero(); +// angle_generator(tmp, 0, 80.f); +// gc_init_.tail(12) = tmp; + + /// set pd gains + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(2000.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(100); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + + /// MUST BE DONE FOR ALL ENVIRONMENTS + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + +// READ_YAML(); + actionStd_.setConstant(action_std); + + join_limit = anymal_->getJointLimits(); + /// Reward coefficients + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + /// indices of links that should not make contact with ground + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + void init() final { } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + /// action scaling +// COUNT ++; +// std::cout<setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = 0; quat[1] = 0; quat[2] = 0; quat[3] = 0; +// raisim::quatToRotMat(quat, rot); +// anymal_->setBaseOrientation(rot); +// raisim::Vec<4> quat(4); +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// anymal_->setBaseOrientation(quat); +// pTarget_.tail(nJoints_) = angle_list; +// anymal_->setPdTarget(pTarget_, vTarget_); + } + // angle_list *= 0.3; +// angle_list.setZero(); +// Eigen::VectorXd idx1(8), idx2(4); +// idx1.setZero();idx2.setZero(); +// idx1<<1, 2, 4, 5, 7,8,10,11; +// idx2<<0, 3, 6, 9; + + pTarget12_ = action.cast(); +// Eigen::VectorXd ttmp =action.cast(); +// map_from_origin_to_limit(join_limit, pTarget12_,ttmp); + // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); +// pTarget12_ += actionMean_; +// pTarget12_ = angle_list; + + +// angle_mulit(pTarget12_, idx1, action_std); +// angle_mulit(pTarget12_, idx2, action_std); +// +// +// angle_list_for_work = angle_list * for_work_rate; + + + + +// pTarget12_ = angle_list_for_work + pTarget12_; + + + +// pTarget12_[11] = pTarget12_[10] *-2; +// pTarget12_[8] = pTarget12_[7] * -2; +// pTarget12_[1] = -pTarget12_[10]; +// pTarget12_[2] = -pTarget12_[11]; +// pTarget12_[4] = -pTarget12_[7]; +// pTarget12_[5] = -pTarget12_[8]; +// pTarget12_[9] = -0.03; +// pTarget12_[0] = -pTarget12_[9]; +// pTarget12_[6] = 0.03; +// pTarget12_[3] = -pTarget12_[6]; + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } +// rrr *= float(COUNT )/ schedule_T); +// for(int i=0; i<=1; i++) +// { +// rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; +// } +// rrr += abs(gc_[5] - gc_init_[5]) * 2 * stable_reward_rate; +// if(COUNT != 0) +// { +// rrr += (gc_ - gc_init_).norm() * reference_rate *0.1; +// } + + +// rrr +=(gc_init_.head(7) - gc_.head(7)).norm() * stable_reward_rate; + rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; +// rrr += abs(bodyLinearVel_[1]); +// rrr += abs(bodyLinearVel_[2]); +// rrr += abs(bodyLinearVel_[0]); + +// rrr += abs(gc_[2] - gc_init_[2]) ; + +// rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::mi); + rewards_.record("Stable", 1 - rrr, false); + rewards_.record("forwardVel", bodyLinearVel_[0], false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); +// std::cout< quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// std::cout<< rot.e().row(2).transpose().size() << " " < left_q(vec_quat); +// left_q[3] = sqr2 * (quat[0] - quat[1]); // -w +// left_q[0] = -sqr2 * (quat[0] + quat[1]); // x +// left_q[1] = -sqr2 * (quat[2] - quat[3]); // z +// left_q[2] = sqr2 * (quat[2] + quat[3]); // y +// raisim::Mat<3,3> left_rot; +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// raisim::quatToRotMat(new_quat, left_rot); + Eigen::Matrix3d left_rot(new_quat); + bodyLinearVel_ = -left_rot.transpose() * gv_.segment(0, 3); // minus was added to test todo + bodyAngularVel_ = -left_rot.transpose() * gv_.segment(3, 3); +// bodyAngularVel_[0] = -bodyAngularVel_[0]; +// double tt = bodyAngularVel_[1]; +// bodyAngularVel_[1] = -bodyAngularVel_[2]; +// bodyAngularVel_[2] = -tt; + + +// std::cout<< "left " << left_q << "right" << quat << std::endl; + + Eigen::VectorXd tmp1(12), tmp2(12); + tmp1 = gc_.tail(12); + tmp2 = gv_.tail(12); + for(auto i=0;i<=2;i++) bodyAngularVel_[i] = rad_deg(bodyAngularVel_[i]); // to be deg + +// for(auto i=0;i<=11;i++) tmp1[i] = rad_deg(tmp1[i]); // to be deg +// for(auto i=0;i<=11;i++) tmp2[i] = rad_deg(tmp2[i]); // to be deg + obDouble_ << new_quat.x(), + new_quat.y(), + new_quat.z(), + new_quat.w(), +// rot.e().row(2).transpose(), /// body orientation + bodyAngularVel_, + bodyLinearVel_; /// body linear&angular velocity +// tmp1, /// joint angles +// tmp2; /// joint velocity + + for(auto i=0; i<12; i++){ +// std::cout<<2*i + 10 << " " << tmp1[i] << " " << tmp2[i] < ob) final { + /// convert it to float + ob = obDouble_.cast(); +// std::cout<<"observe in c++\n" << ob <getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// std::cout<<"terminate "<0.3 ) +// { +// return true; +// } +// if(abs(gc_[4]-gc_init_[4]) >0.2 ) +// { +// return true; +// } +// if(abs(gc_[6]-gc_init_[6]) >0.2 ) +// { +// return true; +// } +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) +// return true; + +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8 || ) +// return true; + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} + +//int main() +//{ +// raisim::ENVIRONMENT a("../rsc/","/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml", +// true); +//} \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment_ylq.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment_ylq.hpp new file mode 100644 index 000000000..5661bbaa0 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment_ylq.hpp @@ -0,0 +1,426 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#define PI 3.1415926 + +double cal(double low, double upp, double now){ + return (now + 1)/2 * (upp- low) + low; +} + +void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); +// std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } +// std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} + +//void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +//{ +//// std::cout<< "size is "<< angle_list.size() << std::endl; +// double base1= 0.82, base3=0.0; +// double base2 = -2 * base1; +// double ang = abs(sin( float(idx) / T * PI)) * rate; +// +// int idx_base = 0; +//// std::cout<(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + /// add objects + anymal_ = world_->addArticulatedSystem(resourceDir_+"/a1/urdf/a1.urdf"); + anymal_->setName("dog"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); + nJoints_ = gvDim_ - 6; + + /// initialize containers + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + /// this is nominal configuration of anymal +// gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// anymal_1->setGeneralizedCoordinate(gc_init_); + gc_init_<< 0, 0, 0.30, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; + +// jointNominalConfig.tail(12).setZero(); + Eigen::VectorXd tmp(12); + tmp.setZero(); + angle_generator(tmp, 0, 80.f); + gc_init_.tail(12) = tmp; + + /// set pd gains + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(120.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(3); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + + /// MUST BE DONE FOR ALL ENVIRONMENTS + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + +// READ_YAML(); + actionStd_.setConstant(action_std); + + join_limit = anymal_->getJointLimits(); + /// Reward coefficients + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + /// indices of links that should not make contact with ground + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + void init() final { } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + /// action scaling + COUNT ++; +// std::cout<setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = 0; quat[1] = 0; quat[2] = 0; quat[3] = 0; +// raisim::quatToRotMat(quat, rot); +// anymal_->setBaseOrientation(rot); +// raisim::Vec<4> quat(4); +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// anymal_->setBaseOrientation(quat); +// pTarget_.tail(nJoints_) = angle_list; +// anymal_->setPdTarget(pTarget_, vTarget_); + } + // angle_list *= 0.3; +// angle_list.setZero(); + Eigen::VectorXd idx1(8), idx2(4); + idx1.setZero();idx2.setZero(); + idx1<<1, 2, 4, 5, 7,8,10,11; + idx2<<0, 3, 6, 9; + + pTarget12_ = action.cast(); + Eigen::VectorXd ttmp =action.cast(); + map_from_origin_to_limit(join_limit, pTarget12_,ttmp); + // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); +// pTarget12_ += actionMean_; +// pTarget12_ = angle_list; + + + angle_mulit(pTarget12_, idx1, action_std); + angle_mulit(pTarget12_, idx2, action_std); + + + angle_list_for_work = angle_list * for_work_rate; + + + + + pTarget12_ = angle_list_for_work + pTarget12_; +// pTarget12_[11] = pTarget12_[10] *-2; +// pTarget12_[8] = pTarget12_[7] * -2; +// pTarget12_[1] = -pTarget12_[10]; +// pTarget12_[2] = -pTarget12_[11]; +// pTarget12_[4] = -pTarget12_[7]; +// pTarget12_[5] = -pTarget12_[8]; +// pTarget12_[9] = -0.03; +// pTarget12_[0] = -pTarget12_[9]; +// pTarget12_[6] = 0.03; +// pTarget12_[3] = -pTarget12_[6]; + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } +// rrr *= float(COUNT )/ schedule_T); +// for(int i=0; i<=1; i++) +// { +// rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; +// } +// rrr += abs(gc_[5] - gc_init_[5]) * 2 * stable_reward_rate; +// if(COUNT != 0) +// { +// rrr += (gc_ - gc_init_).norm() * reference_rate *0.1; +// } + + +// rrr +=(gc_init_.head(7) - gc_.head(7)).norm() * stable_reward_rate; + rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; +// rrr += abs(bodyLinearVel_[1]); +// rrr += abs(bodyLinearVel_[2]); +// rrr += abs(bodyLinearVel_[0]); + +// rrr += abs(gc_[2] - gc_init_[2]) ; + +// rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::mi); + rewards_.record("Stable", 1 - rrr, false); + rewards_.record("forwardVel", bodyLinearVel_[0], false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// std::cout<< rot.e().row(2).transpose().size() << " " < ob) final { + /// convert it to float + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + +// / if the contact body is not feet + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// std::cout<<"terminate "<0.3 ) +// { +// return true; +// } +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) +// return true; + +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8 || ) +// return true; + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml new file mode 100644 index 000000000..15ee76666 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml @@ -0,0 +1,32 @@ +seed: 1 +record_video: false + +environment: + render: true +# just testing commenting + num_envs: 1 + eval_every_n: 100 + num_threads: 1 + simulation_dt: 0.0025 + control_dt: 0.01 + max_time: 8.0 + action_std: 0.01 + show_ref: false + angle_rate: 0.3 + stable: 1 + reference: 0 + schedule: 50 + for_work: 1 + float_base: False + learnning_rate: 5e-4 + reward: + forwardVel: + coeff: 3 + torque: + coeff: -4e-5 + Stable: + coeff: 0.9 + +architecture: + policy_net: [128, 128] + value_net: [128, 128] diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py new file mode 100755 index 000000000..bb92a989a --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py @@ -0,0 +1,258 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger +from raisimGymTorch.env.bin.rsg_go1 import NormalSampler +from raisimGymTorch.env.bin.rsg_go1 import RaisimGymEnv +from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO + + +import os +import math +import time +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse + + + +# task specification +task_name = "go1_locomotion" + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=120) +parser.add_argument('-p', '--cfg_path', help='where to find the path', type=str, default=None) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +mode = args.mode +weight_path = args.weight +cfg_path = args.cfg_path +# load_best = args.load_best +# check if gpu is available +device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +if cfg_path is not None: + cfg = YAML().load(open(cfg_path, 'r')) +else: + cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# create environment from the configuration file +env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts +num_threads = cfg['environment']['num_threads'] + +# Training +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * env.num_envs + +avg_rewards = [] + +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + env.num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + +saver = ConfigurationSaver(log_dir=home_path + "/raisimGymTorch/data/"+task_name, + save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) +logger = RaisimLogger(saver.data_dir+"/train.log") + +if mode =='train' or mode == 'retrain': + tensorboard_launcher(saver.data_dir+"/..") # press refresh (F5) after the first ppo update + +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=4, + device=device, + log_dir=saver.data_dir, + shuffle_batch=False, + learning_rate=cfg['environment']['learnning_rate'] + ) + +reward_analyzer = RewardAnalyzer(env, ppo.writer) +biggest_reward = 0 +biggest_iter = 0 +if mode == 'retrain': + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + +# if load_best == True: +# weight_path = "" +print = logger.info + +mode == 'test' + +total_update = args.update +if mode =='train' or mode == 'retrain': + for update in range(total_update): + start = time.time() + env.reset() + reward_sum = 0 + done_sum = 0 + average_dones = 0. + + if update % cfg['environment']['eval_every_n'] == 0: + print("Visualizing and evaluating the current policy") + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + # we create another graph just to demonstrate the save/load method + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) + + env.turn_on_visualization() + env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') + + for step in range(n_steps): + with torch.no_grad(): + frame_start = time.time() + obs = env.observe(False) + + # action = ppo.act(torch.from_numpy(obs).cpu()) + action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + # print(action.min()) + reward, dones = env.step(action.cpu().detach().numpy()) + reward_analyzer.add_reward_info(env.get_reward_info()) + frame_end = time.time() + wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) + if wait_time > 0.: + time.sleep(wait_time) + + env.stop_video_recording() + env.turn_off_visualization() + + reward_analyzer.analyze_and_plot(update) + env.reset() + env.save_scaling(saver.data_dir, str(update)) + + # actual training + for step in range(n_steps): + obs = env.observe() + action = ppo.act(obs) + reward, dones = env.step(action) + ppo.step(value_obs=obs, rews=reward, dones=dones) + done_sum = done_sum + np.sum(dones) + reward_sum = reward_sum + np.sum(reward) + # take st step to get value obs + obs = env.observe() + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 10 == 0, update=update) + average_ll_performance = reward_sum / total_steps + if average_ll_performance > biggest_reward: + biggest_iter = update + biggest_reward = average_ll_performance + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + env.save_scaling(saver.data_dir, str(update)) + average_dones = done_sum / total_steps + avg_rewards.append(average_ll_performance) + + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) + + # curriculum update. Implement it in Environment.hpp + env.curriculum_callback() + + end = time.time() + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + print('{:<40} {:>6}'.format("dones: ", '{:0.6f}'.format(average_dones))) + print('{:<40} {:>6}'.format("time elapsed in this iteration: ", '{:6.4f}'.format(end - start))) + print('{:<40} {:>6}'.format("fps: ", '{:6.0f}'.format(total_steps / (end - start)))) + print('{:<40} {:>6}'.format("real time factor: ", '{:6.0f}'.format(total_steps / (end - start) + * cfg['environment']['control_dt']))) + print('----------------------------------------------------\n') +else: + env.reset() + start = time.time() + onnx_flag = True + debug = True + if onnx_flag: + cnt_onnx = 0 + from raisimGymTorch.env.deploy_util import onnx_deploy + T = 50 + np.set_printoptions(threshold=np.inf) + draw_line =[] + # load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + for step in range(n_steps * 10): + time.sleep(0.01) + obs = env.observe(False) + + if debug: + angle = obs[0][[0,1,2,4,5,6]] + angle[0] *= 100 + angle[1] *= 100 + angle[2] *= 100 + draw_line.append(angle.copy()) + + if cnt_onnx == 100: + import matplotlib.pyplot as plt + # print(obs) + colo = ['r','g','b','y','magenta','cyan'] + # colo = ['r','g','b','y'] + # print(angle) + ttt = np.array(draw_line).transpose() + leen = ttt.shape[1] + ze = [0 for x in range(leen)] + xx = [x for x in range(leen)] + t = 0 + for i in ttt: + plt.plot(xx, i, color=colo[t]) + t += 1 + plt.plot(xx, ze) + print(ttt) + plt.show() + input('wait') + + # input('?') + # print(obs.shape) + if onnx_flag: + if cnt_onnx >= 2 * T: + cnt_onnx =0 + action = onnx_deploy.run_model(obs, cnt_onnx, T) + action = np.array(action)[0] + cnt_onnx += 1 + # action = np.array([act for x in range(100)]) + else: + action = ppo.act(obs) + # if cnt_onnx == 1: + # print(action) + reward, dones = env.step(action) + if dones[0]: + cnt_onnx = 0 + + +print(f'biggest:{biggest_reward},rate = {biggest_iter}') + + diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/tester.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/tester.py new file mode 100755 index 000000000..bdea58d30 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/tester.py @@ -0,0 +1,76 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.bin import rsg_anymal +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +import raisimGymTorch.algo.ppo.module as ppo_module +import os +import math +import time +import torch +import argparse + + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-w', '--weight', help='trained weight path', type=str, default='') +args = parser.parse_args() + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# create environment from the configuration file +cfg['environment']['num_envs'] = 1 + +env = VecEnv(rsg_anymal.RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper)), cfg['environment']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts + +weight_path = args.weight +iteration_number = weight_path.rsplit('/', 1)[1].split('_', 1)[1].rsplit('.', 1)[0] +weight_dir = weight_path.rsplit('/', 1)[0] + '/' + +if weight_path == "": + print("Can't find trained weight, please provide a trained weight with --weight switch\n") +else: + print("Loaded weight from {}\n".format(weight_path)) + start = time.time() + env.reset() + reward_ll_sum = 0 + done_sum = 0 + average_dones = 0. + n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) + total_steps = n_steps * 1 + start_step_id = 0 + + print("Visualizing and evaluating the policy: ", weight_path) + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], torch.nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(weight_path)['actor_architecture_state_dict']) + + env.load_scaling(weight_dir, int(iteration_number)) + env.turn_on_visualization() + + # max_steps = 1000000 + max_steps = 1000 ## 10 secs + + for step in range(max_steps): + time.sleep(0.01) + obs = env.observe(False) + action_ll = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + reward_ll, dones = env.step(action_ll.cpu().detach().numpy()) + reward_ll_sum = reward_ll_sum + reward_ll[0] + if dones or step == max_steps - 1: + print('----------------------------------------------------') + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(reward_ll_sum / (step + 1 - start_step_id)))) + print('{:<40} {:>6}'.format("time elapsed [sec]: ", '{:6.4f}'.format((step + 1 - start_step_id) * 0.01))) + print('----------------------------------------------------\n') + start_step_id = step + 1 + reward_ll_sum = 0.0 + + env.turn_off_visualization() + env.reset() + print("Finished at the maximum visualization steps") diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/Environment.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/Environment.hpp new file mode 100644 index 000000000..1ed569acb --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/Environment.hpp @@ -0,0 +1,159 @@ +#pragma once +#include +#include +#include +#include "../../RaisimGymEnv.hpp" +#include +namespace raisim{ + +class ENVIRONMENT: public RaisimGymEnv{ +public: + explicit ENVIRONMENT(const std::string& resourceDir, const Yaml::Node& cfg, bool visualizable): + RaisimGymEnv(resourceDir, cfg), visualizable_(visualizable){ + world_ = std::make_unique(); + + leg_ = world_->addArticulatedSystem(resourceDir_ + "do_legs/do_legs.urdf") ; // + leg_->setName("leg"); + leg_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_ -> addGround(); + + gcDim_ = leg_ -> getGeneralizedCoordinateDim(); + gvDim_ = leg_ -> getDOF(); +// nJoints_ = gvDim_ - 6;// + nJoints_ = gcDim_; + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_);pTarget_.setZero(nJoints_); + no_collision_.push_back(1); + no_collision_.push_back(2); + no_collision_.push_back(3); +// no_collision_.push_back(); + + gc_init_ << 0, 0, 0, 0, 0; // + + + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(100.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(1); + leg_ ->setPdGains(jointPgain, jointDgain); + leg_ ->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + obDim_ = 10;// + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + + actionMean_ = gc_init_.tail(nJoints_); + double action_std; + READ_YAML(double, action_std, cfg_["action_std"]); + actionStd_.setConstant(action_std); + + rewards_.initializeFromConfigurationFile(cfg["reward"]); + + +// footIndices_.insert(leg_ ->getBodyIdx("shank")); // set for foot; +// footIndices_.insert(leg_ ->getBodyIdx("knee")); // set for foot; +// footIndices_.insert(leg_ ->getBodyIdx("thigh")); // set for foot; +// footIndices_.insert(leg_ ->getBodyIdx("body")); // set for foot; +// footIndices_.insert(leg_ ->getBodyIdx("lk5")); // set for foot; + + + if(visualizable_) + { + server_ = std::make_unique(world_.get()); + server_ ->launchServer(); + server_ ->focusOn(leg_); + } + } + + + + void init() final {} + + void reset() final { + leg_ ->setState(gc_init_, gv_init_); + updateObservation(); + } + + float step(const Eigen::Ref& action) final{ +// std::cout<< "action:\n" << action << std::endl; + pTarget12_ = action.cast (); // target for p ,12 is because of the 12 joints + pTarget12_ = pTarget12_.cwiseProduct(actionStd_); + pTarget12_ += actionMean_; + pTarget_.tail(nJoints_) = pTarget12_; +// pTarget_[1] = 0; +// std::cout<setPdTarget(pTarget_, vTarget_); + // note to excute the step command + // the pd is just the controller to fit the position to the robot + for(int i=0; i lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_ -> unlockVisualizationServerMutex(); + } + updateObservation(); + +// rewards_.record("torque", leg_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::min(3.0, bodyLinearVel_[0])); + rewards_.record("position", -bodyLinearPos_[1]); // +// std::cout<< "height : " << std::endl<< -bodyLinearPos_[1] << std::endl; + return rewards_.sum(); + } + + void updateObservation() { + leg_ ->getState(gc_, gv_); +// raisim::Vec<4> quat; +// raisim::Mat<3, 3> rot; +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// raisim::quatToRotMat(quat, rot); +// bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); +// bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// std::cout << "data: " << leg_ ->getGeneralizedVelocity().data() << std::endl; + + +// obDouble_ << gc_[2], // body height // 1 +// rot.e().row(2).transpose(), // body orientation // 3 +// gc_.tail(12), // joint angles // 12 +// bodyLinearVel_, bodyAngularVel_, // body vel // 6 +// gv_.tail(12); // 12 + bodyLinearVel_ = gv_; + bodyLinearPos_ = gc_; + obDouble_ << gc_.tail(5), gv_.tail(5); + } + + void observe(Eigen::Ref ob) final{ + ob = obDouble_.cast( ); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + for(auto& contact: leg_->getContacts()) + { + std::vector::iterator it = std::find(no_collision_.begin(), no_collision_.end(), contact.getlocalBodyIndex()); + if(it != no_collision_.end()) // if it != end ,means it was found + return true; + } + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() {}; + + +private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* leg_; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_, bodyLinearPos_; + std::set footIndices_; + std::vector no_collision_; + +}; + + +} \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/cfg.yaml new file mode 100755 index 000000000..d8666d266 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/cfg.yaml @@ -0,0 +1,24 @@ +seed: 1 +record_video: yes + +environment: + render: True +# just testing commenting + num_envs: 100 + eval_every_n: 300 + num_threads: 30 + simulation_dt: 0.0025 + control_dt: 0.01 + max_time: 4.0 + action_std: 0.3 + reward: + forwardVel: + coeff: 0.3 + torque: + coeff: -4e-5 + position: + coeff: 0.4 + +architecture: + policy_net: [128, 128] + value_net: [128, 128] diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/runner.py new file mode 100644 index 000000000..1207ac1d3 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/runner.py @@ -0,0 +1,147 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher +from raisimGymTorch.env.bin.rsg_leg import NormalSampler +from raisimGymTorch.env.bin.rsg_leg import RaisimGymEnv +import os +import math +import time +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse + +task_name = 'leg_locomotion' + +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train' ) +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +args = parser.parse_args() +mode = args.mode +weight_path = args.weight + +device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') + +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + '/../../../../..' + +cfg = YAML().load(open(task_path + '/cfg.yaml', 'r')) + +env = VecEnv(RaisimGymEnv(home_path + '/rsc/', dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +ob_dim = env.num_obs +act_dim = env.num_acts +num_threads = cfg['environment']['num_threads'] + +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * env.num_envs + +avg_rewards = [] + +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + env.num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) + +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + + +saver = ConfigurationSaver(log_dir=home_path + '/raisimGymTorch/data/' + task_name, + save_items=[task_path+'/cfg.yaml', task_path+'/Environment.hpp']) +tensorboard_launcher(saver.data_dir + '/..') + + +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=4, + learning_rate=1e-2, + device=device, + log_dir=saver.data_dir, + shuffle_batch=False) + +if mode == 'retrain': + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + + +for update in range(10000): + start = time.time() + env.reset() + reward_ll_sum = 0 + done_sum = 0 + average_dones = 0 + + if update % cfg['environment']['eval_every_n'] == 0: + print('Visualizing and evaluating the current policy') + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'ppo_optimizer_state_dict': ppo.optimizer.state_dict() + }, saver.data_dir+'/full_'+ str(update)+'.pt') + + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(saver.data_dir+'/full_'+ str(update) + '.pt')['actor_architecture_state_dict']) + + env.turn_on_visualization() + env.start_video_recording(datetime.datetime.now().strftime('%Y-%m-%d-%H-%M-%S') + 'policy_' + str(update) + '.mp4') + + for step in range(n_steps * 2): + with torch.no_grad(): + frame_start = time.time() + obs = env.observe(False) + action_ll = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + reward_ll, dones =env.step(action_ll.cpu().detach().numpy()) + frame_end = time.time() + wait_time = cfg['environment']['control_dt'] - (frame_end - frame_start) + if wait_time> 0: + time.sleep(wait_time) + + env.stop_video_recording() + env.turn_off_visualization() + + env.reset() + env.save_scaling(saver.data_dir, str(update)) + + for step in range(n_steps): + obs = env.observe() + action = ppo.act(obs) + reward, dones = env.step(action) + ppo.step(value_obs=obs, rews=reward, dones=dones) + done_sum = done_sum + np.sum(dones) + reward_ll_sum = reward_ll_sum + np.sum(reward) + + obs = env.observe() + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 10 ==0, update=update) + average_ll_performance = reward_ll_sum / total_steps + average_dones = done_sum / total_steps + avg_rewards.append(average_ll_performance) + + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(5) * 0.2).to(device)) # + + env.curriculum_callback() + + end = time.time() + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + print('{:<40} {:>6}'.format("dones: ", '{:0.6f}'.format(average_dones))) + print('{:<40} {:>6}'.format("time elapsed in this iteration: ", '{:6.4f}'.format(end - start))) + print('{:<40} {:>6}'.format("fps: ", '{:6.0f}'.format(total_steps / (end - start)))) + print('{:<40} {:>6}'.format("real time factor: ", '{:6.0f}'.format(total_steps / (end - start) + * cfg['environment']['control_dt']))) + print('----------------------------------------------------\n') diff --git a/raisimGymTorch/raisimGymTorch/env/raisim_gym.cpp b/raisimGymTorch/raisimGymTorch/env/raisim_gym.cpp index a5934edb6..2ce437582 100755 --- a/raisimGymTorch/raisimGymTorch/env/raisim_gym.cpp +++ b/raisimGymTorch/raisimGymTorch/env/raisim_gym.cpp @@ -6,7 +6,7 @@ #include #include #include -#include "Environment.hpp" +#include "Environment_wheel.hpp" #include "VectorizedEnvironment.hpp" namespace py = pybind11; @@ -24,6 +24,7 @@ PYBIND11_MODULE(RAISIMGYM_TORCH_ENV_NAME, m) { .def("reset", &VectorizedEnvironment::reset) .def("observe", &VectorizedEnvironment::observe) .def("step", &VectorizedEnvironment::step) + .def("init_posi", &VectorizedEnvironment::init_position) .def("setSeed", &VectorizedEnvironment::setSeed) .def("getRewardInfo", &VectorizedEnvironment::getRewardInfo) .def("close", &VectorizedEnvironment::close) diff --git a/raisimGymTorch/raisimGymTorch/env/test.yaml b/raisimGymTorch/raisimGymTorch/env/test.yaml new file mode 100644 index 000000000..21cf408af --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/test.yaml @@ -0,0 +1,32 @@ +seed: 1 +record_video: false + +environment: + render: true +# just testing commenting + num_envs: 100 + eval_every_n: 40 + num_threads: 30 + simulation_dt: 0.0025 + control_dt: 0.01 + max_time: 8.0 + action_std: 0.03 + show_ref: false + angle_rate: 0.3 + stable: 5 + reference: 0 + schedule: 40 + for_work: 1 + float_base: false + learnning_rate: 5e-4 + reward: + forwardVel: + coeff: 0.0 + torque: + coeff: -4e-5 + Stable: + coeff: 0.9 + +architecture: + policy_net: [128, 128] + value_net: [128, 128] diff --git a/raisimGymTorch/raisimGymTorch/env/utils/transfer_act.py b/raisimGymTorch/raisimGymTorch/env/utils/transfer_act.py new file mode 100644 index 000000000..e69de29bb diff --git a/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py b/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py index bc65f3500..16aea52d6 100755 --- a/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py +++ b/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py @@ -3,7 +3,7 @@ import os import ntpath import torch - +import logging class ConfigurationSaver: def __init__(self, log_dir, save_items): @@ -28,7 +28,7 @@ def tensorboard_launcher(directory_path): tb.configure(argv=[None, '--logdir', directory_path]) url = tb.launch() print("[RAISIM_GYM] Tensorboard session created: "+url) - webbrowser.open_new(url) + # webbrowser.open_new(url) def load_param(weight_path, env, actor, critic, optimizer, data_dir): @@ -58,3 +58,32 @@ def load_param(weight_path, env, actor, critic, optimizer, data_dir): actor.distribution.load_state_dict(checkpoint['actor_distribution_state_dict']) critic.architecture.load_state_dict(checkpoint['critic_architecture_state_dict']) optimizer.load_state_dict(checkpoint['optimizer_state_dict']) + +class RaisimLogger(): + def __init__(self, path): + self.logger = logging.getLogger(__file__) + self.logger.setLevel(logging.INFO) + self.fh = logging.FileHandler(path) + self.ch = logging.StreamHandler() + self.fh.setLevel(logging.DEBUG) + self.ch.setLevel(logging.DEBUG) + + self.formatter = logging.Formatter("%(asctime)s.%(msecs)03d - %(levelname)s - %(message)s", + datefmt='%Y-%m-%d,%H:%M:%S') + self.ch.setFormatter(self.formatter) + self.fh.setFormatter(self.formatter) + self.logger.addHandler(self.ch) + self.logger.addHandler(self.fh) + + def info(self, msg): + self.logger.info(msg) + def warning(self, msg): + self.logger.warning(msg) + def debug(self, msg): + self.logger.debug(msg) + def error(self, msg): + self.logger.error(msg) + + def setLevel(self, Level): + self.fh.setLevel(Level) + self.ch.setLevel(Level) \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/Environment.hpp b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/Environment.hpp new file mode 100644 index 000000000..82a196374 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/Environment.hpp @@ -0,0 +1,466 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#define PI 3.1415926 + +double cal(double low, double upp, double now){ + return (now + 1)/2 * (upp- low) + low; +} +void swap(Eigen::VectorXd &ob, int a, int b) +{ + double tmp = ob[a]; + ob[a] = ob[b]; + ob[b] = ob[a]; +} + +double rad_deg(double rad) +{ + return rad / PI * 180; +} + +void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); +// std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } +// std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} + +//void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +//{ +//// std::cout<< "size is "<< angle_list.size() << std::endl; +// double base1= 0.82, base3=0.0; +// double base2 = -2 * base1; +// double ang = abs(sin( float(idx) / T * PI)) * rate; +// +// int idx_base = 0; +//// std::cout<(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + /// add objects + anymal_ = world_->addArticulatedSystem(resourceDir_+"/a1_description/urdf/a1.urdf"); + anymal_->setName("dog"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); + nJoints_ = gvDim_ - 6; + + /// initialize containers + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + /// this is nominal configuration of anymal +// gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// anymal_1->setGeneralizedCoordinate(gc_init_); + gc_init_<< 0, 0, 0.41, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; + +// jointNominalConfig.tail(12).setZero(); +// Eigen::VectorXd tmp(12); +// tmp.setZero(); +// angle_generator(tmp, 0, 80.f); +// gc_init_.tail(12) = tmp; + + /// set pd gains + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(2000.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(100); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + + /// MUST BE DONE FOR ALL ENVIRONMENTS + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + +// READ_YAML(); + actionStd_.setConstant(action_std); + + join_limit = anymal_->getJointLimits(); + /// Reward coefficients + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + /// indices of links that should not make contact with ground + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + void init() final { } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + /// action scaling +// COUNT ++; +// std::cout<setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = 0; quat[1] = 0; quat[2] = 0; quat[3] = 0; +// raisim::quatToRotMat(quat, rot); +// anymal_->setBaseOrientation(rot); +// raisim::Vec<4> quat(4); +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// anymal_->setBaseOrientation(quat); +// pTarget_.tail(nJoints_) = angle_list; +// anymal_->setPdTarget(pTarget_, vTarget_); + } + // angle_list *= 0.3; +// angle_list.setZero(); +// Eigen::VectorXd idx1(8), idx2(4); +// idx1.setZero();idx2.setZero(); +// idx1<<1, 2, 4, 5, 7,8,10,11; +// idx2<<0, 3, 6, 9; + + pTarget12_ = action.cast(); +// Eigen::VectorXd ttmp =action.cast(); +// map_from_origin_to_limit(join_limit, pTarget12_,ttmp); + // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); +// pTarget12_ += actionMean_; +// pTarget12_ = angle_list; + + +// angle_mulit(pTarget12_, idx1, action_std); +// angle_mulit(pTarget12_, idx2, action_std); +// +// +// angle_list_for_work = angle_list * for_work_rate; + + + + +// pTarget12_ = angle_list_for_work + pTarget12_; + + + +// pTarget12_[11] = pTarget12_[10] *-2; +// pTarget12_[8] = pTarget12_[7] * -2; +// pTarget12_[1] = -pTarget12_[10]; +// pTarget12_[2] = -pTarget12_[11]; +// pTarget12_[4] = -pTarget12_[7]; +// pTarget12_[5] = -pTarget12_[8]; +// pTarget12_[9] = -0.03; +// pTarget12_[0] = -pTarget12_[9]; +// pTarget12_[6] = 0.03; +// pTarget12_[3] = -pTarget12_[6]; + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } +// rrr *= float(COUNT )/ schedule_T); +// for(int i=0; i<=1; i++) +// { +// rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; +// } +// rrr += abs(gc_[5] - gc_init_[5]) * 2 * stable_reward_rate; +// if(COUNT != 0) +// { +// rrr += (gc_ - gc_init_).norm() * reference_rate *0.1; +// } + + +// rrr +=(gc_init_.head(7) - gc_.head(7)).norm() * stable_reward_rate; + rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; +// rrr += abs(bodyLinearVel_[1]); +// rrr += abs(bodyLinearVel_[2]); +// rrr += abs(bodyLinearVel_[0]); + +// rrr += abs(gc_[2] - gc_init_[2]) ; + +// rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::mi); + rewards_.record("Stable", 1 - rrr, false); + rewards_.record("forwardVel", bodyLinearVel_[0], false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// std::cout<< rot.e().row(2).transpose().size() << " " < ob) final { + /// convert it to float + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + +// / if the contact body is not feet + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// std::cout<<"terminate "<0.3 ) +// { +// return true; +// } +// if(abs(gc_[4]-gc_init_[4]) >0.2 ) +// { +// return true; +// } +// if(abs(gc_[6]-gc_init_[6]) >0.2 ) +// { +// return true; +// } +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) +// return true; + +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8 || ) +// return true; + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} + +//int main() +//{ +// raisim::ENVIRONMENT a("../rsc/","/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml", +// true); +//} \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_0.pt b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_0.pt new file mode 100644 index 000000000..fd452a337 Binary files /dev/null and b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_0.pt differ diff --git a/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_120.pt b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_120.pt new file mode 100644 index 000000000..b03624910 Binary files /dev/null and b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_120.pt differ diff --git a/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_40.pt b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_40.pt new file mode 100644 index 000000000..a4099fcc0 Binary files /dev/null and b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_40.pt differ diff --git a/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_80.pt b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_80.pt new file mode 100644 index 000000000..7aa0235cf Binary files /dev/null and b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_80.pt differ diff --git a/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/reward.csv b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/reward.csv new file mode 100644 index 000000000..5e135bc11 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/reward.csv @@ -0,0 +1,134 @@ +,0 +0,-0.0615046456 +1,0.0126537349 +2,0.0279216359 +3,0.0427288112 +4,0.0212131324 +5,0.0398206397 +6,0.0518128525 +7,0.0447794446 +8,0.0484998804 +9,0.0422174849 +10,0.0414611474 +11,0.0256659385 +12,0.0323371572 +13,0.0775789361 +14,0.0364677203 +15,0.0327392954 +16,0.0797946859 +17,0.0567636694 +18,0.0563721836 +19,0.0668730299 +20,0.0380283327 +21,0.0661672911 +22,0.0762766505 +23,0.0456716058 +24,0.0621512444 +25,0.0357220345 +26,0.0544254147 +27,0.0736507719 +28,0.0556717726 +29,0.0776508413 +30,0.1098937313 +31,0.0547023832 +32,0.0742180259 +33,0.0957763146 +34,0.0712858858 +35,0.0868520612 +36,0.066873029 +37,0.106287811 +38,0.0664842076 +39,0.1011239419 +40,0.1098724256 +41,0.0971744745 +42,0.1344720458 +43,0.0792593901 +44,0.0964261261 +45,0.1179684342 +46,0.1116753856 +47,0.0998030153 +48,0.1170523074 +49,0.1165702759 +50,0.0894086967 +51,0.0976032444 +52,0.0906870161 +53,0.0856376623 +54,0.0873154542 +55,0.0858587038 +56,0.1288660903 +57,0.1236915687 +58,0.1212148281 +59,0.1111853654 +60,0.0932303344 +61,0.1033583346 +62,0.0916777122 +63,0.0889453081 +64,0.0876856323 +65,0.1113211861 +66,0.1253480547 +67,0.1014062391 +68,0.0753285667 +69,0.0786415392 +70,0.0864845469 +71,0.077014346 +72,0.0835737115 +73,0.0846496291 +74,0.0805190675 +75,0.0822874046 +76,0.0896750129 +77,0.0933208793 +78,0.0808519627 +79,0.1020800184 +80,0.1109243739 +81,0.1231243163 +82,0.122029754 +83,0.1046206729 +84,0.0859891971 +85,0.0922742588 +86,0.083642953 +87,0.0938242186 +88,0.0945299567 +89,0.0764683972 +90,0.0881277178 +91,0.0761568075 +92,0.0727958989 +93,0.0693098211 +94,0.0682924935 +95,0.0802527498 +96,0.0782047798 +97,0.0834538686 +98,0.0827081835 +99,0.0788439365 +100,0.0964767258 +101,0.1005593526 +102,0.086359377 +103,0.0928361842 +104,0.0962024206 +105,0.1080108761 +106,0.0945512624 +107,0.1288367951 +108,0.0786761581 +109,0.1057605067 +110,0.1102505942 +111,0.089195644 +112,0.0851023651 +113,0.0905751605 +114,0.0805989603 +115,0.0750169766 +116,0.0974541077 +117,0.087160989 +118,0.088905359 +119,0.0859838732 +120,0.0809265303 +121,0.0871929481 +122,0.0872675161 +123,0.0806974981 +124,0.0884472965 +125,0.1181069184 +126,0.0850171438 +127,0.0859918628 +128,0.1005620147 +129,0.1043969659 +130,0.0949027992 +131,0.0996299097 +132,0.095424778 diff --git a/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/train.log b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/train.log new file mode 100644 index 000000000..0f2012b4d --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/train.log @@ -0,0 +1,8400 @@ +2023-08-22,18:03:09.914 - INFO - actural position [0.06026352941989899, 0.712289571762085, -1.475023627281189, -0.043701592832803726, 0.6610443592071533, -1.4900684356689453, 0.039403077214956284, 0.6895747184753418, -1.369794249534607, -0.015171238221228123, 0.7029337882995605, -1.3707635402679443] +2023-08-22,18:03:14.971 - INFO - actual zero angle : (0.02419760636985302, 0.030052626505494118) +2023-08-22,18:03:14.991 - INFO - pre take action the first time +2023-08-22,18:03:19.049 - INFO - threading running +2023-08-22,18:03:19.062 - INFO - threading running +2023-08-22,18:03:19.073 - INFO - threading running +2023-08-22,18:03:19.084 - INFO - threading running +2023-08-22,18:03:19.093 - INFO - threading running +2023-08-22,18:03:19.103 - INFO - threading running +2023-08-22,18:03:19.113 - INFO - threading running +2023-08-22,18:03:19.123 - INFO - threading running +2023-08-22,18:03:19.133 - INFO - threading running +2023-08-22,18:03:19.143 - INFO - threading running +2023-08-22,18:03:19.153 - INFO - threading running +2023-08-22,18:03:19.163 - INFO - threading running +2023-08-22,18:03:19.174 - INFO - threading running +2023-08-22,18:03:19.183 - INFO - threading running +2023-08-22,18:03:19.193 - INFO - threading running +2023-08-22,18:03:19.203 - INFO - threading running +2023-08-22,18:03:19.213 - INFO - threading running +2023-08-22,18:03:19.223 - INFO - threading running +2023-08-22,18:03:19.233 - INFO - threading running +2023-08-22,18:03:19.244 - INFO - threading running +2023-08-22,18:03:19.254 - INFO - threading running +2023-08-22,18:03:19.264 - INFO - threading running +2023-08-22,18:03:19.275 - INFO - threading running +2023-08-22,18:03:19.285 - INFO - threading running +2023-08-22,18:03:19.294 - INFO - threading running +2023-08-22,18:03:19.305 - INFO - threading running +2023-08-22,18:03:19.314 - INFO - threading running +2023-08-22,18:03:19.324 - INFO - threading running +2023-08-22,18:03:19.334 - INFO - threading running +2023-08-22,18:03:19.344 - INFO - threading running +2023-08-22,18:03:19.354 - INFO - threading running +2023-08-22,18:03:19.364 - INFO - threading running +2023-08-22,18:03:19.374 - INFO - threading running +2023-08-22,18:03:19.384 - INFO - threading running +2023-08-22,18:03:19.395 - INFO - threading running +2023-08-22,18:03:19.406 - INFO - threading running +2023-08-22,18:03:19.415 - INFO - threading running +2023-08-22,18:03:19.426 - INFO - threading running +2023-08-22,18:03:19.436 - INFO - threading running +2023-08-22,18:03:19.447 - INFO - threading running +2023-08-22,18:03:19.457 - INFO - threading running +2023-08-22,18:03:19.467 - INFO - threading running +2023-08-22,18:03:19.477 - INFO - threading running +2023-08-22,18:03:19.487 - INFO - threading running +2023-08-22,18:03:19.497 - INFO - threading running +2023-08-22,18:03:19.507 - INFO - threading running +2023-08-22,18:03:19.517 - INFO - threading running +2023-08-22,18:03:19.527 - INFO - threading running +2023-08-22,18:03:19.537 - INFO - threading running +2023-08-22,18:03:19.547 - INFO - threading running +2023-08-22,18:03:19.558 - INFO - threading running +2023-08-22,18:03:19.572 - INFO - threading running +2023-08-22,18:03:19.582 - INFO - threading running +2023-08-22,18:03:19.595 - INFO - threading running +2023-08-22,18:03:19.599 - INFO - ---------------------------------------------------- +2023-08-22,18:03:19.599 - INFO - 0th iteration +2023-08-22,18:03:19.599 - INFO - average ll reward: -0.0615046456 +2023-08-22,18:03:19.599 - INFO - ---------------------------------------------------- + +2023-08-22,18:03:19.605 - INFO - updating finished +2023-08-22,18:03:23.629 - INFO - threading running +2023-08-22,18:03:23.642 - INFO - threading running +2023-08-22,18:03:23.652 - INFO - threading running +2023-08-22,18:03:23.663 - INFO - threading running +2023-08-22,18:03:23.673 - INFO - threading running +2023-08-22,18:03:23.683 - INFO - threading running +2023-08-22,18:03:23.694 - INFO - threading running +2023-08-22,18:03:23.704 - INFO - threading running +2023-08-22,18:03:23.714 - INFO - threading running +2023-08-22,18:03:23.725 - INFO - threading running +2023-08-22,18:03:23.736 - INFO - threading running +2023-08-22,18:03:23.745 - INFO - threading running +2023-08-22,18:03:23.756 - INFO - threading running +2023-08-22,18:03:23.765 - INFO - threading running +2023-08-22,18:03:23.776 - INFO - threading running +2023-08-22,18:03:23.785 - INFO - threading running +2023-08-22,18:03:23.795 - INFO - threading running +2023-08-22,18:03:23.806 - INFO - threading running +2023-08-22,18:03:23.817 - INFO - threading running +2023-08-22,18:03:23.826 - INFO - threading running +2023-08-22,18:03:23.836 - INFO - threading running +2023-08-22,18:03:23.846 - INFO - threading running +2023-08-22,18:03:23.856 - INFO - threading running +2023-08-22,18:03:23.867 - INFO - threading running +2023-08-22,18:03:23.877 - INFO - threading running +2023-08-22,18:03:23.887 - INFO - threading running +2023-08-22,18:03:23.897 - INFO - threading running +2023-08-22,18:03:23.908 - INFO - threading running +2023-08-22,18:03:23.918 - INFO - threading running +2023-08-22,18:03:23.928 - INFO - threading running +2023-08-22,18:03:23.939 - INFO - threading running +2023-08-22,18:03:23.948 - INFO - threading running +2023-08-22,18:03:23.958 - INFO - threading running +2023-08-22,18:03:23.968 - INFO - threading running +2023-08-22,18:03:23.979 - INFO - threading running +2023-08-22,18:03:23.990 - INFO - threading running +2023-08-22,18:03:23.999 - INFO - threading running +2023-08-22,18:03:24.010 - INFO - threading running +2023-08-22,18:03:24.019 - INFO - threading running +2023-08-22,18:03:24.029 - INFO - threading running +2023-08-22,18:03:24.039 - INFO - threading running +2023-08-22,18:03:24.049 - INFO - threading running +2023-08-22,18:03:24.059 - INFO - threading running +2023-08-22,18:03:24.069 - INFO - threading running +2023-08-22,18:03:24.080 - INFO - threading running +2023-08-22,18:03:24.089 - INFO - threading running +2023-08-22,18:03:24.100 - INFO - threading running +2023-08-22,18:03:24.111 - INFO - threading running +2023-08-22,18:03:24.121 - INFO - threading running +2023-08-22,18:03:24.131 - INFO - threading running +2023-08-22,18:03:24.137 - INFO - ---------------------------------------------------- +2023-08-22,18:03:24.137 - INFO - 1th iteration +2023-08-22,18:03:24.137 - INFO - average ll reward: 0.0126537349 +2023-08-22,18:03:24.137 - INFO - ---------------------------------------------------- + +2023-08-22,18:03:24.141 - INFO - updating finished +2023-08-22,18:03:28.182 - INFO - threading running +2023-08-22,18:03:28.197 - INFO - threading running +2023-08-22,18:03:28.207 - INFO - threading running +2023-08-22,18:03:28.218 - INFO - threading running +2023-08-22,18:03:28.228 - INFO - threading running +2023-08-22,18:03:28.238 - INFO - threading running +2023-08-22,18:03:28.248 - INFO - threading running +2023-08-22,18:03:28.258 - INFO - threading running +2023-08-22,18:03:28.268 - INFO - threading running +2023-08-22,18:03:28.279 - INFO - threading running +2023-08-22,18:03:28.289 - INFO - threading running +2023-08-22,18:03:28.300 - INFO - threading running +2023-08-22,18:03:28.309 - INFO - threading running +2023-08-22,18:03:28.319 - INFO - threading running +2023-08-22,18:03:28.329 - INFO - threading running +2023-08-22,18:03:28.339 - INFO - threading running +2023-08-22,18:03:28.349 - INFO - threading running +2023-08-22,18:03:28.359 - INFO - threading running +2023-08-22,18:03:28.369 - INFO - threading running +2023-08-22,18:03:28.379 - INFO - threading running +2023-08-22,18:03:28.389 - INFO - threading running +2023-08-22,18:03:28.399 - INFO - threading running +2023-08-22,18:03:28.409 - INFO - threading running +2023-08-22,18:03:28.419 - INFO - threading running +2023-08-22,18:03:28.429 - INFO - threading running +2023-08-22,18:03:28.440 - INFO - threading running +2023-08-22,18:03:28.450 - INFO - threading running +2023-08-22,18:03:28.461 - INFO - threading running +2023-08-22,18:03:28.470 - INFO - threading running +2023-08-22,18:03:28.480 - INFO - threading running +2023-08-22,18:03:28.491 - INFO - threading running +2023-08-22,18:03:28.500 - INFO - threading running +2023-08-22,18:03:28.510 - INFO - threading running +2023-08-22,18:03:28.520 - INFO - threading running +2023-08-22,18:03:28.530 - INFO - threading running +2023-08-22,18:03:28.541 - INFO - threading running +2023-08-22,18:03:28.551 - INFO - threading running +2023-08-22,18:03:28.562 - INFO - threading running +2023-08-22,18:03:28.571 - INFO - threading running +2023-08-22,18:03:28.582 - INFO - threading running +2023-08-22,18:03:28.591 - INFO - threading running +2023-08-22,18:03:28.602 - INFO - threading running +2023-08-22,18:03:28.611 - INFO - threading running +2023-08-22,18:03:28.621 - INFO - threading running +2023-08-22,18:03:28.631 - INFO - threading running +2023-08-22,18:03:28.641 - INFO - threading running +2023-08-22,18:03:28.651 - INFO - threading running +2023-08-22,18:03:28.661 - INFO - threading running +2023-08-22,18:03:28.671 - INFO - threading running +2023-08-22,18:03:28.676 - INFO - ---------------------------------------------------- +2023-08-22,18:03:28.676 - INFO - 2th iteration +2023-08-22,18:03:28.676 - INFO - average ll reward: 0.0279216359 +2023-08-22,18:03:28.676 - INFO - ---------------------------------------------------- + +2023-08-22,18:03:28.682 - INFO - updating finished +2023-08-22,18:03:32.730 - INFO - threading running +2023-08-22,18:03:32.745 - INFO - threading running +2023-08-22,18:03:32.755 - INFO - threading running +2023-08-22,18:03:32.765 - INFO - threading running +2023-08-22,18:03:32.775 - INFO - threading running +2023-08-22,18:03:32.786 - INFO - threading running +2023-08-22,18:03:32.796 - INFO - threading running +2023-08-22,18:03:32.806 - INFO - threading running +2023-08-22,18:03:32.816 - INFO - threading running +2023-08-22,18:03:32.827 - INFO - threading running +2023-08-22,18:03:32.836 - INFO - threading running +2023-08-22,18:03:32.846 - INFO - threading running +2023-08-22,18:03:32.857 - INFO - threading running +2023-08-22,18:03:32.867 - INFO - threading running +2023-08-22,18:03:32.878 - INFO - threading running +2023-08-22,18:03:32.887 - INFO - threading running +2023-08-22,18:03:32.897 - INFO - threading running +2023-08-22,18:03:32.907 - INFO - threading running +2023-08-22,18:03:32.917 - INFO - threading running +2023-08-22,18:03:32.927 - INFO - threading running +2023-08-22,18:03:32.938 - INFO - threading running +2023-08-22,18:03:32.948 - INFO - threading running +2023-08-22,18:03:32.958 - INFO - threading running +2023-08-22,18:03:32.968 - INFO - threading running +2023-08-22,18:03:32.978 - INFO - threading running +2023-08-22,18:03:32.988 - INFO - threading running +2023-08-22,18:03:32.998 - INFO - threading running +2023-08-22,18:03:33.008 - INFO - threading running +2023-08-22,18:03:33.018 - INFO - threading running +2023-08-22,18:03:33.028 - INFO - threading running +2023-08-22,18:03:33.038 - INFO - threading running +2023-08-22,18:03:33.049 - INFO - threading running +2023-08-22,18:03:33.058 - INFO - threading running +2023-08-22,18:03:33.069 - INFO - threading running +2023-08-22,18:03:33.078 - INFO - threading running +2023-08-22,18:03:33.088 - INFO - threading running +2023-08-22,18:03:33.098 - INFO - threading running +2023-08-22,18:03:33.108 - INFO - threading running +2023-08-22,18:03:33.119 - INFO - threading running +2023-08-22,18:03:33.128 - INFO - threading running +2023-08-22,18:03:33.139 - INFO - threading running +2023-08-22,18:03:33.148 - INFO - threading running +2023-08-22,18:03:33.159 - INFO - threading running +2023-08-22,18:03:33.168 - INFO - threading running +2023-08-22,18:03:33.178 - INFO - threading running +2023-08-22,18:03:33.189 - INFO - threading running +2023-08-22,18:03:33.198 - INFO - threading running +2023-08-22,18:03:33.208 - INFO - threading running +2023-08-22,18:03:33.219 - INFO - threading running +2023-08-22,18:03:33.228 - INFO - threading running +2023-08-22,18:03:33.238 - INFO - threading running +2023-08-22,18:03:33.242 - INFO - ---------------------------------------------------- +2023-08-22,18:03:33.242 - INFO - 3th iteration +2023-08-22,18:03:33.242 - INFO - average ll reward: 0.0427288112 +2023-08-22,18:03:33.242 - INFO - ---------------------------------------------------- + +2023-08-22,18:03:33.248 - INFO - updating finished +2023-08-22,18:03:37.350 - INFO - threading running +2023-08-22,18:03:37.364 - INFO - threading running +2023-08-22,18:03:37.374 - INFO - threading running +2023-08-22,18:03:37.384 - INFO - threading running +2023-08-22,18:03:37.394 - INFO - threading running +2023-08-22,18:03:37.404 - INFO - threading running +2023-08-22,18:03:37.415 - INFO - threading running +2023-08-22,18:03:37.424 - INFO - threading running +2023-08-22,18:03:37.435 - INFO - threading running +2023-08-22,18:03:37.445 - INFO - threading running +2023-08-22,18:03:37.454 - INFO - threading running +2023-08-22,18:03:37.465 - INFO - threading running +2023-08-22,18:03:37.474 - INFO - threading running +2023-08-22,18:03:37.484 - INFO - threading running +2023-08-22,18:03:37.494 - INFO - threading running +2023-08-22,18:03:37.504 - INFO - threading running +2023-08-22,18:03:37.514 - INFO - threading running +2023-08-22,18:03:37.524 - INFO - threading running +2023-08-22,18:03:37.534 - INFO - threading running +2023-08-22,18:03:37.544 - INFO - threading running +2023-08-22,18:03:37.554 - INFO - threading running +2023-08-22,18:03:37.564 - INFO - threading running +2023-08-22,18:03:37.574 - INFO - threading running +2023-08-22,18:03:37.584 - INFO - threading running +2023-08-22,18:03:37.594 - INFO - threading running +2023-08-22,18:03:37.604 - INFO - threading running +2023-08-22,18:03:37.615 - INFO - threading running +2023-08-22,18:03:37.625 - INFO - threading running +2023-08-22,18:03:37.636 - INFO - threading running +2023-08-22,18:03:37.646 - INFO - threading running +2023-08-22,18:03:37.657 - INFO - threading running +2023-08-22,18:03:37.666 - INFO - threading running +2023-08-22,18:03:37.676 - INFO - threading running +2023-08-22,18:03:37.687 - INFO - threading running +2023-08-22,18:03:37.697 - INFO - threading running +2023-08-22,18:03:37.707 - INFO - threading running +2023-08-22,18:03:37.717 - INFO - threading running +2023-08-22,18:03:37.727 - INFO - threading running +2023-08-22,18:03:37.738 - INFO - threading running +2023-08-22,18:03:37.748 - INFO - threading running +2023-08-22,18:03:37.759 - INFO - threading running +2023-08-22,18:03:37.768 - INFO - threading running +2023-08-22,18:03:37.778 - INFO - threading running +2023-08-22,18:03:37.789 - INFO - threading running +2023-08-22,18:03:37.799 - INFO - threading running +2023-08-22,18:03:37.809 - INFO - threading running +2023-08-22,18:03:37.819 - INFO - threading running +2023-08-22,18:03:37.829 - INFO - threading running +2023-08-22,18:03:37.840 - INFO - threading running +2023-08-22,18:03:37.849 - INFO - threading running +2023-08-22,18:03:37.859 - INFO - threading running +2023-08-22,18:03:37.869 - INFO - ---------------------------------------------------- +2023-08-22,18:03:37.869 - INFO - 4th iteration +2023-08-22,18:03:37.869 - INFO - average ll reward: 0.0212131324 +2023-08-22,18:03:37.869 - INFO - ---------------------------------------------------- + +2023-08-22,18:03:37.869 - INFO - updating finished +2023-08-22,18:03:42.002 - INFO - threading running +2023-08-22,18:03:42.017 - INFO - threading running +2023-08-22,18:03:42.027 - INFO - threading running +2023-08-22,18:03:42.037 - INFO - threading running +2023-08-22,18:03:42.048 - INFO - threading running +2023-08-22,18:03:42.059 - INFO - threading running +2023-08-22,18:03:42.068 - INFO - threading running +2023-08-22,18:03:42.078 - INFO - threading running +2023-08-22,18:03:42.088 - INFO - threading running +2023-08-22,18:03:42.099 - INFO - threading running +2023-08-22,18:03:42.109 - INFO - threading running +2023-08-22,18:03:42.119 - INFO - threading running +2023-08-22,18:03:42.129 - INFO - threading running +2023-08-22,18:03:42.140 - INFO - threading running +2023-08-22,18:03:42.151 - INFO - threading running +2023-08-22,18:03:42.160 - INFO - threading running +2023-08-22,18:03:42.170 - INFO - threading running +2023-08-22,18:03:42.181 - INFO - threading running +2023-08-22,18:03:42.192 - INFO - threading running +2023-08-22,18:03:42.201 - INFO - threading running +2023-08-22,18:03:42.212 - INFO - threading running +2023-08-22,18:03:42.222 - INFO - threading running +2023-08-22,18:03:42.233 - INFO - threading running +2023-08-22,18:03:42.243 - INFO - threading running +2023-08-22,18:03:42.254 - INFO - threading running +2023-08-22,18:03:42.264 - INFO - threading running +2023-08-22,18:03:42.274 - INFO - threading running +2023-08-22,18:03:42.284 - INFO - threading running +2023-08-22,18:03:42.294 - INFO - threading running +2023-08-22,18:03:42.304 - INFO - threading running +2023-08-22,18:03:42.315 - INFO - threading running +2023-08-22,18:03:42.325 - INFO - threading running +2023-08-22,18:03:42.335 - INFO - threading running +2023-08-22,18:03:42.345 - INFO - threading running +2023-08-22,18:03:42.356 - INFO - threading running +2023-08-22,18:03:42.365 - INFO - threading running +2023-08-22,18:03:42.376 - INFO - threading running +2023-08-22,18:03:42.385 - INFO - threading running +2023-08-22,18:03:42.395 - INFO - threading running +2023-08-22,18:03:42.405 - INFO - threading running +2023-08-22,18:03:42.415 - INFO - threading running +2023-08-22,18:03:42.426 - INFO - threading running +2023-08-22,18:03:42.437 - INFO - threading running +2023-08-22,18:03:42.447 - INFO - threading running +2023-08-22,18:03:42.456 - INFO - threading running +2023-08-22,18:03:42.467 - INFO - threading running +2023-08-22,18:03:42.476 - INFO - threading running +2023-08-22,18:03:42.486 - INFO - threading running +2023-08-22,18:03:42.496 - INFO - threading running +2023-08-22,18:03:42.507 - INFO - threading running +2023-08-22,18:03:42.517 - INFO - threading running +2023-08-22,18:03:42.527 - INFO - threading running +2023-08-22,18:03:42.537 - INFO - threading running +2023-08-22,18:03:42.546 - INFO - ---------------------------------------------------- +2023-08-22,18:03:42.546 - INFO - 5th iteration +2023-08-22,18:03:42.546 - INFO - average ll reward: 0.0398206397 +2023-08-22,18:03:42.546 - INFO - ---------------------------------------------------- + +2023-08-22,18:03:42.547 - INFO - updating finished +2023-08-22,18:03:46.595 - INFO - threading running +2023-08-22,18:03:46.606 - INFO - threading running +2023-08-22,18:03:46.617 - INFO - threading running +2023-08-22,18:03:46.626 - INFO - threading running +2023-08-22,18:03:46.636 - INFO - threading running +2023-08-22,18:03:46.646 - INFO - threading running +2023-08-22,18:03:46.656 - INFO - threading running +2023-08-22,18:03:46.666 - INFO - threading running +2023-08-22,18:03:46.676 - INFO - threading running +2023-08-22,18:03:46.687 - INFO - threading running +2023-08-22,18:03:46.696 - INFO - threading running +2023-08-22,18:03:46.707 - INFO - threading running +2023-08-22,18:03:46.717 - INFO - threading running +2023-08-22,18:03:46.728 - INFO - threading running +2023-08-22,18:03:46.737 - INFO - threading running +2023-08-22,18:03:46.747 - INFO - threading running +2023-08-22,18:03:46.757 - INFO - threading running +2023-08-22,18:03:46.767 - INFO - threading running +2023-08-22,18:03:46.777 - INFO - threading running +2023-08-22,18:03:46.787 - INFO - threading running +2023-08-22,18:03:46.798 - INFO - threading running +2023-08-22,18:03:46.807 - INFO - threading running +2023-08-22,18:03:46.817 - INFO - threading running +2023-08-22,18:03:46.827 - INFO - threading running +2023-08-22,18:03:46.837 - INFO - threading running +2023-08-22,18:03:46.848 - INFO - threading running +2023-08-22,18:03:46.857 - INFO - threading running +2023-08-22,18:03:46.868 - INFO - threading running +2023-08-22,18:03:46.878 - INFO - threading running +2023-08-22,18:03:46.888 - INFO - threading running +2023-08-22,18:03:46.898 - INFO - threading running +2023-08-22,18:03:46.909 - INFO - threading running +2023-08-22,18:03:46.918 - INFO - threading running +2023-08-22,18:03:46.929 - INFO - threading running +2023-08-22,18:03:46.939 - INFO - threading running +2023-08-22,18:03:46.950 - INFO - threading running +2023-08-22,18:03:46.959 - INFO - threading running +2023-08-22,18:03:46.970 - INFO - threading running +2023-08-22,18:03:46.979 - INFO - threading running +2023-08-22,18:03:46.990 - INFO - threading running +2023-08-22,18:03:47.001 - INFO - threading running +2023-08-22,18:03:47.011 - INFO - threading running +2023-08-22,18:03:47.020 - INFO - threading running +2023-08-22,18:03:47.030 - INFO - threading running +2023-08-22,18:03:47.040 - INFO - threading running +2023-08-22,18:03:47.050 - INFO - threading running +2023-08-22,18:03:47.060 - INFO - threading running +2023-08-22,18:03:47.071 - INFO - threading running +2023-08-22,18:03:47.080 - INFO - threading running +2023-08-22,18:03:47.086 - INFO - ---------------------------------------------------- +2023-08-22,18:03:47.086 - INFO - 6th iteration +2023-08-22,18:03:47.086 - INFO - average ll reward: 0.0518128525 +2023-08-22,18:03:47.086 - INFO - ---------------------------------------------------- + +2023-08-22,18:03:47.090 - INFO - updating finished +2023-08-22,18:03:51.205 - INFO - threading running +2023-08-22,18:03:51.215 - INFO - threading running +2023-08-22,18:03:51.225 - INFO - threading running +2023-08-22,18:03:51.235 - INFO - threading running +2023-08-22,18:03:51.246 - INFO - threading running +2023-08-22,18:03:51.256 - INFO - threading running +2023-08-22,18:03:51.266 - INFO - threading running +2023-08-22,18:03:51.277 - INFO - threading running +2023-08-22,18:03:51.286 - INFO - threading running +2023-08-22,18:03:51.297 - INFO - threading running +2023-08-22,18:03:51.307 - INFO - threading running +2023-08-22,18:03:51.317 - INFO - threading running +2023-08-22,18:03:51.328 - INFO - threading running +2023-08-22,18:03:51.337 - INFO - threading running +2023-08-22,18:03:51.347 - INFO - threading running +2023-08-22,18:03:51.358 - INFO - threading running +2023-08-22,18:03:51.367 - INFO - threading running +2023-08-22,18:03:51.377 - INFO - threading running +2023-08-22,18:03:51.387 - INFO - threading running +2023-08-22,18:03:51.397 - INFO - threading running +2023-08-22,18:03:51.407 - INFO - threading running +2023-08-22,18:03:51.417 - INFO - threading running +2023-08-22,18:03:51.427 - INFO - threading running +2023-08-22,18:03:51.437 - INFO - threading running +2023-08-22,18:03:51.447 - INFO - threading running +2023-08-22,18:03:51.457 - INFO - threading running +2023-08-22,18:03:51.467 - INFO - threading running +2023-08-22,18:03:51.477 - INFO - threading running +2023-08-22,18:03:51.487 - INFO - threading running +2023-08-22,18:03:51.497 - INFO - threading running +2023-08-22,18:03:51.508 - INFO - threading running +2023-08-22,18:03:51.517 - INFO - threading running +2023-08-22,18:03:51.528 - INFO - threading running +2023-08-22,18:03:51.537 - INFO - threading running +2023-08-22,18:03:51.547 - INFO - threading running +2023-08-22,18:03:51.557 - INFO - threading running +2023-08-22,18:03:51.567 - INFO - threading running +2023-08-22,18:03:51.577 - INFO - threading running +2023-08-22,18:03:51.588 - INFO - threading running +2023-08-22,18:03:51.597 - INFO - threading running +2023-08-22,18:03:51.608 - INFO - threading running +2023-08-22,18:03:51.617 - INFO - threading running +2023-08-22,18:03:51.628 - INFO - threading running +2023-08-22,18:03:51.637 - INFO - threading running +2023-08-22,18:03:51.647 - INFO - threading running +2023-08-22,18:03:51.657 - INFO - threading running +2023-08-22,18:03:51.668 - INFO - threading running +2023-08-22,18:03:51.678 - INFO - threading running +2023-08-22,18:03:51.687 - INFO - threading running +2023-08-22,18:03:51.697 - INFO - threading running +2023-08-22,18:03:51.708 - INFO - threading running +2023-08-22,18:03:51.717 - INFO - threading running +2023-08-22,18:03:51.728 - INFO - threading running +2023-08-22,18:03:51.731 - INFO - ---------------------------------------------------- +2023-08-22,18:03:51.731 - INFO - 7th iteration +2023-08-22,18:03:51.731 - INFO - average ll reward: 0.0447794446 +2023-08-22,18:03:51.732 - INFO - ---------------------------------------------------- + +2023-08-22,18:03:51.737 - INFO - updating finished +2023-08-22,18:03:55.808 - INFO - threading running +2023-08-22,18:03:55.815 - INFO - threading running +2023-08-22,18:03:55.826 - INFO - threading running +2023-08-22,18:03:55.835 - INFO - threading running +2023-08-22,18:03:55.846 - INFO - threading running +2023-08-22,18:03:55.856 - INFO - threading running +2023-08-22,18:03:55.867 - INFO - threading running +2023-08-22,18:03:55.877 - INFO - threading running +2023-08-22,18:03:55.888 - INFO - threading running +2023-08-22,18:03:55.897 - INFO - threading running +2023-08-22,18:03:55.907 - INFO - threading running +2023-08-22,18:03:55.917 - INFO - threading running +2023-08-22,18:03:55.927 - INFO - threading running +2023-08-22,18:03:55.937 - INFO - threading running +2023-08-22,18:03:55.947 - INFO - threading running +2023-08-22,18:03:55.957 - INFO - threading running +2023-08-22,18:03:55.968 - INFO - threading running +2023-08-22,18:03:55.977 - INFO - threading running +2023-08-22,18:03:55.987 - INFO - threading running +2023-08-22,18:03:55.998 - INFO - threading running +2023-08-22,18:03:56.008 - INFO - threading running +2023-08-22,18:03:56.018 - INFO - threading running +2023-08-22,18:03:56.028 - INFO - threading running +2023-08-22,18:03:56.039 - INFO - threading running +2023-08-22,18:03:56.048 - INFO - threading running +2023-08-22,18:03:56.059 - INFO - threading running +2023-08-22,18:03:56.070 - INFO - threading running +2023-08-22,18:03:56.079 - INFO - threading running +2023-08-22,18:03:56.089 - INFO - threading running +2023-08-22,18:03:56.099 - INFO - threading running +2023-08-22,18:03:56.109 - INFO - threading running +2023-08-22,18:03:56.119 - INFO - threading running +2023-08-22,18:03:56.129 - INFO - threading running +2023-08-22,18:03:56.139 - INFO - threading running +2023-08-22,18:03:56.150 - INFO - threading running +2023-08-22,18:03:56.160 - INFO - threading running +2023-08-22,18:03:56.170 - INFO - threading running +2023-08-22,18:03:56.180 - INFO - threading running +2023-08-22,18:03:56.190 - INFO - threading running +2023-08-22,18:03:56.200 - INFO - threading running +2023-08-22,18:03:56.210 - INFO - threading running +2023-08-22,18:03:56.220 - INFO - threading running +2023-08-22,18:03:56.231 - INFO - threading running +2023-08-22,18:03:56.240 - INFO - threading running +2023-08-22,18:03:56.250 - INFO - threading running +2023-08-22,18:03:56.260 - INFO - threading running +2023-08-22,18:03:56.270 - INFO - threading running +2023-08-22,18:03:56.281 - INFO - threading running +2023-08-22,18:03:56.290 - INFO - threading running +2023-08-22,18:03:56.301 - INFO - threading running +2023-08-22,18:03:56.312 - INFO - threading running +2023-08-22,18:03:56.318 - INFO - ---------------------------------------------------- +2023-08-22,18:03:56.318 - INFO - 8th iteration +2023-08-22,18:03:56.318 - INFO - average ll reward: 0.0484998804 +2023-08-22,18:03:56.318 - INFO - ---------------------------------------------------- + +2023-08-22,18:03:56.321 - INFO - updating finished +2023-08-22,18:04:00.371 - INFO - threading running +2023-08-22,18:04:00.386 - INFO - threading running +2023-08-22,18:04:00.395 - INFO - threading running +2023-08-22,18:04:00.405 - INFO - threading running +2023-08-22,18:04:00.415 - INFO - threading running +2023-08-22,18:04:00.425 - INFO - threading running +2023-08-22,18:04:00.436 - INFO - threading running +2023-08-22,18:04:00.445 - INFO - threading running +2023-08-22,18:04:00.455 - INFO - threading running +2023-08-22,18:04:00.465 - INFO - threading running +2023-08-22,18:04:00.475 - INFO - threading running +2023-08-22,18:04:00.485 - INFO - threading running +2023-08-22,18:04:00.495 - INFO - threading running +2023-08-22,18:04:00.505 - INFO - threading running +2023-08-22,18:04:00.515 - INFO - threading running +2023-08-22,18:04:00.525 - INFO - threading running +2023-08-22,18:04:00.536 - INFO - threading running +2023-08-22,18:04:00.546 - INFO - threading running +2023-08-22,18:04:00.557 - INFO - threading running +2023-08-22,18:04:00.566 - INFO - threading running +2023-08-22,18:04:00.576 - INFO - threading running +2023-08-22,18:04:00.586 - INFO - threading running +2023-08-22,18:04:00.597 - INFO - threading running +2023-08-22,18:04:00.606 - INFO - threading running +2023-08-22,18:04:00.617 - INFO - threading running +2023-08-22,18:04:00.626 - INFO - threading running +2023-08-22,18:04:00.636 - INFO - threading running +2023-08-22,18:04:00.646 - INFO - threading running +2023-08-22,18:04:00.656 - INFO - threading running +2023-08-22,18:04:00.666 - INFO - threading running +2023-08-22,18:04:00.676 - INFO - threading running +2023-08-22,18:04:00.687 - INFO - threading running +2023-08-22,18:04:00.697 - INFO - threading running +2023-08-22,18:04:00.708 - INFO - threading running +2023-08-22,18:04:00.719 - INFO - threading running +2023-08-22,18:04:00.728 - INFO - threading running +2023-08-22,18:04:00.738 - INFO - threading running +2023-08-22,18:04:00.748 - INFO - threading running +2023-08-22,18:04:00.758 - INFO - threading running +2023-08-22,18:04:00.768 - INFO - threading running +2023-08-22,18:04:00.778 - INFO - threading running +2023-08-22,18:04:00.788 - INFO - threading running +2023-08-22,18:04:00.798 - INFO - threading running +2023-08-22,18:04:00.808 - INFO - threading running +2023-08-22,18:04:00.818 - INFO - threading running +2023-08-22,18:04:00.829 - INFO - threading running +2023-08-22,18:04:00.838 - INFO - threading running +2023-08-22,18:04:00.848 - INFO - threading running +2023-08-22,18:04:00.859 - INFO - threading running +2023-08-22,18:04:00.869 - INFO - threading running +2023-08-22,18:04:00.878 - INFO - threading running +2023-08-22,18:04:00.888 - INFO - threading running +2023-08-22,18:04:00.899 - INFO - threading running +2023-08-22,18:04:00.909 - INFO - threading running +2023-08-22,18:04:00.912 - INFO - ---------------------------------------------------- +2023-08-22,18:04:00.912 - INFO - 9th iteration +2023-08-22,18:04:00.912 - INFO - average ll reward: 0.0422174849 +2023-08-22,18:04:00.912 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:00.919 - INFO - updating finished +2023-08-22,18:04:05.002 - INFO - threading running +2023-08-22,18:04:05.014 - INFO - threading running +2023-08-22,18:04:05.024 - INFO - threading running +2023-08-22,18:04:05.034 - INFO - threading running +2023-08-22,18:04:05.044 - INFO - threading running +2023-08-22,18:04:05.054 - INFO - threading running +2023-08-22,18:04:05.065 - INFO - threading running +2023-08-22,18:04:05.075 - INFO - threading running +2023-08-22,18:04:05.085 - INFO - threading running +2023-08-22,18:04:05.095 - INFO - threading running +2023-08-22,18:04:05.105 - INFO - threading running +2023-08-22,18:04:05.115 - INFO - threading running +2023-08-22,18:04:05.126 - INFO - threading running +2023-08-22,18:04:05.137 - INFO - threading running +2023-08-22,18:04:05.146 - INFO - threading running +2023-08-22,18:04:05.156 - INFO - threading running +2023-08-22,18:04:05.167 - INFO - threading running +2023-08-22,18:04:05.176 - INFO - threading running +2023-08-22,18:04:05.186 - INFO - threading running +2023-08-22,18:04:05.197 - INFO - threading running +2023-08-22,18:04:05.206 - INFO - threading running +2023-08-22,18:04:05.216 - INFO - threading running +2023-08-22,18:04:05.226 - INFO - threading running +2023-08-22,18:04:05.237 - INFO - threading running +2023-08-22,18:04:05.248 - INFO - threading running +2023-08-22,18:04:05.257 - INFO - threading running +2023-08-22,18:04:05.267 - INFO - threading running +2023-08-22,18:04:05.277 - INFO - threading running +2023-08-22,18:04:05.288 - INFO - threading running +2023-08-22,18:04:05.297 - INFO - threading running +2023-08-22,18:04:05.308 - INFO - threading running +2023-08-22,18:04:05.318 - INFO - threading running +2023-08-22,18:04:05.328 - INFO - threading running +2023-08-22,18:04:05.337 - INFO - threading running +2023-08-22,18:04:05.347 - INFO - threading running +2023-08-22,18:04:05.357 - INFO - threading running +2023-08-22,18:04:05.367 - INFO - threading running +2023-08-22,18:04:05.377 - INFO - threading running +2023-08-22,18:04:05.387 - INFO - threading running +2023-08-22,18:04:05.397 - INFO - threading running +2023-08-22,18:04:05.407 - INFO - threading running +2023-08-22,18:04:05.417 - INFO - threading running +2023-08-22,18:04:05.427 - INFO - threading running +2023-08-22,18:04:05.437 - INFO - threading running +2023-08-22,18:04:05.448 - INFO - threading running +2023-08-22,18:04:05.457 - INFO - threading running +2023-08-22,18:04:05.468 - INFO - threading running +2023-08-22,18:04:05.478 - INFO - threading running +2023-08-22,18:04:05.488 - INFO - threading running +2023-08-22,18:04:05.498 - INFO - threading running +2023-08-22,18:04:05.509 - INFO - threading running +2023-08-22,18:04:05.518 - INFO - threading running +2023-08-22,18:04:05.529 - INFO - threading running +2023-08-22,18:04:05.540 - INFO - threading running +2023-08-22,18:04:05.546 - INFO - ---------------------------------------------------- +2023-08-22,18:04:05.546 - INFO - 10th iteration +2023-08-22,18:04:05.546 - INFO - average ll reward: 0.0414611474 +2023-08-22,18:04:05.546 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:05.549 - INFO - updating finished +2023-08-22,18:04:09.640 - INFO - threading running +2023-08-22,18:04:09.654 - INFO - threading running +2023-08-22,18:04:09.665 - INFO - threading running +2023-08-22,18:04:09.675 - INFO - threading running +2023-08-22,18:04:09.686 - INFO - threading running +2023-08-22,18:04:09.696 - INFO - threading running +2023-08-22,18:04:09.706 - INFO - threading running +2023-08-22,18:04:09.716 - INFO - threading running +2023-08-22,18:04:09.727 - INFO - threading running +2023-08-22,18:04:09.737 - INFO - threading running +2023-08-22,18:04:09.747 - INFO - threading running +2023-08-22,18:04:09.757 - INFO - threading running +2023-08-22,18:04:09.767 - INFO - threading running +2023-08-22,18:04:09.777 - INFO - threading running +2023-08-22,18:04:09.787 - INFO - threading running +2023-08-22,18:04:09.797 - INFO - threading running +2023-08-22,18:04:09.807 - INFO - threading running +2023-08-22,18:04:09.817 - INFO - threading running +2023-08-22,18:04:09.828 - INFO - threading running +2023-08-22,18:04:09.838 - INFO - threading running +2023-08-22,18:04:09.847 - INFO - threading running +2023-08-22,18:04:09.857 - INFO - threading running +2023-08-22,18:04:09.867 - INFO - threading running +2023-08-22,18:04:09.878 - INFO - threading running +2023-08-22,18:04:09.888 - INFO - threading running +2023-08-22,18:04:09.898 - INFO - threading running +2023-08-22,18:04:09.908 - INFO - threading running +2023-08-22,18:04:09.918 - INFO - threading running +2023-08-22,18:04:09.928 - INFO - threading running +2023-08-22,18:04:09.938 - INFO - threading running +2023-08-22,18:04:09.948 - INFO - threading running +2023-08-22,18:04:09.958 - INFO - threading running +2023-08-22,18:04:09.968 - INFO - threading running +2023-08-22,18:04:09.978 - INFO - threading running +2023-08-22,18:04:09.988 - INFO - threading running +2023-08-22,18:04:09.999 - INFO - threading running +2023-08-22,18:04:10.009 - INFO - threading running +2023-08-22,18:04:10.019 - INFO - threading running +2023-08-22,18:04:10.030 - INFO - threading running +2023-08-22,18:04:10.041 - INFO - threading running +2023-08-22,18:04:10.050 - INFO - threading running +2023-08-22,18:04:10.061 - INFO - threading running +2023-08-22,18:04:10.071 - INFO - threading running +2023-08-22,18:04:10.081 - INFO - threading running +2023-08-22,18:04:10.091 - INFO - threading running +2023-08-22,18:04:10.101 - INFO - threading running +2023-08-22,18:04:10.111 - INFO - threading running +2023-08-22,18:04:10.121 - INFO - threading running +2023-08-22,18:04:10.131 - INFO - threading running +2023-08-22,18:04:10.141 - INFO - threading running +2023-08-22,18:04:10.146 - INFO - ---------------------------------------------------- +2023-08-22,18:04:10.146 - INFO - 11th iteration +2023-08-22,18:04:10.146 - INFO - average ll reward: 0.0256659385 +2023-08-22,18:04:10.146 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:10.152 - INFO - updating finished +2023-08-22,18:04:14.250 - INFO - threading running +2023-08-22,18:04:14.264 - INFO - threading running +2023-08-22,18:04:14.274 - INFO - threading running +2023-08-22,18:04:14.284 - INFO - threading running +2023-08-22,18:04:14.295 - INFO - threading running +2023-08-22,18:04:14.304 - INFO - threading running +2023-08-22,18:04:14.314 - INFO - threading running +2023-08-22,18:04:14.325 - INFO - threading running +2023-08-22,18:04:14.334 - INFO - threading running +2023-08-22,18:04:14.345 - INFO - threading running +2023-08-22,18:04:14.355 - INFO - threading running +2023-08-22,18:04:14.365 - INFO - threading running +2023-08-22,18:04:14.375 - INFO - threading running +2023-08-22,18:04:14.385 - INFO - threading running +2023-08-22,18:04:14.395 - INFO - threading running +2023-08-22,18:04:14.405 - INFO - threading running +2023-08-22,18:04:14.415 - INFO - threading running +2023-08-22,18:04:14.425 - INFO - threading running +2023-08-22,18:04:14.435 - INFO - threading running +2023-08-22,18:04:14.445 - INFO - threading running +2023-08-22,18:04:14.456 - INFO - threading running +2023-08-22,18:04:14.465 - INFO - threading running +2023-08-22,18:04:14.476 - INFO - threading running +2023-08-22,18:04:14.487 - INFO - threading running +2023-08-22,18:04:14.496 - INFO - threading running +2023-08-22,18:04:14.507 - INFO - threading running +2023-08-22,18:04:14.516 - INFO - threading running +2023-08-22,18:04:14.526 - INFO - threading running +2023-08-22,18:04:14.536 - INFO - threading running +2023-08-22,18:04:14.546 - INFO - threading running +2023-08-22,18:04:14.556 - INFO - threading running +2023-08-22,18:04:14.567 - INFO - threading running +2023-08-22,18:04:14.576 - INFO - threading running +2023-08-22,18:04:14.586 - INFO - threading running +2023-08-22,18:04:14.597 - INFO - threading running +2023-08-22,18:04:14.606 - INFO - threading running +2023-08-22,18:04:14.616 - INFO - threading running +2023-08-22,18:04:14.627 - INFO - threading running +2023-08-22,18:04:14.636 - INFO - threading running +2023-08-22,18:04:14.646 - INFO - threading running +2023-08-22,18:04:14.656 - INFO - threading running +2023-08-22,18:04:14.666 - INFO - threading running +2023-08-22,18:04:14.676 - INFO - threading running +2023-08-22,18:04:14.687 - INFO - threading running +2023-08-22,18:04:14.698 - INFO - threading running +2023-08-22,18:04:14.707 - INFO - threading running +2023-08-22,18:04:14.717 - INFO - threading running +2023-08-22,18:04:14.727 - INFO - threading running +2023-08-22,18:04:14.738 - INFO - threading running +2023-08-22,18:04:14.748 - INFO - threading running +2023-08-22,18:04:14.758 - INFO - threading running +2023-08-22,18:04:14.768 - INFO - threading running +2023-08-22,18:04:14.778 - INFO - threading running +2023-08-22,18:04:14.786 - INFO - ---------------------------------------------------- +2023-08-22,18:04:14.786 - INFO - 12th iteration +2023-08-22,18:04:14.786 - INFO - average ll reward: 0.0323371572 +2023-08-22,18:04:14.786 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:14.789 - INFO - updating finished +2023-08-22,18:04:18.849 - INFO - threading running +2023-08-22,18:04:18.856 - INFO - threading running +2023-08-22,18:04:18.866 - INFO - threading running +2023-08-22,18:04:18.876 - INFO - threading running +2023-08-22,18:04:18.886 - INFO - threading running +2023-08-22,18:04:18.897 - INFO - threading running +2023-08-22,18:04:18.907 - INFO - threading running +2023-08-22,18:04:18.918 - INFO - threading running +2023-08-22,18:04:18.927 - INFO - threading running +2023-08-22,18:04:18.938 - INFO - threading running +2023-08-22,18:04:18.947 - INFO - threading running +2023-08-22,18:04:18.958 - INFO - threading running +2023-08-22,18:04:18.967 - INFO - threading running +2023-08-22,18:04:18.977 - INFO - threading running +2023-08-22,18:04:18.987 - INFO - threading running +2023-08-22,18:04:18.997 - INFO - threading running +2023-08-22,18:04:19.007 - INFO - threading running +2023-08-22,18:04:19.018 - INFO - threading running +2023-08-22,18:04:19.029 - INFO - threading running +2023-08-22,18:04:19.039 - INFO - threading running +2023-08-22,18:04:19.050 - INFO - threading running +2023-08-22,18:04:19.060 - INFO - threading running +2023-08-22,18:04:19.070 - INFO - threading running +2023-08-22,18:04:19.081 - INFO - threading running +2023-08-22,18:04:19.091 - INFO - threading running +2023-08-22,18:04:19.101 - INFO - threading running +2023-08-22,18:04:19.111 - INFO - threading running +2023-08-22,18:04:19.121 - INFO - threading running +2023-08-22,18:04:19.131 - INFO - threading running +2023-08-22,18:04:19.142 - INFO - threading running +2023-08-22,18:04:19.151 - INFO - threading running +2023-08-22,18:04:19.161 - INFO - threading running +2023-08-22,18:04:19.171 - INFO - threading running +2023-08-22,18:04:19.181 - INFO - threading running +2023-08-22,18:04:19.191 - INFO - threading running +2023-08-22,18:04:19.201 - INFO - threading running +2023-08-22,18:04:19.211 - INFO - threading running +2023-08-22,18:04:19.221 - INFO - threading running +2023-08-22,18:04:19.231 - INFO - threading running +2023-08-22,18:04:19.241 - INFO - threading running +2023-08-22,18:04:19.251 - INFO - threading running +2023-08-22,18:04:19.262 - INFO - threading running +2023-08-22,18:04:19.271 - INFO - threading running +2023-08-22,18:04:19.281 - INFO - threading running +2023-08-22,18:04:19.291 - INFO - threading running +2023-08-22,18:04:19.301 - INFO - threading running +2023-08-22,18:04:19.311 - INFO - threading running +2023-08-22,18:04:19.321 - INFO - threading running +2023-08-22,18:04:19.332 - INFO - threading running +2023-08-22,18:04:19.341 - INFO - threading running +2023-08-22,18:04:19.352 - INFO - threading running +2023-08-22,18:04:19.361 - INFO - threading running +2023-08-22,18:04:19.371 - INFO - threading running +2023-08-22,18:04:19.381 - INFO - threading running +2023-08-22,18:04:19.392 - INFO - threading running +2023-08-22,18:04:19.401 - INFO - threading running +2023-08-22,18:04:19.412 - INFO - threading running +2023-08-22,18:04:19.421 - INFO - threading running +2023-08-22,18:04:19.432 - INFO - threading running +2023-08-22,18:04:19.438 - INFO - ---------------------------------------------------- +2023-08-22,18:04:19.438 - INFO - 13th iteration +2023-08-22,18:04:19.438 - INFO - average ll reward: 0.0775789361 +2023-08-22,18:04:19.438 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:19.442 - INFO - updating finished +2023-08-22,18:04:23.499 - INFO - threading running +2023-08-22,18:04:23.514 - INFO - threading running +2023-08-22,18:04:23.524 - INFO - threading running +2023-08-22,18:04:23.534 - INFO - threading running +2023-08-22,18:04:23.544 - INFO - threading running +2023-08-22,18:04:23.555 - INFO - threading running +2023-08-22,18:04:23.565 - INFO - threading running +2023-08-22,18:04:23.575 - INFO - threading running +2023-08-22,18:04:23.586 - INFO - threading running +2023-08-22,18:04:23.596 - INFO - threading running +2023-08-22,18:04:23.607 - INFO - threading running +2023-08-22,18:04:23.617 - INFO - threading running +2023-08-22,18:04:23.628 - INFO - threading running +2023-08-22,18:04:23.637 - INFO - threading running +2023-08-22,18:04:23.647 - INFO - threading running +2023-08-22,18:04:23.657 - INFO - threading running +2023-08-22,18:04:23.667 - INFO - threading running +2023-08-22,18:04:23.677 - INFO - threading running +2023-08-22,18:04:23.687 - INFO - threading running +2023-08-22,18:04:23.698 - INFO - threading running +2023-08-22,18:04:23.708 - INFO - threading running +2023-08-22,18:04:23.718 - INFO - threading running +2023-08-22,18:04:23.728 - INFO - threading running +2023-08-22,18:04:23.738 - INFO - threading running +2023-08-22,18:04:23.748 - INFO - threading running +2023-08-22,18:04:23.759 - INFO - threading running +2023-08-22,18:04:23.769 - INFO - threading running +2023-08-22,18:04:23.779 - INFO - threading running +2023-08-22,18:04:23.789 - INFO - threading running +2023-08-22,18:04:23.799 - INFO - threading running +2023-08-22,18:04:23.809 - INFO - threading running +2023-08-22,18:04:23.819 - INFO - threading running +2023-08-22,18:04:23.829 - INFO - threading running +2023-08-22,18:04:23.840 - INFO - threading running +2023-08-22,18:04:23.851 - INFO - threading running +2023-08-22,18:04:23.861 - INFO - threading running +2023-08-22,18:04:23.872 - INFO - threading running +2023-08-22,18:04:23.881 - INFO - threading running +2023-08-22,18:04:23.891 - INFO - threading running +2023-08-22,18:04:23.901 - INFO - threading running +2023-08-22,18:04:23.911 - INFO - threading running +2023-08-22,18:04:23.921 - INFO - threading running +2023-08-22,18:04:23.932 - INFO - threading running +2023-08-22,18:04:23.941 - INFO - threading running +2023-08-22,18:04:23.952 - INFO - threading running +2023-08-22,18:04:23.963 - INFO - threading running +2023-08-22,18:04:23.973 - INFO - threading running +2023-08-22,18:04:23.982 - INFO - threading running +2023-08-22,18:04:23.992 - INFO - threading running +2023-08-22,18:04:24.003 - INFO - threading running +2023-08-22,18:04:24.013 - INFO - threading running +2023-08-22,18:04:24.023 - INFO - threading running +2023-08-22,18:04:24.034 - INFO - threading running +2023-08-22,18:04:24.044 - INFO - threading running +2023-08-22,18:04:24.054 - INFO - threading running +2023-08-22,18:04:24.060 - INFO - ---------------------------------------------------- +2023-08-22,18:04:24.060 - INFO - 14th iteration +2023-08-22,18:04:24.060 - INFO - average ll reward: 0.0364677203 +2023-08-22,18:04:24.060 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:24.065 - INFO - updating finished +2023-08-22,18:04:28.132 - INFO - threading running +2023-08-22,18:04:28.139 - INFO - threading running +2023-08-22,18:04:28.149 - INFO - threading running +2023-08-22,18:04:28.159 - INFO - threading running +2023-08-22,18:04:28.169 - INFO - threading running +2023-08-22,18:04:28.179 - INFO - threading running +2023-08-22,18:04:28.190 - INFO - threading running +2023-08-22,18:04:28.201 - INFO - threading running +2023-08-22,18:04:28.210 - INFO - threading running +2023-08-22,18:04:28.220 - INFO - threading running +2023-08-22,18:04:28.230 - INFO - threading running +2023-08-22,18:04:28.241 - INFO - threading running +2023-08-22,18:04:28.251 - INFO - threading running +2023-08-22,18:04:28.261 - INFO - threading running +2023-08-22,18:04:28.270 - INFO - threading running +2023-08-22,18:04:28.280 - INFO - threading running +2023-08-22,18:04:28.290 - INFO - threading running +2023-08-22,18:04:28.301 - INFO - threading running +2023-08-22,18:04:28.310 - INFO - threading running +2023-08-22,18:04:28.321 - INFO - threading running +2023-08-22,18:04:28.330 - INFO - threading running +2023-08-22,18:04:28.340 - INFO - threading running +2023-08-22,18:04:28.350 - INFO - threading running +2023-08-22,18:04:28.361 - INFO - threading running +2023-08-22,18:04:28.371 - INFO - threading running +2023-08-22,18:04:28.381 - INFO - threading running +2023-08-22,18:04:28.390 - INFO - threading running +2023-08-22,18:04:28.401 - INFO - threading running +2023-08-22,18:04:28.410 - INFO - threading running +2023-08-22,18:04:28.420 - INFO - threading running +2023-08-22,18:04:28.430 - INFO - threading running +2023-08-22,18:04:28.440 - INFO - threading running +2023-08-22,18:04:28.451 - INFO - threading running +2023-08-22,18:04:28.460 - INFO - threading running +2023-08-22,18:04:28.470 - INFO - threading running +2023-08-22,18:04:28.480 - INFO - threading running +2023-08-22,18:04:28.490 - INFO - threading running +2023-08-22,18:04:28.501 - INFO - threading running +2023-08-22,18:04:28.511 - INFO - threading running +2023-08-22,18:04:28.521 - INFO - threading running +2023-08-22,18:04:28.531 - INFO - threading running +2023-08-22,18:04:28.542 - INFO - threading running +2023-08-22,18:04:28.551 - INFO - threading running +2023-08-22,18:04:28.562 - INFO - threading running +2023-08-22,18:04:28.572 - INFO - threading running +2023-08-22,18:04:28.582 - INFO - threading running +2023-08-22,18:04:28.592 - INFO - threading running +2023-08-22,18:04:28.602 - INFO - threading running +2023-08-22,18:04:28.613 - INFO - threading running +2023-08-22,18:04:28.622 - INFO - threading running +2023-08-22,18:04:28.632 - INFO - threading running +2023-08-22,18:04:28.642 - INFO - threading running +2023-08-22,18:04:28.652 - INFO - threading running +2023-08-22,18:04:28.659 - INFO - ---------------------------------------------------- +2023-08-22,18:04:28.659 - INFO - 15th iteration +2023-08-22,18:04:28.659 - INFO - average ll reward: 0.0327392954 +2023-08-22,18:04:28.659 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:28.662 - INFO - updating finished +2023-08-22,18:04:32.733 - INFO - threading running +2023-08-22,18:04:32.745 - INFO - threading running +2023-08-22,18:04:32.755 - INFO - threading running +2023-08-22,18:04:32.765 - INFO - threading running +2023-08-22,18:04:32.775 - INFO - threading running +2023-08-22,18:04:32.785 - INFO - threading running +2023-08-22,18:04:32.795 - INFO - threading running +2023-08-22,18:04:32.805 - INFO - threading running +2023-08-22,18:04:32.815 - INFO - threading running +2023-08-22,18:04:32.826 - INFO - threading running +2023-08-22,18:04:32.836 - INFO - threading running +2023-08-22,18:04:32.845 - INFO - threading running +2023-08-22,18:04:32.855 - INFO - threading running +2023-08-22,18:04:32.865 - INFO - threading running +2023-08-22,18:04:32.875 - INFO - threading running +2023-08-22,18:04:32.886 - INFO - threading running +2023-08-22,18:04:32.896 - INFO - threading running +2023-08-22,18:04:32.907 - INFO - threading running +2023-08-22,18:04:32.916 - INFO - threading running +2023-08-22,18:04:32.927 - INFO - threading running +2023-08-22,18:04:32.936 - INFO - threading running +2023-08-22,18:04:32.946 - INFO - threading running +2023-08-22,18:04:32.957 - INFO - threading running +2023-08-22,18:04:32.966 - INFO - threading running +2023-08-22,18:04:32.977 - INFO - threading running +2023-08-22,18:04:32.988 - INFO - threading running +2023-08-22,18:04:32.998 - INFO - threading running +2023-08-22,18:04:33.008 - INFO - threading running +2023-08-22,18:04:33.018 - INFO - threading running +2023-08-22,18:04:33.028 - INFO - threading running +2023-08-22,18:04:33.039 - INFO - threading running +2023-08-22,18:04:33.048 - INFO - threading running +2023-08-22,18:04:33.058 - INFO - threading running +2023-08-22,18:04:33.068 - INFO - threading running +2023-08-22,18:04:33.078 - INFO - threading running +2023-08-22,18:04:33.088 - INFO - threading running +2023-08-22,18:04:33.098 - INFO - threading running +2023-08-22,18:04:33.108 - INFO - threading running +2023-08-22,18:04:33.118 - INFO - threading running +2023-08-22,18:04:33.128 - INFO - threading running +2023-08-22,18:04:33.139 - INFO - threading running +2023-08-22,18:04:33.148 - INFO - threading running +2023-08-22,18:04:33.158 - INFO - threading running +2023-08-22,18:04:33.168 - INFO - threading running +2023-08-22,18:04:33.178 - INFO - threading running +2023-08-22,18:04:33.188 - INFO - threading running +2023-08-22,18:04:33.199 - INFO - threading running +2023-08-22,18:04:33.208 - INFO - threading running +2023-08-22,18:04:33.219 - INFO - threading running +2023-08-22,18:04:33.229 - INFO - threading running +2023-08-22,18:04:33.239 - INFO - threading running +2023-08-22,18:04:33.250 - INFO - threading running +2023-08-22,18:04:33.259 - INFO - threading running +2023-08-22,18:04:33.270 - INFO - threading running +2023-08-22,18:04:33.280 - INFO - threading running +2023-08-22,18:04:33.284 - INFO - ---------------------------------------------------- +2023-08-22,18:04:33.284 - INFO - 16th iteration +2023-08-22,18:04:33.284 - INFO - average ll reward: 0.0797946859 +2023-08-22,18:04:33.284 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:33.290 - INFO - updating finished +2023-08-22,18:04:37.382 - INFO - threading running +2023-08-22,18:04:37.397 - INFO - threading running +2023-08-22,18:04:37.407 - INFO - threading running +2023-08-22,18:04:37.417 - INFO - threading running +2023-08-22,18:04:37.427 - INFO - threading running +2023-08-22,18:04:37.437 - INFO - threading running +2023-08-22,18:04:37.447 - INFO - threading running +2023-08-22,18:04:37.458 - INFO - threading running +2023-08-22,18:04:37.468 - INFO - threading running +2023-08-22,18:04:37.478 - INFO - threading running +2023-08-22,18:04:37.489 - INFO - threading running +2023-08-22,18:04:37.498 - INFO - threading running +2023-08-22,18:04:37.508 - INFO - threading running +2023-08-22,18:04:37.518 - INFO - threading running +2023-08-22,18:04:37.528 - INFO - threading running +2023-08-22,18:04:37.538 - INFO - threading running +2023-08-22,18:04:37.548 - INFO - threading running +2023-08-22,18:04:37.558 - INFO - threading running +2023-08-22,18:04:37.568 - INFO - threading running +2023-08-22,18:04:37.578 - INFO - threading running +2023-08-22,18:04:37.589 - INFO - threading running +2023-08-22,18:04:37.598 - INFO - threading running +2023-08-22,18:04:37.609 - INFO - threading running +2023-08-22,18:04:37.619 - INFO - threading running +2023-08-22,18:04:37.629 - INFO - threading running +2023-08-22,18:04:37.639 - INFO - threading running +2023-08-22,18:04:37.649 - INFO - threading running +2023-08-22,18:04:37.659 - INFO - threading running +2023-08-22,18:04:37.670 - INFO - threading running +2023-08-22,18:04:37.681 - INFO - threading running +2023-08-22,18:04:37.691 - INFO - threading running +2023-08-22,18:04:37.702 - INFO - threading running +2023-08-22,18:04:37.713 - INFO - threading running +2023-08-22,18:04:37.724 - INFO - threading running +2023-08-22,18:04:37.734 - INFO - threading running +2023-08-22,18:04:37.745 - INFO - threading running +2023-08-22,18:04:37.754 - INFO - threading running +2023-08-22,18:04:37.765 - INFO - threading running +2023-08-22,18:04:37.775 - INFO - threading running +2023-08-22,18:04:37.786 - INFO - threading running +2023-08-22,18:04:37.795 - INFO - threading running +2023-08-22,18:04:37.805 - INFO - threading running +2023-08-22,18:04:37.816 - INFO - threading running +2023-08-22,18:04:37.825 - INFO - threading running +2023-08-22,18:04:37.835 - INFO - threading running +2023-08-22,18:04:37.845 - INFO - threading running +2023-08-22,18:04:37.855 - INFO - threading running +2023-08-22,18:04:37.866 - INFO - threading running +2023-08-22,18:04:37.876 - INFO - threading running +2023-08-22,18:04:37.886 - INFO - threading running +2023-08-22,18:04:37.897 - INFO - threading running +2023-08-22,18:04:37.908 - INFO - threading running +2023-08-22,18:04:37.917 - INFO - threading running +2023-08-22,18:04:37.927 - INFO - threading running +2023-08-22,18:04:37.937 - INFO - threading running +2023-08-22,18:04:37.944 - INFO - ---------------------------------------------------- +2023-08-22,18:04:37.944 - INFO - 17th iteration +2023-08-22,18:04:37.944 - INFO - average ll reward: 0.0567636694 +2023-08-22,18:04:37.944 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:37.947 - INFO - updating finished +2023-08-22,18:04:42.035 - INFO - threading running +2023-08-22,18:04:42.046 - INFO - threading running +2023-08-22,18:04:42.056 - INFO - threading running +2023-08-22,18:04:42.067 - INFO - threading running +2023-08-22,18:04:42.077 - INFO - threading running +2023-08-22,18:04:42.086 - INFO - threading running +2023-08-22,18:04:42.096 - INFO - threading running +2023-08-22,18:04:42.106 - INFO - threading running +2023-08-22,18:04:42.116 - INFO - threading running +2023-08-22,18:04:42.127 - INFO - threading running +2023-08-22,18:04:42.138 - INFO - threading running +2023-08-22,18:04:42.147 - INFO - threading running +2023-08-22,18:04:42.157 - INFO - threading running +2023-08-22,18:04:42.168 - INFO - threading running +2023-08-22,18:04:42.178 - INFO - threading running +2023-08-22,18:04:42.189 - INFO - threading running +2023-08-22,18:04:42.198 - INFO - threading running +2023-08-22,18:04:42.208 - INFO - threading running +2023-08-22,18:04:42.219 - INFO - threading running +2023-08-22,18:04:42.230 - INFO - threading running +2023-08-22,18:04:42.239 - INFO - threading running +2023-08-22,18:04:42.249 - INFO - threading running +2023-08-22,18:04:42.259 - INFO - threading running +2023-08-22,18:04:42.270 - INFO - threading running +2023-08-22,18:04:42.279 - INFO - threading running +2023-08-22,18:04:42.289 - INFO - threading running +2023-08-22,18:04:42.299 - INFO - threading running +2023-08-22,18:04:42.309 - INFO - threading running +2023-08-22,18:04:42.320 - INFO - threading running +2023-08-22,18:04:42.330 - INFO - threading running +2023-08-22,18:04:42.339 - INFO - threading running +2023-08-22,18:04:42.350 - INFO - threading running +2023-08-22,18:04:42.359 - INFO - threading running +2023-08-22,18:04:42.369 - INFO - threading running +2023-08-22,18:04:42.380 - INFO - threading running +2023-08-22,18:04:42.391 - INFO - threading running +2023-08-22,18:04:42.400 - INFO - threading running +2023-08-22,18:04:42.411 - INFO - threading running +2023-08-22,18:04:42.422 - INFO - threading running +2023-08-22,18:04:42.432 - INFO - threading running +2023-08-22,18:04:42.442 - INFO - threading running +2023-08-22,18:04:42.452 - INFO - threading running +2023-08-22,18:04:42.463 - INFO - threading running +2023-08-22,18:04:42.473 - INFO - threading running +2023-08-22,18:04:42.484 - INFO - threading running +2023-08-22,18:04:42.494 - INFO - threading running +2023-08-22,18:04:42.504 - INFO - threading running +2023-08-22,18:04:42.514 - INFO - threading running +2023-08-22,18:04:42.524 - INFO - threading running +2023-08-22,18:04:42.534 - INFO - threading running +2023-08-22,18:04:42.544 - INFO - threading running +2023-08-22,18:04:42.555 - INFO - threading running +2023-08-22,18:04:42.564 - INFO - threading running +2023-08-22,18:04:42.574 - INFO - threading running +2023-08-22,18:04:42.585 - INFO - threading running +2023-08-22,18:04:42.588 - INFO - ---------------------------------------------------- +2023-08-22,18:04:42.588 - INFO - 18th iteration +2023-08-22,18:04:42.588 - INFO - average ll reward: 0.0563721836 +2023-08-22,18:04:42.588 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:42.595 - INFO - updating finished +2023-08-22,18:04:46.669 - INFO - threading running +2023-08-22,18:04:46.681 - INFO - threading running +2023-08-22,18:04:46.691 - INFO - threading running +2023-08-22,18:04:46.701 - INFO - threading running +2023-08-22,18:04:46.711 - INFO - threading running +2023-08-22,18:04:46.722 - INFO - threading running +2023-08-22,18:04:46.731 - INFO - threading running +2023-08-22,18:04:46.741 - INFO - threading running +2023-08-22,18:04:46.751 - INFO - threading running +2023-08-22,18:04:46.761 - INFO - threading running +2023-08-22,18:04:46.771 - INFO - threading running +2023-08-22,18:04:46.782 - INFO - threading running +2023-08-22,18:04:46.791 - INFO - threading running +2023-08-22,18:04:46.801 - INFO - threading running +2023-08-22,18:04:46.811 - INFO - threading running +2023-08-22,18:04:46.823 - INFO - threading running +2023-08-22,18:04:46.832 - INFO - threading running +2023-08-22,18:04:46.842 - INFO - threading running +2023-08-22,18:04:46.852 - INFO - threading running +2023-08-22,18:04:46.863 - INFO - threading running +2023-08-22,18:04:46.873 - INFO - threading running +2023-08-22,18:04:46.883 - INFO - threading running +2023-08-22,18:04:46.894 - INFO - threading running +2023-08-22,18:04:46.903 - INFO - threading running +2023-08-22,18:04:46.913 - INFO - threading running +2023-08-22,18:04:46.923 - INFO - threading running +2023-08-22,18:04:46.933 - INFO - threading running +2023-08-22,18:04:46.943 - INFO - threading running +2023-08-22,18:04:46.953 - INFO - threading running +2023-08-22,18:04:46.963 - INFO - threading running +2023-08-22,18:04:46.973 - INFO - threading running +2023-08-22,18:04:46.983 - INFO - threading running +2023-08-22,18:04:46.993 - INFO - threading running +2023-08-22,18:04:47.004 - INFO - threading running +2023-08-22,18:04:47.014 - INFO - threading running +2023-08-22,18:04:47.024 - INFO - threading running +2023-08-22,18:04:47.035 - INFO - threading running +2023-08-22,18:04:47.044 - INFO - threading running +2023-08-22,18:04:47.054 - INFO - threading running +2023-08-22,18:04:47.065 - INFO - threading running +2023-08-22,18:04:47.075 - INFO - threading running +2023-08-22,18:04:47.085 - INFO - threading running +2023-08-22,18:04:47.096 - INFO - threading running +2023-08-22,18:04:47.105 - INFO - threading running +2023-08-22,18:04:47.115 - INFO - threading running +2023-08-22,18:04:47.125 - INFO - threading running +2023-08-22,18:04:47.135 - INFO - threading running +2023-08-22,18:04:47.146 - INFO - threading running +2023-08-22,18:04:47.157 - INFO - threading running +2023-08-22,18:04:47.167 - INFO - threading running +2023-08-22,18:04:47.177 - INFO - threading running +2023-08-22,18:04:47.187 - INFO - threading running +2023-08-22,18:04:47.197 - INFO - threading running +2023-08-22,18:04:47.207 - INFO - threading running +2023-08-22,18:04:47.218 - INFO - threading running +2023-08-22,18:04:47.228 - INFO - threading running +2023-08-22,18:04:47.238 - INFO - threading running +2023-08-22,18:04:47.248 - INFO - threading running +2023-08-22,18:04:47.254 - INFO - ---------------------------------------------------- +2023-08-22,18:04:47.255 - INFO - 19th iteration +2023-08-22,18:04:47.255 - INFO - average ll reward: 0.0668730299 +2023-08-22,18:04:47.255 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:47.258 - INFO - updating finished +2023-08-22,18:04:51.345 - INFO - threading running +2023-08-22,18:04:51.352 - INFO - threading running +2023-08-22,18:04:51.363 - INFO - threading running +2023-08-22,18:04:51.373 - INFO - threading running +2023-08-22,18:04:51.383 - INFO - threading running +2023-08-22,18:04:51.394 - INFO - threading running +2023-08-22,18:04:51.403 - INFO - threading running +2023-08-22,18:04:51.413 - INFO - threading running +2023-08-22,18:04:51.423 - INFO - threading running +2023-08-22,18:04:51.434 - INFO - threading running +2023-08-22,18:04:51.443 - INFO - threading running +2023-08-22,18:04:51.453 - INFO - threading running +2023-08-22,18:04:51.463 - INFO - threading running +2023-08-22,18:04:51.473 - INFO - threading running +2023-08-22,18:04:51.484 - INFO - threading running +2023-08-22,18:04:51.493 - INFO - threading running +2023-08-22,18:04:51.503 - INFO - threading running +2023-08-22,18:04:51.513 - INFO - threading running +2023-08-22,18:04:51.523 - INFO - threading running +2023-08-22,18:04:51.533 - INFO - threading running +2023-08-22,18:04:51.543 - INFO - threading running +2023-08-22,18:04:51.553 - INFO - threading running +2023-08-22,18:04:51.563 - INFO - threading running +2023-08-22,18:04:51.574 - INFO - threading running +2023-08-22,18:04:51.584 - INFO - threading running +2023-08-22,18:04:51.594 - INFO - threading running +2023-08-22,18:04:51.604 - INFO - threading running +2023-08-22,18:04:51.615 - INFO - threading running +2023-08-22,18:04:51.624 - INFO - threading running +2023-08-22,18:04:51.634 - INFO - threading running +2023-08-22,18:04:51.644 - INFO - threading running +2023-08-22,18:04:51.654 - INFO - threading running +2023-08-22,18:04:51.664 - INFO - threading running +2023-08-22,18:04:51.674 - INFO - threading running +2023-08-22,18:04:51.684 - INFO - threading running +2023-08-22,18:04:51.695 - INFO - threading running +2023-08-22,18:04:51.704 - INFO - threading running +2023-08-22,18:04:51.714 - INFO - threading running +2023-08-22,18:04:51.724 - INFO - threading running +2023-08-22,18:04:51.734 - INFO - threading running +2023-08-22,18:04:51.745 - INFO - threading running +2023-08-22,18:04:51.755 - INFO - threading running +2023-08-22,18:04:51.765 - INFO - threading running +2023-08-22,18:04:51.775 - INFO - threading running +2023-08-22,18:04:51.786 - INFO - threading running +2023-08-22,18:04:51.797 - INFO - threading running +2023-08-22,18:04:51.806 - INFO - threading running +2023-08-22,18:04:51.816 - INFO - threading running +2023-08-22,18:04:51.826 - INFO - threading running +2023-08-22,18:04:51.836 - INFO - threading running +2023-08-22,18:04:51.847 - INFO - threading running +2023-08-22,18:04:51.856 - INFO - threading running +2023-08-22,18:04:51.866 - INFO - threading running +2023-08-22,18:04:51.876 - INFO - threading running +2023-08-22,18:04:51.887 - INFO - threading running +2023-08-22,18:04:51.897 - INFO - threading running +2023-08-22,18:04:51.904 - INFO - ---------------------------------------------------- +2023-08-22,18:04:51.904 - INFO - 20th iteration +2023-08-22,18:04:51.904 - INFO - average ll reward: 0.0380283327 +2023-08-22,18:04:51.904 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:51.907 - INFO - updating finished +2023-08-22,18:04:55.956 - INFO - threading running +2023-08-22,18:04:55.964 - INFO - threading running +2023-08-22,18:04:55.974 - INFO - threading running +2023-08-22,18:04:55.984 - INFO - threading running +2023-08-22,18:04:55.995 - INFO - threading running +2023-08-22,18:04:56.004 - INFO - threading running +2023-08-22,18:04:56.014 - INFO - threading running +2023-08-22,18:04:56.025 - INFO - threading running +2023-08-22,18:04:56.036 - INFO - threading running +2023-08-22,18:04:56.045 - INFO - threading running +2023-08-22,18:04:56.056 - INFO - threading running +2023-08-22,18:04:56.066 - INFO - threading running +2023-08-22,18:04:56.076 - INFO - threading running +2023-08-22,18:04:56.086 - INFO - threading running +2023-08-22,18:04:56.096 - INFO - threading running +2023-08-22,18:04:56.106 - INFO - threading running +2023-08-22,18:04:56.117 - INFO - threading running +2023-08-22,18:04:56.126 - INFO - threading running +2023-08-22,18:04:56.136 - INFO - threading running +2023-08-22,18:04:56.147 - INFO - threading running +2023-08-22,18:04:56.157 - INFO - threading running +2023-08-22,18:04:56.167 - INFO - threading running +2023-08-22,18:04:56.178 - INFO - threading running +2023-08-22,18:04:56.187 - INFO - threading running +2023-08-22,18:04:56.197 - INFO - threading running +2023-08-22,18:04:56.207 - INFO - threading running +2023-08-22,18:04:56.217 - INFO - threading running +2023-08-22,18:04:56.227 - INFO - threading running +2023-08-22,18:04:56.237 - INFO - threading running +2023-08-22,18:04:56.247 - INFO - threading running +2023-08-22,18:04:56.258 - INFO - threading running +2023-08-22,18:04:56.268 - INFO - threading running +2023-08-22,18:04:56.279 - INFO - threading running +2023-08-22,18:04:56.289 - INFO - threading running +2023-08-22,18:04:56.299 - INFO - threading running +2023-08-22,18:04:56.309 - INFO - threading running +2023-08-22,18:04:56.319 - INFO - threading running +2023-08-22,18:04:56.329 - INFO - threading running +2023-08-22,18:04:56.339 - INFO - threading running +2023-08-22,18:04:56.349 - INFO - threading running +2023-08-22,18:04:56.359 - INFO - threading running +2023-08-22,18:04:56.370 - INFO - threading running +2023-08-22,18:04:56.379 - INFO - threading running +2023-08-22,18:04:56.389 - INFO - threading running +2023-08-22,18:04:56.399 - INFO - threading running +2023-08-22,18:04:56.409 - INFO - threading running +2023-08-22,18:04:56.419 - INFO - threading running +2023-08-22,18:04:56.429 - INFO - threading running +2023-08-22,18:04:56.440 - INFO - threading running +2023-08-22,18:04:56.449 - INFO - threading running +2023-08-22,18:04:56.459 - INFO - threading running +2023-08-22,18:04:56.470 - INFO - threading running +2023-08-22,18:04:56.480 - INFO - threading running +2023-08-22,18:04:56.490 - INFO - threading running +2023-08-22,18:04:56.500 - INFO - threading running +2023-08-22,18:04:56.511 - INFO - threading running +2023-08-22,18:04:56.517 - INFO - ---------------------------------------------------- +2023-08-22,18:04:56.517 - INFO - 21th iteration +2023-08-22,18:04:56.517 - INFO - average ll reward: 0.0661672911 +2023-08-22,18:04:56.518 - INFO - ---------------------------------------------------- + +2023-08-22,18:04:56.521 - INFO - updating finished +2023-08-22,18:05:00.562 - INFO - threading running +2023-08-22,18:05:00.573 - INFO - threading running +2023-08-22,18:05:00.583 - INFO - threading running +2023-08-22,18:05:00.593 - INFO - threading running +2023-08-22,18:05:00.604 - INFO - threading running +2023-08-22,18:05:00.614 - INFO - threading running +2023-08-22,18:05:00.624 - INFO - threading running +2023-08-22,18:05:00.635 - INFO - threading running +2023-08-22,18:05:00.644 - INFO - threading running +2023-08-22,18:05:00.654 - INFO - threading running +2023-08-22,18:05:00.664 - INFO - threading running +2023-08-22,18:05:00.675 - INFO - threading running +2023-08-22,18:05:00.685 - INFO - threading running +2023-08-22,18:05:00.696 - INFO - threading running +2023-08-22,18:05:00.706 - INFO - threading running +2023-08-22,18:05:00.716 - INFO - threading running +2023-08-22,18:05:00.727 - INFO - threading running +2023-08-22,18:05:00.737 - INFO - threading running +2023-08-22,18:05:00.747 - INFO - threading running +2023-08-22,18:05:00.757 - INFO - threading running +2023-08-22,18:05:00.767 - INFO - threading running +2023-08-22,18:05:00.777 - INFO - threading running +2023-08-22,18:05:00.787 - INFO - threading running +2023-08-22,18:05:00.797 - INFO - threading running +2023-08-22,18:05:00.807 - INFO - threading running +2023-08-22,18:05:00.817 - INFO - threading running +2023-08-22,18:05:00.827 - INFO - threading running +2023-08-22,18:05:00.838 - INFO - threading running +2023-08-22,18:05:00.848 - INFO - threading running +2023-08-22,18:05:00.858 - INFO - threading running +2023-08-22,18:05:00.868 - INFO - threading running +2023-08-22,18:05:00.878 - INFO - threading running +2023-08-22,18:05:00.888 - INFO - threading running +2023-08-22,18:05:00.898 - INFO - threading running +2023-08-22,18:05:00.908 - INFO - threading running +2023-08-22,18:05:00.919 - INFO - threading running +2023-08-22,18:05:00.929 - INFO - threading running +2023-08-22,18:05:00.939 - INFO - threading running +2023-08-22,18:05:00.949 - INFO - threading running +2023-08-22,18:05:00.959 - INFO - threading running +2023-08-22,18:05:00.969 - INFO - threading running +2023-08-22,18:05:00.980 - INFO - threading running +2023-08-22,18:05:00.990 - INFO - threading running +2023-08-22,18:05:01.000 - INFO - threading running +2023-08-22,18:05:01.010 - INFO - threading running +2023-08-22,18:05:01.020 - INFO - threading running +2023-08-22,18:05:01.030 - INFO - threading running +2023-08-22,18:05:01.040 - INFO - threading running +2023-08-22,18:05:01.051 - INFO - threading running +2023-08-22,18:05:01.060 - INFO - threading running +2023-08-22,18:05:01.070 - INFO - ---------------------------------------------------- +2023-08-22,18:05:01.070 - INFO - 22th iteration +2023-08-22,18:05:01.070 - INFO - average ll reward: 0.0762766505 +2023-08-22,18:05:01.070 - INFO - threading running +2023-08-22,18:05:01.070 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:01.081 - INFO - updating finished +2023-08-22,18:05:05.172 - INFO - threading running +2023-08-22,18:05:05.185 - INFO - threading running +2023-08-22,18:05:05.195 - INFO - threading running +2023-08-22,18:05:05.205 - INFO - threading running +2023-08-22,18:05:05.216 - INFO - threading running +2023-08-22,18:05:05.225 - INFO - threading running +2023-08-22,18:05:05.235 - INFO - threading running +2023-08-22,18:05:05.245 - INFO - threading running +2023-08-22,18:05:05.256 - INFO - threading running +2023-08-22,18:05:05.266 - INFO - threading running +2023-08-22,18:05:05.277 - INFO - threading running +2023-08-22,18:05:05.286 - INFO - threading running +2023-08-22,18:05:05.296 - INFO - threading running +2023-08-22,18:05:05.306 - INFO - threading running +2023-08-22,18:05:05.316 - INFO - threading running +2023-08-22,18:05:05.327 - INFO - threading running +2023-08-22,18:05:05.336 - INFO - threading running +2023-08-22,18:05:05.346 - INFO - threading running +2023-08-22,18:05:05.356 - INFO - threading running +2023-08-22,18:05:05.366 - INFO - threading running +2023-08-22,18:05:05.376 - INFO - threading running +2023-08-22,18:05:05.386 - INFO - threading running +2023-08-22,18:05:05.396 - INFO - threading running +2023-08-22,18:05:05.406 - INFO - threading running +2023-08-22,18:05:05.416 - INFO - threading running +2023-08-22,18:05:05.426 - INFO - threading running +2023-08-22,18:05:05.436 - INFO - threading running +2023-08-22,18:05:05.446 - INFO - threading running +2023-08-22,18:05:05.456 - INFO - threading running +2023-08-22,18:05:05.466 - INFO - threading running +2023-08-22,18:05:05.476 - INFO - threading running +2023-08-22,18:05:05.486 - INFO - threading running +2023-08-22,18:05:05.496 - INFO - threading running +2023-08-22,18:05:05.506 - INFO - threading running +2023-08-22,18:05:05.516 - INFO - threading running +2023-08-22,18:05:05.527 - INFO - threading running +2023-08-22,18:05:05.537 - INFO - threading running +2023-08-22,18:05:05.547 - INFO - threading running +2023-08-22,18:05:05.557 - INFO - threading running +2023-08-22,18:05:05.567 - INFO - threading running +2023-08-22,18:05:05.578 - INFO - threading running +2023-08-22,18:05:05.587 - INFO - threading running +2023-08-22,18:05:05.597 - INFO - threading running +2023-08-22,18:05:05.607 - INFO - threading running +2023-08-22,18:05:05.617 - INFO - threading running +2023-08-22,18:05:05.627 - INFO - threading running +2023-08-22,18:05:05.637 - INFO - threading running +2023-08-22,18:05:05.647 - INFO - threading running +2023-08-22,18:05:05.658 - INFO - threading running +2023-08-22,18:05:05.668 - INFO - threading running +2023-08-22,18:05:05.672 - INFO - ---------------------------------------------------- +2023-08-22,18:05:05.673 - INFO - 23th iteration +2023-08-22,18:05:05.673 - INFO - average ll reward: 0.0456716058 +2023-08-22,18:05:05.673 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:05.679 - INFO - updating finished +2023-08-22,18:05:09.765 - INFO - threading running +2023-08-22,18:05:09.780 - INFO - threading running +2023-08-22,18:05:09.790 - INFO - threading running +2023-08-22,18:05:09.800 - INFO - threading running +2023-08-22,18:05:09.811 - INFO - threading running +2023-08-22,18:05:09.820 - INFO - threading running +2023-08-22,18:05:09.830 - INFO - threading running +2023-08-22,18:05:09.840 - INFO - threading running +2023-08-22,18:05:09.851 - INFO - threading running +2023-08-22,18:05:09.860 - INFO - threading running +2023-08-22,18:05:09.870 - INFO - threading running +2023-08-22,18:05:09.881 - INFO - threading running +2023-08-22,18:05:09.891 - INFO - threading running +2023-08-22,18:05:09.901 - INFO - threading running +2023-08-22,18:05:09.911 - INFO - threading running +2023-08-22,18:05:09.921 - INFO - threading running +2023-08-22,18:05:09.931 - INFO - threading running +2023-08-22,18:05:09.941 - INFO - threading running +2023-08-22,18:05:09.951 - INFO - threading running +2023-08-22,18:05:09.961 - INFO - threading running +2023-08-22,18:05:09.971 - INFO - threading running +2023-08-22,18:05:09.981 - INFO - threading running +2023-08-22,18:05:09.992 - INFO - threading running +2023-08-22,18:05:10.002 - INFO - threading running +2023-08-22,18:05:10.011 - INFO - threading running +2023-08-22,18:05:10.022 - INFO - threading running +2023-08-22,18:05:10.032 - INFO - threading running +2023-08-22,18:05:10.042 - INFO - threading running +2023-08-22,18:05:10.052 - INFO - threading running +2023-08-22,18:05:10.062 - INFO - threading running +2023-08-22,18:05:10.072 - INFO - threading running +2023-08-22,18:05:10.082 - INFO - threading running +2023-08-22,18:05:10.092 - INFO - threading running +2023-08-22,18:05:10.103 - INFO - threading running +2023-08-22,18:05:10.113 - INFO - threading running +2023-08-22,18:05:10.122 - INFO - threading running +2023-08-22,18:05:10.133 - INFO - threading running +2023-08-22,18:05:10.142 - INFO - threading running +2023-08-22,18:05:10.152 - INFO - threading running +2023-08-22,18:05:10.162 - INFO - threading running +2023-08-22,18:05:10.173 - INFO - threading running +2023-08-22,18:05:10.182 - INFO - threading running +2023-08-22,18:05:10.192 - INFO - threading running +2023-08-22,18:05:10.203 - INFO - threading running +2023-08-22,18:05:10.212 - INFO - threading running +2023-08-22,18:05:10.223 - INFO - threading running +2023-08-22,18:05:10.232 - INFO - threading running +2023-08-22,18:05:10.243 - INFO - threading running +2023-08-22,18:05:10.252 - INFO - threading running +2023-08-22,18:05:10.262 - INFO - threading running +2023-08-22,18:05:10.272 - INFO - threading running +2023-08-22,18:05:10.282 - INFO - threading running +2023-08-22,18:05:10.292 - INFO - threading running +2023-08-22,18:05:10.299 - INFO - ---------------------------------------------------- +2023-08-22,18:05:10.299 - INFO - 24th iteration +2023-08-22,18:05:10.299 - INFO - average ll reward: 0.0621512444 +2023-08-22,18:05:10.299 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:10.302 - INFO - updating finished +2023-08-22,18:05:14.367 - INFO - threading running +2023-08-22,18:05:14.380 - INFO - threading running +2023-08-22,18:05:14.391 - INFO - threading running +2023-08-22,18:05:14.402 - INFO - threading running +2023-08-22,18:05:14.412 - INFO - threading running +2023-08-22,18:05:14.423 - INFO - threading running +2023-08-22,18:05:14.432 - INFO - threading running +2023-08-22,18:05:14.442 - INFO - threading running +2023-08-22,18:05:14.452 - INFO - threading running +2023-08-22,18:05:14.462 - INFO - threading running +2023-08-22,18:05:14.472 - INFO - threading running +2023-08-22,18:05:14.482 - INFO - threading running +2023-08-22,18:05:14.493 - INFO - threading running +2023-08-22,18:05:14.502 - INFO - threading running +2023-08-22,18:05:14.513 - INFO - threading running +2023-08-22,18:05:14.522 - INFO - threading running +2023-08-22,18:05:14.532 - INFO - threading running +2023-08-22,18:05:14.543 - INFO - threading running +2023-08-22,18:05:14.552 - INFO - threading running +2023-08-22,18:05:14.563 - INFO - threading running +2023-08-22,18:05:14.574 - INFO - threading running +2023-08-22,18:05:14.584 - INFO - threading running +2023-08-22,18:05:14.593 - INFO - threading running +2023-08-22,18:05:14.603 - INFO - threading running +2023-08-22,18:05:14.613 - INFO - threading running +2023-08-22,18:05:14.623 - INFO - threading running +2023-08-22,18:05:14.633 - INFO - threading running +2023-08-22,18:05:14.643 - INFO - threading running +2023-08-22,18:05:14.654 - INFO - threading running +2023-08-22,18:05:14.664 - INFO - threading running +2023-08-22,18:05:14.675 - INFO - threading running +2023-08-22,18:05:14.684 - INFO - threading running +2023-08-22,18:05:14.694 - INFO - threading running +2023-08-22,18:05:14.705 - INFO - threading running +2023-08-22,18:05:14.716 - INFO - threading running +2023-08-22,18:05:14.726 - INFO - threading running +2023-08-22,18:05:14.735 - INFO - threading running +2023-08-22,18:05:14.745 - INFO - threading running +2023-08-22,18:05:14.755 - INFO - threading running +2023-08-22,18:05:14.765 - INFO - threading running +2023-08-22,18:05:14.775 - INFO - threading running +2023-08-22,18:05:14.786 - INFO - threading running +2023-08-22,18:05:14.795 - INFO - threading running +2023-08-22,18:05:14.806 - INFO - threading running +2023-08-22,18:05:14.817 - INFO - threading running +2023-08-22,18:05:14.827 - INFO - threading running +2023-08-22,18:05:14.837 - INFO - threading running +2023-08-22,18:05:14.847 - INFO - threading running +2023-08-22,18:05:14.857 - INFO - threading running +2023-08-22,18:05:14.867 - INFO - threading running +2023-08-22,18:05:14.877 - INFO - threading running +2023-08-22,18:05:14.887 - INFO - threading running +2023-08-22,18:05:14.897 - INFO - threading running +2023-08-22,18:05:14.907 - INFO - threading running +2023-08-22,18:05:14.909 - INFO - ---------------------------------------------------- +2023-08-22,18:05:14.910 - INFO - 25th iteration +2023-08-22,18:05:14.910 - INFO - average ll reward: 0.0357220345 +2023-08-22,18:05:14.910 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:14.918 - INFO - updating finished +2023-08-22,18:05:18.999 - INFO - threading running +2023-08-22,18:05:19.012 - INFO - threading running +2023-08-22,18:05:19.023 - INFO - threading running +2023-08-22,18:05:19.032 - INFO - threading running +2023-08-22,18:05:19.042 - INFO - threading running +2023-08-22,18:05:19.053 - INFO - threading running +2023-08-22,18:05:19.062 - INFO - threading running +2023-08-22,18:05:19.072 - INFO - threading running +2023-08-22,18:05:19.082 - INFO - threading running +2023-08-22,18:05:19.092 - INFO - threading running +2023-08-22,18:05:19.102 - INFO - threading running +2023-08-22,18:05:19.113 - INFO - threading running +2023-08-22,18:05:19.123 - INFO - threading running +2023-08-22,18:05:19.133 - INFO - threading running +2023-08-22,18:05:19.143 - INFO - threading running +2023-08-22,18:05:19.154 - INFO - threading running +2023-08-22,18:05:19.163 - INFO - threading running +2023-08-22,18:05:19.173 - INFO - threading running +2023-08-22,18:05:19.183 - INFO - threading running +2023-08-22,18:05:19.193 - INFO - threading running +2023-08-22,18:05:19.203 - INFO - threading running +2023-08-22,18:05:19.213 - INFO - threading running +2023-08-22,18:05:19.224 - INFO - threading running +2023-08-22,18:05:19.233 - INFO - threading running +2023-08-22,18:05:19.243 - INFO - threading running +2023-08-22,18:05:19.253 - INFO - threading running +2023-08-22,18:05:19.263 - INFO - threading running +2023-08-22,18:05:19.273 - INFO - threading running +2023-08-22,18:05:19.283 - INFO - threading running +2023-08-22,18:05:19.293 - INFO - threading running +2023-08-22,18:05:19.304 - INFO - threading running +2023-08-22,18:05:19.314 - INFO - threading running +2023-08-22,18:05:19.324 - INFO - threading running +2023-08-22,18:05:19.334 - INFO - threading running +2023-08-22,18:05:19.345 - INFO - threading running +2023-08-22,18:05:19.354 - INFO - threading running +2023-08-22,18:05:19.364 - INFO - threading running +2023-08-22,18:05:19.374 - INFO - threading running +2023-08-22,18:05:19.385 - INFO - threading running +2023-08-22,18:05:19.395 - INFO - threading running +2023-08-22,18:05:19.405 - INFO - threading running +2023-08-22,18:05:19.415 - INFO - threading running +2023-08-22,18:05:19.426 - INFO - threading running +2023-08-22,18:05:19.436 - INFO - threading running +2023-08-22,18:05:19.446 - INFO - threading running +2023-08-22,18:05:19.456 - INFO - threading running +2023-08-22,18:05:19.466 - INFO - threading running +2023-08-22,18:05:19.477 - INFO - threading running +2023-08-22,18:05:19.486 - INFO - threading running +2023-08-22,18:05:19.496 - INFO - threading running +2023-08-22,18:05:19.506 - INFO - threading running +2023-08-22,18:05:19.516 - INFO - threading running +2023-08-22,18:05:19.527 - INFO - threading running +2023-08-22,18:05:19.537 - INFO - threading running +2023-08-22,18:05:19.548 - INFO - threading running +2023-08-22,18:05:19.558 - INFO - threading running +2023-08-22,18:05:19.568 - INFO - threading running +2023-08-22,18:05:19.578 - INFO - threading running +2023-08-22,18:05:19.584 - INFO - ---------------------------------------------------- +2023-08-22,18:05:19.584 - INFO - 26th iteration +2023-08-22,18:05:19.584 - INFO - average ll reward: 0.0544254147 +2023-08-22,18:05:19.584 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:19.589 - INFO - updating finished +2023-08-22,18:05:23.661 - INFO - threading running +2023-08-22,18:05:23.674 - INFO - threading running +2023-08-22,18:05:23.684 - INFO - threading running +2023-08-22,18:05:23.694 - INFO - threading running +2023-08-22,18:05:23.705 - INFO - threading running +2023-08-22,18:05:23.714 - INFO - threading running +2023-08-22,18:05:23.724 - INFO - threading running +2023-08-22,18:05:23.734 - INFO - threading running +2023-08-22,18:05:23.745 - INFO - threading running +2023-08-22,18:05:23.755 - INFO - threading running +2023-08-22,18:05:23.765 - INFO - threading running +2023-08-22,18:05:23.775 - INFO - threading running +2023-08-22,18:05:23.785 - INFO - threading running +2023-08-22,18:05:23.795 - INFO - threading running +2023-08-22,18:05:23.806 - INFO - threading running +2023-08-22,18:05:23.815 - INFO - threading running +2023-08-22,18:05:23.825 - INFO - threading running +2023-08-22,18:05:23.836 - INFO - threading running +2023-08-22,18:05:23.846 - INFO - threading running +2023-08-22,18:05:23.856 - INFO - threading running +2023-08-22,18:05:23.866 - INFO - threading running +2023-08-22,18:05:23.877 - INFO - threading running +2023-08-22,18:05:23.886 - INFO - threading running +2023-08-22,18:05:23.896 - INFO - threading running +2023-08-22,18:05:23.907 - INFO - threading running +2023-08-22,18:05:23.916 - INFO - threading running +2023-08-22,18:05:23.926 - INFO - threading running +2023-08-22,18:05:23.937 - INFO - threading running +2023-08-22,18:05:23.946 - INFO - threading running +2023-08-22,18:05:23.956 - INFO - threading running +2023-08-22,18:05:23.966 - INFO - threading running +2023-08-22,18:05:23.977 - INFO - threading running +2023-08-22,18:05:23.987 - INFO - threading running +2023-08-22,18:05:23.997 - INFO - threading running +2023-08-22,18:05:24.007 - INFO - threading running +2023-08-22,18:05:24.018 - INFO - threading running +2023-08-22,18:05:24.028 - INFO - threading running +2023-08-22,18:05:24.038 - INFO - threading running +2023-08-22,18:05:24.048 - INFO - threading running +2023-08-22,18:05:24.059 - INFO - threading running +2023-08-22,18:05:24.069 - INFO - threading running +2023-08-22,18:05:24.080 - INFO - threading running +2023-08-22,18:05:24.090 - INFO - threading running +2023-08-22,18:05:24.100 - INFO - threading running +2023-08-22,18:05:24.110 - INFO - threading running +2023-08-22,18:05:24.120 - INFO - threading running +2023-08-22,18:05:24.130 - INFO - threading running +2023-08-22,18:05:24.140 - INFO - threading running +2023-08-22,18:05:24.151 - INFO - threading running +2023-08-22,18:05:24.161 - INFO - threading running +2023-08-22,18:05:24.172 - INFO - threading running +2023-08-22,18:05:24.181 - INFO - threading running +2023-08-22,18:05:24.192 - INFO - threading running +2023-08-22,18:05:24.202 - INFO - threading running +2023-08-22,18:05:24.213 - INFO - threading running +2023-08-22,18:05:24.221 - INFO - ---------------------------------------------------- +2023-08-22,18:05:24.221 - INFO - 27th iteration +2023-08-22,18:05:24.221 - INFO - average ll reward: 0.0736507719 +2023-08-22,18:05:24.221 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:24.223 - INFO - updating finished +2023-08-22,18:05:28.292 - INFO - threading running +2023-08-22,18:05:28.302 - INFO - threading running +2023-08-22,18:05:28.313 - INFO - threading running +2023-08-22,18:05:28.323 - INFO - threading running +2023-08-22,18:05:28.334 - INFO - threading running +2023-08-22,18:05:28.344 - INFO - threading running +2023-08-22,18:05:28.354 - INFO - threading running +2023-08-22,18:05:28.365 - INFO - threading running +2023-08-22,18:05:28.376 - INFO - threading running +2023-08-22,18:05:28.386 - INFO - threading running +2023-08-22,18:05:28.395 - INFO - threading running +2023-08-22,18:05:28.406 - INFO - threading running +2023-08-22,18:05:28.415 - INFO - threading running +2023-08-22,18:05:28.425 - INFO - threading running +2023-08-22,18:05:28.435 - INFO - threading running +2023-08-22,18:05:28.446 - INFO - threading running +2023-08-22,18:05:28.455 - INFO - threading running +2023-08-22,18:05:28.465 - INFO - threading running +2023-08-22,18:05:28.475 - INFO - threading running +2023-08-22,18:05:28.486 - INFO - threading running +2023-08-22,18:05:28.496 - INFO - threading running +2023-08-22,18:05:28.506 - INFO - threading running +2023-08-22,18:05:28.516 - INFO - threading running +2023-08-22,18:05:28.526 - INFO - threading running +2023-08-22,18:05:28.536 - INFO - threading running +2023-08-22,18:05:28.546 - INFO - threading running +2023-08-22,18:05:28.556 - INFO - threading running +2023-08-22,18:05:28.566 - INFO - threading running +2023-08-22,18:05:28.576 - INFO - threading running +2023-08-22,18:05:28.586 - INFO - threading running +2023-08-22,18:05:28.596 - INFO - threading running +2023-08-22,18:05:28.606 - INFO - threading running +2023-08-22,18:05:28.616 - INFO - threading running +2023-08-22,18:05:28.626 - INFO - threading running +2023-08-22,18:05:28.636 - INFO - threading running +2023-08-22,18:05:28.646 - INFO - threading running +2023-08-22,18:05:28.656 - INFO - threading running +2023-08-22,18:05:28.666 - INFO - threading running +2023-08-22,18:05:28.676 - INFO - threading running +2023-08-22,18:05:28.687 - INFO - threading running +2023-08-22,18:05:28.697 - INFO - threading running +2023-08-22,18:05:28.706 - INFO - threading running +2023-08-22,18:05:28.717 - INFO - threading running +2023-08-22,18:05:28.726 - INFO - threading running +2023-08-22,18:05:28.736 - INFO - threading running +2023-08-22,18:05:28.746 - INFO - threading running +2023-08-22,18:05:28.756 - INFO - threading running +2023-08-22,18:05:28.766 - INFO - threading running +2023-08-22,18:05:28.777 - INFO - threading running +2023-08-22,18:05:28.787 - INFO - threading running +2023-08-22,18:05:28.797 - INFO - threading running +2023-08-22,18:05:28.807 - INFO - threading running +2023-08-22,18:05:28.818 - INFO - threading running +2023-08-22,18:05:28.827 - INFO - threading running +2023-08-22,18:05:28.837 - INFO - threading running +2023-08-22,18:05:28.847 - INFO - threading running +2023-08-22,18:05:28.858 - INFO - threading running +2023-08-22,18:05:28.867 - INFO - threading running +2023-08-22,18:05:28.877 - INFO - threading running +2023-08-22,18:05:28.887 - INFO - threading running +2023-08-22,18:05:28.897 - INFO - threading running +2023-08-22,18:05:28.907 - INFO - threading running +2023-08-22,18:05:28.909 - INFO - ---------------------------------------------------- +2023-08-22,18:05:28.910 - INFO - 28th iteration +2023-08-22,18:05:28.910 - INFO - average ll reward: 0.0556717726 +2023-08-22,18:05:28.910 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:28.917 - INFO - updating finished +2023-08-22,18:05:32.982 - INFO - threading running +2023-08-22,18:05:32.994 - INFO - threading running +2023-08-22,18:05:33.003 - INFO - threading running +2023-08-22,18:05:33.013 - INFO - threading running +2023-08-22,18:05:33.023 - INFO - threading running +2023-08-22,18:05:33.034 - INFO - threading running +2023-08-22,18:05:33.043 - INFO - threading running +2023-08-22,18:05:33.053 - INFO - threading running +2023-08-22,18:05:33.064 - INFO - threading running +2023-08-22,18:05:33.074 - INFO - threading running +2023-08-22,18:05:33.084 - INFO - threading running +2023-08-22,18:05:33.095 - INFO - threading running +2023-08-22,18:05:33.104 - INFO - threading running +2023-08-22,18:05:33.114 - INFO - threading running +2023-08-22,18:05:33.124 - INFO - threading running +2023-08-22,18:05:33.134 - INFO - threading running +2023-08-22,18:05:33.144 - INFO - threading running +2023-08-22,18:05:33.154 - INFO - threading running +2023-08-22,18:05:33.164 - INFO - threading running +2023-08-22,18:05:33.174 - INFO - threading running +2023-08-22,18:05:33.184 - INFO - threading running +2023-08-22,18:05:33.195 - INFO - threading running +2023-08-22,18:05:33.204 - INFO - threading running +2023-08-22,18:05:33.215 - INFO - threading running +2023-08-22,18:05:33.224 - INFO - threading running +2023-08-22,18:05:33.234 - INFO - threading running +2023-08-22,18:05:33.244 - INFO - threading running +2023-08-22,18:05:33.254 - INFO - threading running +2023-08-22,18:05:33.265 - INFO - threading running +2023-08-22,18:05:33.276 - INFO - threading running +2023-08-22,18:05:33.285 - INFO - threading running +2023-08-22,18:05:33.296 - INFO - threading running +2023-08-22,18:05:33.305 - INFO - threading running +2023-08-22,18:05:33.315 - INFO - threading running +2023-08-22,18:05:33.325 - INFO - threading running +2023-08-22,18:05:33.335 - INFO - threading running +2023-08-22,18:05:33.346 - INFO - threading running +2023-08-22,18:05:33.356 - INFO - threading running +2023-08-22,18:05:33.366 - INFO - threading running +2023-08-22,18:05:33.376 - INFO - threading running +2023-08-22,18:05:33.386 - INFO - threading running +2023-08-22,18:05:33.396 - INFO - threading running +2023-08-22,18:05:33.406 - INFO - threading running +2023-08-22,18:05:33.416 - INFO - threading running +2023-08-22,18:05:33.426 - INFO - threading running +2023-08-22,18:05:33.436 - INFO - threading running +2023-08-22,18:05:33.446 - INFO - threading running +2023-08-22,18:05:33.457 - INFO - threading running +2023-08-22,18:05:33.467 - INFO - threading running +2023-08-22,18:05:33.477 - INFO - threading running +2023-08-22,18:05:33.487 - INFO - threading running +2023-08-22,18:05:33.497 - INFO - threading running +2023-08-22,18:05:33.507 - INFO - threading running +2023-08-22,18:05:33.517 - INFO - threading running +2023-08-22,18:05:33.527 - INFO - threading running +2023-08-22,18:05:33.537 - INFO - threading running +2023-08-22,18:05:33.547 - INFO - ---------------------------------------------------- +2023-08-22,18:05:33.547 - INFO - 29th iteration +2023-08-22,18:05:33.547 - INFO - average ll reward: 0.0776508413 +2023-08-22,18:05:33.547 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:33.547 - INFO - updating finished +2023-08-22,18:05:37.622 - INFO - threading running +2023-08-22,18:05:37.634 - INFO - threading running +2023-08-22,18:05:37.644 - INFO - threading running +2023-08-22,18:05:37.654 - INFO - threading running +2023-08-22,18:05:37.664 - INFO - threading running +2023-08-22,18:05:37.674 - INFO - threading running +2023-08-22,18:05:37.684 - INFO - threading running +2023-08-22,18:05:37.694 - INFO - threading running +2023-08-22,18:05:37.704 - INFO - threading running +2023-08-22,18:05:37.714 - INFO - threading running +2023-08-22,18:05:37.724 - INFO - threading running +2023-08-22,18:05:37.734 - INFO - threading running +2023-08-22,18:05:37.744 - INFO - threading running +2023-08-22,18:05:37.754 - INFO - threading running +2023-08-22,18:05:37.764 - INFO - threading running +2023-08-22,18:05:37.775 - INFO - threading running +2023-08-22,18:05:37.784 - INFO - threading running +2023-08-22,18:05:37.795 - INFO - threading running +2023-08-22,18:05:37.804 - INFO - threading running +2023-08-22,18:05:37.814 - INFO - threading running +2023-08-22,18:05:37.824 - INFO - threading running +2023-08-22,18:05:37.834 - INFO - threading running +2023-08-22,18:05:37.844 - INFO - threading running +2023-08-22,18:05:37.854 - INFO - threading running +2023-08-22,18:05:37.864 - INFO - threading running +2023-08-22,18:05:37.874 - INFO - threading running +2023-08-22,18:05:37.885 - INFO - threading running +2023-08-22,18:05:37.895 - INFO - threading running +2023-08-22,18:05:37.905 - INFO - threading running +2023-08-22,18:05:37.915 - INFO - threading running +2023-08-22,18:05:37.925 - INFO - threading running +2023-08-22,18:05:37.936 - INFO - threading running +2023-08-22,18:05:37.946 - INFO - threading running +2023-08-22,18:05:37.955 - INFO - threading running +2023-08-22,18:05:37.965 - INFO - threading running +2023-08-22,18:05:37.975 - INFO - threading running +2023-08-22,18:05:37.986 - INFO - threading running +2023-08-22,18:05:37.996 - INFO - threading running +2023-08-22,18:05:38.006 - INFO - threading running +2023-08-22,18:05:38.016 - INFO - threading running +2023-08-22,18:05:38.026 - INFO - threading running +2023-08-22,18:05:38.036 - INFO - threading running +2023-08-22,18:05:38.046 - INFO - threading running +2023-08-22,18:05:38.057 - INFO - threading running +2023-08-22,18:05:38.067 - INFO - threading running +2023-08-22,18:05:38.077 - INFO - threading running +2023-08-22,18:05:38.087 - INFO - threading running +2023-08-22,18:05:38.097 - INFO - threading running +2023-08-22,18:05:38.104 - INFO - ---------------------------------------------------- +2023-08-22,18:05:38.104 - INFO - 30th iteration +2023-08-22,18:05:38.104 - INFO - average ll reward: 0.1098937313 +2023-08-22,18:05:38.105 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:38.107 - INFO - updating finished +2023-08-22,18:05:42.189 - INFO - threading running +2023-08-22,18:05:42.201 - INFO - threading running +2023-08-22,18:05:42.211 - INFO - threading running +2023-08-22,18:05:42.221 - INFO - threading running +2023-08-22,18:05:42.231 - INFO - threading running +2023-08-22,18:05:42.241 - INFO - threading running +2023-08-22,18:05:42.252 - INFO - threading running +2023-08-22,18:05:42.261 - INFO - threading running +2023-08-22,18:05:42.271 - INFO - threading running +2023-08-22,18:05:42.281 - INFO - threading running +2023-08-22,18:05:42.291 - INFO - threading running +2023-08-22,18:05:42.302 - INFO - threading running +2023-08-22,18:05:42.312 - INFO - threading running +2023-08-22,18:05:42.323 - INFO - threading running +2023-08-22,18:05:42.333 - INFO - threading running +2023-08-22,18:05:42.343 - INFO - threading running +2023-08-22,18:05:42.353 - INFO - threading running +2023-08-22,18:05:42.363 - INFO - threading running +2023-08-22,18:05:42.373 - INFO - threading running +2023-08-22,18:05:42.383 - INFO - threading running +2023-08-22,18:05:42.394 - INFO - threading running +2023-08-22,18:05:42.404 - INFO - threading running +2023-08-22,18:05:42.414 - INFO - threading running +2023-08-22,18:05:42.424 - INFO - threading running +2023-08-22,18:05:42.435 - INFO - threading running +2023-08-22,18:05:42.446 - INFO - threading running +2023-08-22,18:05:42.455 - INFO - threading running +2023-08-22,18:05:42.465 - INFO - threading running +2023-08-22,18:05:42.475 - INFO - threading running +2023-08-22,18:05:42.485 - INFO - threading running +2023-08-22,18:05:42.495 - INFO - threading running +2023-08-22,18:05:42.505 - INFO - threading running +2023-08-22,18:05:42.516 - INFO - threading running +2023-08-22,18:05:42.525 - INFO - threading running +2023-08-22,18:05:42.535 - INFO - threading running +2023-08-22,18:05:42.545 - INFO - threading running +2023-08-22,18:05:42.555 - INFO - threading running +2023-08-22,18:05:42.565 - INFO - threading running +2023-08-22,18:05:42.575 - INFO - threading running +2023-08-22,18:05:42.585 - INFO - threading running +2023-08-22,18:05:42.595 - INFO - threading running +2023-08-22,18:05:42.605 - INFO - threading running +2023-08-22,18:05:42.615 - INFO - threading running +2023-08-22,18:05:42.625 - INFO - threading running +2023-08-22,18:05:42.636 - INFO - threading running +2023-08-22,18:05:42.645 - INFO - threading running +2023-08-22,18:05:42.655 - INFO - threading running +2023-08-22,18:05:42.666 - INFO - threading running +2023-08-22,18:05:42.676 - INFO - threading running +2023-08-22,18:05:42.685 - INFO - threading running +2023-08-22,18:05:42.695 - INFO - threading running +2023-08-22,18:05:42.706 - INFO - threading running +2023-08-22,18:05:42.716 - INFO - threading running +2023-08-22,18:05:42.726 - INFO - threading running +2023-08-22,18:05:42.737 - INFO - threading running +2023-08-22,18:05:42.747 - INFO - threading running +2023-08-22,18:05:42.757 - INFO - threading running +2023-08-22,18:05:42.767 - INFO - threading running +2023-08-22,18:05:42.775 - INFO - ---------------------------------------------------- +2023-08-22,18:05:42.775 - INFO - 31th iteration +2023-08-22,18:05:42.775 - INFO - average ll reward: 0.0547023832 +2023-08-22,18:05:42.775 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:42.777 - INFO - updating finished +2023-08-22,18:05:46.885 - INFO - threading running +2023-08-22,18:05:46.898 - INFO - threading running +2023-08-22,18:05:46.908 - INFO - threading running +2023-08-22,18:05:46.918 - INFO - threading running +2023-08-22,18:05:46.928 - INFO - threading running +2023-08-22,18:05:46.939 - INFO - threading running +2023-08-22,18:05:46.948 - INFO - threading running +2023-08-22,18:05:46.959 - INFO - threading running +2023-08-22,18:05:46.970 - INFO - threading running +2023-08-22,18:05:46.981 - INFO - threading running +2023-08-22,18:05:46.992 - INFO - threading running +2023-08-22,18:05:47.001 - INFO - threading running +2023-08-22,18:05:47.011 - INFO - threading running +2023-08-22,18:05:47.021 - INFO - threading running +2023-08-22,18:05:47.031 - INFO - threading running +2023-08-22,18:05:47.041 - INFO - threading running +2023-08-22,18:05:47.052 - INFO - threading running +2023-08-22,18:05:47.063 - INFO - threading running +2023-08-22,18:05:47.072 - INFO - threading running +2023-08-22,18:05:47.082 - INFO - threading running +2023-08-22,18:05:47.093 - INFO - threading running +2023-08-22,18:05:47.102 - INFO - threading running +2023-08-22,18:05:47.113 - INFO - threading running +2023-08-22,18:05:47.123 - INFO - threading running +2023-08-22,18:05:47.133 - INFO - threading running +2023-08-22,18:05:47.143 - INFO - threading running +2023-08-22,18:05:47.154 - INFO - threading running +2023-08-22,18:05:47.163 - INFO - threading running +2023-08-22,18:05:47.173 - INFO - threading running +2023-08-22,18:05:47.184 - INFO - threading running +2023-08-22,18:05:47.194 - INFO - threading running +2023-08-22,18:05:47.205 - INFO - threading running +2023-08-22,18:05:47.215 - INFO - threading running +2023-08-22,18:05:47.225 - INFO - threading running +2023-08-22,18:05:47.236 - INFO - threading running +2023-08-22,18:05:47.246 - INFO - threading running +2023-08-22,18:05:47.256 - INFO - threading running +2023-08-22,18:05:47.267 - INFO - threading running +2023-08-22,18:05:47.277 - INFO - threading running +2023-08-22,18:05:47.286 - INFO - threading running +2023-08-22,18:05:47.296 - INFO - threading running +2023-08-22,18:05:47.307 - INFO - threading running +2023-08-22,18:05:47.316 - INFO - threading running +2023-08-22,18:05:47.326 - INFO - threading running +2023-08-22,18:05:47.336 - INFO - threading running +2023-08-22,18:05:47.346 - INFO - threading running +2023-08-22,18:05:47.356 - INFO - threading running +2023-08-22,18:05:47.366 - INFO - threading running +2023-08-22,18:05:47.377 - INFO - threading running +2023-08-22,18:05:47.387 - INFO - threading running +2023-08-22,18:05:47.390 - INFO - ---------------------------------------------------- +2023-08-22,18:05:47.391 - INFO - 32th iteration +2023-08-22,18:05:47.391 - INFO - average ll reward: 0.0742180259 +2023-08-22,18:05:47.391 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:47.397 - INFO - updating finished +2023-08-22,18:05:51.478 - INFO - threading running +2023-08-22,18:05:51.493 - INFO - threading running +2023-08-22,18:05:51.503 - INFO - threading running +2023-08-22,18:05:51.514 - INFO - threading running +2023-08-22,18:05:51.524 - INFO - threading running +2023-08-22,18:05:51.535 - INFO - threading running +2023-08-22,18:05:51.544 - INFO - threading running +2023-08-22,18:05:51.555 - INFO - threading running +2023-08-22,18:05:51.565 - INFO - threading running +2023-08-22,18:05:51.575 - INFO - threading running +2023-08-22,18:05:51.585 - INFO - threading running +2023-08-22,18:05:51.595 - INFO - threading running +2023-08-22,18:05:51.605 - INFO - threading running +2023-08-22,18:05:51.616 - INFO - threading running +2023-08-22,18:05:51.626 - INFO - threading running +2023-08-22,18:05:51.636 - INFO - threading running +2023-08-22,18:05:51.646 - INFO - threading running +2023-08-22,18:05:51.657 - INFO - threading running +2023-08-22,18:05:51.667 - INFO - threading running +2023-08-22,18:05:51.677 - INFO - threading running +2023-08-22,18:05:51.688 - INFO - threading running +2023-08-22,18:05:51.697 - INFO - threading running +2023-08-22,18:05:51.707 - INFO - threading running +2023-08-22,18:05:51.718 - INFO - threading running +2023-08-22,18:05:51.728 - INFO - threading running +2023-08-22,18:05:51.738 - INFO - threading running +2023-08-22,18:05:51.748 - INFO - threading running +2023-08-22,18:05:51.758 - INFO - threading running +2023-08-22,18:05:51.769 - INFO - threading running +2023-08-22,18:05:51.779 - INFO - threading running +2023-08-22,18:05:51.790 - INFO - threading running +2023-08-22,18:05:51.800 - INFO - threading running +2023-08-22,18:05:51.810 - INFO - threading running +2023-08-22,18:05:51.820 - INFO - threading running +2023-08-22,18:05:51.830 - INFO - threading running +2023-08-22,18:05:51.840 - INFO - threading running +2023-08-22,18:05:51.851 - INFO - threading running +2023-08-22,18:05:51.861 - INFO - threading running +2023-08-22,18:05:51.872 - INFO - threading running +2023-08-22,18:05:51.882 - INFO - threading running +2023-08-22,18:05:51.892 - INFO - threading running +2023-08-22,18:05:51.902 - INFO - threading running +2023-08-22,18:05:51.912 - INFO - threading running +2023-08-22,18:05:51.923 - INFO - threading running +2023-08-22,18:05:51.932 - INFO - threading running +2023-08-22,18:05:51.942 - INFO - threading running +2023-08-22,18:05:51.952 - INFO - threading running +2023-08-22,18:05:51.963 - INFO - threading running +2023-08-22,18:05:51.972 - INFO - threading running +2023-08-22,18:05:51.983 - INFO - threading running +2023-08-22,18:05:51.992 - INFO - threading running +2023-08-22,18:05:52.000 - INFO - ---------------------------------------------------- +2023-08-22,18:05:52.000 - INFO - 33th iteration +2023-08-22,18:05:52.000 - INFO - average ll reward: 0.0957763146 +2023-08-22,18:05:52.000 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:52.002 - INFO - updating finished +2023-08-22,18:05:56.129 - INFO - threading running +2023-08-22,18:05:56.142 - INFO - threading running +2023-08-22,18:05:56.151 - INFO - threading running +2023-08-22,18:05:56.162 - INFO - threading running +2023-08-22,18:05:56.171 - INFO - threading running +2023-08-22,18:05:56.181 - INFO - threading running +2023-08-22,18:05:56.191 - INFO - threading running +2023-08-22,18:05:56.201 - INFO - threading running +2023-08-22,18:05:56.211 - INFO - threading running +2023-08-22,18:05:56.221 - INFO - threading running +2023-08-22,18:05:56.231 - INFO - threading running +2023-08-22,18:05:56.242 - INFO - threading running +2023-08-22,18:05:56.253 - INFO - threading running +2023-08-22,18:05:56.264 - INFO - threading running +2023-08-22,18:05:56.274 - INFO - threading running +2023-08-22,18:05:56.285 - INFO - threading running +2023-08-22,18:05:56.294 - INFO - threading running +2023-08-22,18:05:56.304 - INFO - threading running +2023-08-22,18:05:56.314 - INFO - threading running +2023-08-22,18:05:56.324 - INFO - threading running +2023-08-22,18:05:56.334 - INFO - threading running +2023-08-22,18:05:56.344 - INFO - threading running +2023-08-22,18:05:56.354 - INFO - threading running +2023-08-22,18:05:56.364 - INFO - threading running +2023-08-22,18:05:56.374 - INFO - threading running +2023-08-22,18:05:56.384 - INFO - threading running +2023-08-22,18:05:56.394 - INFO - threading running +2023-08-22,18:05:56.404 - INFO - threading running +2023-08-22,18:05:56.414 - INFO - threading running +2023-08-22,18:05:56.424 - INFO - threading running +2023-08-22,18:05:56.435 - INFO - threading running +2023-08-22,18:05:56.445 - INFO - threading running +2023-08-22,18:05:56.455 - INFO - threading running +2023-08-22,18:05:56.465 - INFO - threading running +2023-08-22,18:05:56.475 - INFO - threading running +2023-08-22,18:05:56.485 - INFO - threading running +2023-08-22,18:05:56.496 - INFO - threading running +2023-08-22,18:05:56.505 - INFO - threading running +2023-08-22,18:05:56.516 - INFO - threading running +2023-08-22,18:05:56.526 - INFO - threading running +2023-08-22,18:05:56.536 - INFO - threading running +2023-08-22,18:05:56.546 - INFO - threading running +2023-08-22,18:05:56.556 - INFO - threading running +2023-08-22,18:05:56.567 - INFO - threading running +2023-08-22,18:05:56.577 - INFO - threading running +2023-08-22,18:05:56.588 - INFO - threading running +2023-08-22,18:05:56.597 - INFO - threading running +2023-08-22,18:05:56.607 - INFO - threading running +2023-08-22,18:05:56.617 - INFO - threading running +2023-08-22,18:05:56.627 - INFO - threading running +2023-08-22,18:05:56.638 - INFO - threading running +2023-08-22,18:05:56.647 - INFO - threading running +2023-08-22,18:05:56.657 - INFO - threading running +2023-08-22,18:05:56.667 - INFO - threading running +2023-08-22,18:05:56.677 - INFO - threading running +2023-08-22,18:05:56.687 - INFO - threading running +2023-08-22,18:05:56.698 - INFO - threading running +2023-08-22,18:05:56.708 - INFO - threading running +2023-08-22,18:05:56.717 - INFO - threading running +2023-08-22,18:05:56.727 - INFO - threading running +2023-08-22,18:05:56.737 - INFO - threading running +2023-08-22,18:05:56.738 - INFO - ---------------------------------------------------- +2023-08-22,18:05:56.739 - INFO - 34th iteration +2023-08-22,18:05:56.739 - INFO - average ll reward: 0.0712858858 +2023-08-22,18:05:56.739 - INFO - ---------------------------------------------------- + +2023-08-22,18:05:56.747 - INFO - updating finished +2023-08-22,18:06:00.873 - INFO - threading running +2023-08-22,18:06:00.888 - INFO - threading running +2023-08-22,18:06:00.898 - INFO - threading running +2023-08-22,18:06:00.909 - INFO - threading running +2023-08-22,18:06:00.919 - INFO - threading running +2023-08-22,18:06:00.930 - INFO - threading running +2023-08-22,18:06:00.939 - INFO - threading running +2023-08-22,18:06:00.949 - INFO - threading running +2023-08-22,18:06:00.959 - INFO - threading running +2023-08-22,18:06:00.970 - INFO - threading running +2023-08-22,18:06:00.979 - INFO - threading running +2023-08-22,18:06:00.990 - INFO - threading running +2023-08-22,18:06:01.001 - INFO - threading running +2023-08-22,18:06:01.011 - INFO - threading running +2023-08-22,18:06:01.021 - INFO - threading running +2023-08-22,18:06:01.031 - INFO - threading running +2023-08-22,18:06:01.041 - INFO - threading running +2023-08-22,18:06:01.052 - INFO - threading running +2023-08-22,18:06:01.062 - INFO - threading running +2023-08-22,18:06:01.072 - INFO - threading running +2023-08-22,18:06:01.083 - INFO - threading running +2023-08-22,18:06:01.092 - INFO - threading running +2023-08-22,18:06:01.103 - INFO - threading running +2023-08-22,18:06:01.113 - INFO - threading running +2023-08-22,18:06:01.124 - INFO - threading running +2023-08-22,18:06:01.133 - INFO - threading running +2023-08-22,18:06:01.143 - INFO - threading running +2023-08-22,18:06:01.153 - INFO - threading running +2023-08-22,18:06:01.163 - INFO - threading running +2023-08-22,18:06:01.173 - INFO - threading running +2023-08-22,18:06:01.183 - INFO - threading running +2023-08-22,18:06:01.193 - INFO - threading running +2023-08-22,18:06:01.203 - INFO - threading running +2023-08-22,18:06:01.214 - INFO - threading running +2023-08-22,18:06:01.224 - INFO - threading running +2023-08-22,18:06:01.234 - INFO - threading running +2023-08-22,18:06:01.245 - INFO - threading running +2023-08-22,18:06:01.255 - INFO - threading running +2023-08-22,18:06:01.265 - INFO - threading running +2023-08-22,18:06:01.275 - INFO - threading running +2023-08-22,18:06:01.286 - INFO - threading running +2023-08-22,18:06:01.296 - INFO - threading running +2023-08-22,18:06:01.306 - INFO - threading running +2023-08-22,18:06:01.316 - INFO - threading running +2023-08-22,18:06:01.327 - INFO - threading running +2023-08-22,18:06:01.336 - INFO - threading running +2023-08-22,18:06:01.346 - INFO - threading running +2023-08-22,18:06:01.357 - INFO - threading running +2023-08-22,18:06:01.367 - INFO - threading running +2023-08-22,18:06:01.377 - INFO - threading running +2023-08-22,18:06:01.387 - INFO - threading running +2023-08-22,18:06:01.397 - INFO - threading running +2023-08-22,18:06:01.407 - INFO - threading running +2023-08-22,18:06:01.417 - INFO - threading running +2023-08-22,18:06:01.427 - INFO - threading running +2023-08-22,18:06:01.437 - INFO - threading running +2023-08-22,18:06:01.447 - INFO - threading running +2023-08-22,18:06:01.457 - INFO - threading running +2023-08-22,18:06:01.467 - INFO - threading running +2023-08-22,18:06:01.477 - INFO - threading running +2023-08-22,18:06:01.483 - INFO - ---------------------------------------------------- +2023-08-22,18:06:01.484 - INFO - 35th iteration +2023-08-22,18:06:01.484 - INFO - average ll reward: 0.0868520612 +2023-08-22,18:06:01.484 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:01.487 - INFO - updating finished +2023-08-22,18:06:05.611 - INFO - threading running +2023-08-22,18:06:05.622 - INFO - threading running +2023-08-22,18:06:05.632 - INFO - threading running +2023-08-22,18:06:05.643 - INFO - threading running +2023-08-22,18:06:05.652 - INFO - threading running +2023-08-22,18:06:05.662 - INFO - threading running +2023-08-22,18:06:05.673 - INFO - threading running +2023-08-22,18:06:05.682 - INFO - threading running +2023-08-22,18:06:05.692 - INFO - threading running +2023-08-22,18:06:05.702 - INFO - threading running +2023-08-22,18:06:05.712 - INFO - threading running +2023-08-22,18:06:05.722 - INFO - threading running +2023-08-22,18:06:05.732 - INFO - threading running +2023-08-22,18:06:05.742 - INFO - threading running +2023-08-22,18:06:05.752 - INFO - threading running +2023-08-22,18:06:05.762 - INFO - threading running +2023-08-22,18:06:05.773 - INFO - threading running +2023-08-22,18:06:05.784 - INFO - threading running +2023-08-22,18:06:05.794 - INFO - threading running +2023-08-22,18:06:05.805 - INFO - threading running +2023-08-22,18:06:05.816 - INFO - threading running +2023-08-22,18:06:05.826 - INFO - threading running +2023-08-22,18:06:05.836 - INFO - threading running +2023-08-22,18:06:05.846 - INFO - threading running +2023-08-22,18:06:05.856 - INFO - threading running +2023-08-22,18:06:05.866 - INFO - threading running +2023-08-22,18:06:05.876 - INFO - threading running +2023-08-22,18:06:05.887 - INFO - threading running +2023-08-22,18:06:05.898 - INFO - threading running +2023-08-22,18:06:05.908 - INFO - threading running +2023-08-22,18:06:05.918 - INFO - threading running +2023-08-22,18:06:05.929 - INFO - threading running +2023-08-22,18:06:05.939 - INFO - threading running +2023-08-22,18:06:05.949 - INFO - threading running +2023-08-22,18:06:05.959 - INFO - threading running +2023-08-22,18:06:05.970 - INFO - threading running +2023-08-22,18:06:05.979 - INFO - threading running +2023-08-22,18:06:05.990 - INFO - threading running +2023-08-22,18:06:05.999 - INFO - threading running +2023-08-22,18:06:06.009 - INFO - threading running +2023-08-22,18:06:06.019 - INFO - threading running +2023-08-22,18:06:06.029 - INFO - threading running +2023-08-22,18:06:06.039 - INFO - threading running +2023-08-22,18:06:06.049 - INFO - threading running +2023-08-22,18:06:06.060 - INFO - threading running +2023-08-22,18:06:06.070 - INFO - threading running +2023-08-22,18:06:06.079 - INFO - threading running +2023-08-22,18:06:06.089 - INFO - threading running +2023-08-22,18:06:06.099 - INFO - threading running +2023-08-22,18:06:06.109 - INFO - threading running +2023-08-22,18:06:06.119 - INFO - threading running +2023-08-22,18:06:06.130 - INFO - threading running +2023-08-22,18:06:06.139 - INFO - threading running +2023-08-22,18:06:06.150 - INFO - threading running +2023-08-22,18:06:06.159 - INFO - threading running +2023-08-22,18:06:06.169 - INFO - threading running +2023-08-22,18:06:06.180 - INFO - threading running +2023-08-22,18:06:06.190 - INFO - threading running +2023-08-22,18:06:06.200 - INFO - threading running +2023-08-22,18:06:06.209 - INFO - threading running +2023-08-22,18:06:06.219 - INFO - threading running +2023-08-22,18:06:06.229 - INFO - threading running +2023-08-22,18:06:06.239 - INFO - threading running +2023-08-22,18:06:06.242 - INFO - ---------------------------------------------------- +2023-08-22,18:06:06.242 - INFO - 36th iteration +2023-08-22,18:06:06.242 - INFO - average ll reward: 0.0668730290 +2023-08-22,18:06:06.242 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:06.250 - INFO - updating finished +2023-08-22,18:06:10.374 - INFO - threading running +2023-08-22,18:06:10.385 - INFO - threading running +2023-08-22,18:06:10.396 - INFO - threading running +2023-08-22,18:06:10.405 - INFO - threading running +2023-08-22,18:06:10.415 - INFO - threading running +2023-08-22,18:06:10.425 - INFO - threading running +2023-08-22,18:06:10.436 - INFO - threading running +2023-08-22,18:06:10.445 - INFO - threading running +2023-08-22,18:06:10.455 - INFO - threading running +2023-08-22,18:06:10.465 - INFO - threading running +2023-08-22,18:06:10.475 - INFO - threading running +2023-08-22,18:06:10.485 - INFO - threading running +2023-08-22,18:06:10.495 - INFO - threading running +2023-08-22,18:06:10.505 - INFO - threading running +2023-08-22,18:06:10.515 - INFO - threading running +2023-08-22,18:06:10.525 - INFO - threading running +2023-08-22,18:06:10.535 - INFO - threading running +2023-08-22,18:06:10.546 - INFO - threading running +2023-08-22,18:06:10.555 - INFO - threading running +2023-08-22,18:06:10.565 - INFO - threading running +2023-08-22,18:06:10.576 - INFO - threading running +2023-08-22,18:06:10.585 - INFO - threading running +2023-08-22,18:06:10.595 - INFO - threading running +2023-08-22,18:06:10.605 - INFO - threading running +2023-08-22,18:06:10.615 - INFO - threading running +2023-08-22,18:06:10.626 - INFO - threading running +2023-08-22,18:06:10.637 - INFO - threading running +2023-08-22,18:06:10.646 - INFO - threading running +2023-08-22,18:06:10.656 - INFO - threading running +2023-08-22,18:06:10.666 - INFO - threading running +2023-08-22,18:06:10.676 - INFO - threading running +2023-08-22,18:06:10.686 - INFO - threading running +2023-08-22,18:06:10.696 - INFO - threading running +2023-08-22,18:06:10.706 - INFO - threading running +2023-08-22,18:06:10.716 - INFO - threading running +2023-08-22,18:06:10.726 - INFO - threading running +2023-08-22,18:06:10.736 - INFO - threading running +2023-08-22,18:06:10.747 - INFO - threading running +2023-08-22,18:06:10.758 - INFO - threading running +2023-08-22,18:06:10.768 - INFO - threading running +2023-08-22,18:06:10.778 - INFO - threading running +2023-08-22,18:06:10.789 - INFO - threading running +2023-08-22,18:06:10.798 - INFO - threading running +2023-08-22,18:06:10.808 - INFO - threading running +2023-08-22,18:06:10.818 - INFO - threading running +2023-08-22,18:06:10.828 - INFO - threading running +2023-08-22,18:06:10.838 - INFO - threading running +2023-08-22,18:06:10.848 - INFO - threading running +2023-08-22,18:06:10.858 - INFO - threading running +2023-08-22,18:06:10.869 - INFO - threading running +2023-08-22,18:06:10.878 - INFO - threading running +2023-08-22,18:06:10.888 - INFO - threading running +2023-08-22,18:06:10.899 - INFO - threading running +2023-08-22,18:06:10.908 - INFO - threading running +2023-08-22,18:06:10.918 - INFO - threading running +2023-08-22,18:06:10.928 - INFO - threading running +2023-08-22,18:06:10.939 - INFO - threading running +2023-08-22,18:06:10.949 - INFO - threading running +2023-08-22,18:06:10.958 - INFO - threading running +2023-08-22,18:06:10.969 - INFO - threading running +2023-08-22,18:06:10.978 - INFO - threading running +2023-08-22,18:06:10.988 - INFO - threading running +2023-08-22,18:06:10.998 - INFO - threading running +2023-08-22,18:06:11.001 - INFO - ---------------------------------------------------- +2023-08-22,18:06:11.001 - INFO - 37th iteration +2023-08-22,18:06:11.001 - INFO - average ll reward: 0.1062878110 +2023-08-22,18:06:11.001 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:11.008 - INFO - updating finished +2023-08-22,18:06:15.089 - INFO - threading running +2023-08-22,18:06:15.101 - INFO - threading running +2023-08-22,18:06:15.112 - INFO - threading running +2023-08-22,18:06:15.122 - INFO - threading running +2023-08-22,18:06:15.132 - INFO - threading running +2023-08-22,18:06:15.142 - INFO - threading running +2023-08-22,18:06:15.152 - INFO - threading running +2023-08-22,18:06:15.163 - INFO - threading running +2023-08-22,18:06:15.173 - INFO - threading running +2023-08-22,18:06:15.183 - INFO - threading running +2023-08-22,18:06:15.193 - INFO - threading running +2023-08-22,18:06:15.204 - INFO - threading running +2023-08-22,18:06:15.214 - INFO - threading running +2023-08-22,18:06:15.225 - INFO - threading running +2023-08-22,18:06:15.235 - INFO - threading running +2023-08-22,18:06:15.245 - INFO - threading running +2023-08-22,18:06:15.255 - INFO - threading running +2023-08-22,18:06:15.266 - INFO - threading running +2023-08-22,18:06:15.275 - INFO - threading running +2023-08-22,18:06:15.285 - INFO - threading running +2023-08-22,18:06:15.295 - INFO - threading running +2023-08-22,18:06:15.305 - INFO - threading running +2023-08-22,18:06:15.315 - INFO - threading running +2023-08-22,18:06:15.326 - INFO - threading running +2023-08-22,18:06:15.336 - INFO - threading running +2023-08-22,18:06:15.346 - INFO - threading running +2023-08-22,18:06:15.356 - INFO - threading running +2023-08-22,18:06:15.366 - INFO - threading running +2023-08-22,18:06:15.376 - INFO - threading running +2023-08-22,18:06:15.386 - INFO - threading running +2023-08-22,18:06:15.397 - INFO - threading running +2023-08-22,18:06:15.407 - INFO - threading running +2023-08-22,18:06:15.416 - INFO - threading running +2023-08-22,18:06:15.426 - INFO - threading running +2023-08-22,18:06:15.436 - INFO - threading running +2023-08-22,18:06:15.446 - INFO - threading running +2023-08-22,18:06:15.456 - INFO - threading running +2023-08-22,18:06:15.466 - INFO - threading running +2023-08-22,18:06:15.476 - INFO - threading running +2023-08-22,18:06:15.486 - INFO - threading running +2023-08-22,18:06:15.497 - INFO - threading running +2023-08-22,18:06:15.507 - INFO - threading running +2023-08-22,18:06:15.518 - INFO - threading running +2023-08-22,18:06:15.527 - INFO - threading running +2023-08-22,18:06:15.537 - INFO - threading running +2023-08-22,18:06:15.547 - INFO - threading running +2023-08-22,18:06:15.557 - INFO - threading running +2023-08-22,18:06:15.567 - INFO - threading running +2023-08-22,18:06:15.577 - INFO - threading running +2023-08-22,18:06:15.587 - INFO - threading running +2023-08-22,18:06:15.598 - INFO - threading running +2023-08-22,18:06:15.609 - INFO - threading running +2023-08-22,18:06:15.618 - INFO - threading running +2023-08-22,18:06:15.628 - INFO - threading running +2023-08-22,18:06:15.639 - INFO - threading running +2023-08-22,18:06:15.650 - INFO - threading running +2023-08-22,18:06:15.657 - INFO - ---------------------------------------------------- +2023-08-22,18:06:15.657 - INFO - 38th iteration +2023-08-22,18:06:15.657 - INFO - average ll reward: 0.0664842076 +2023-08-22,18:06:15.657 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:15.659 - INFO - updating finished +2023-08-22,18:06:19.706 - INFO - threading running +2023-08-22,18:06:19.720 - INFO - threading running +2023-08-22,18:06:19.730 - INFO - threading running +2023-08-22,18:06:19.740 - INFO - threading running +2023-08-22,18:06:19.750 - INFO - threading running +2023-08-22,18:06:19.760 - INFO - threading running +2023-08-22,18:06:19.770 - INFO - threading running +2023-08-22,18:06:19.781 - INFO - threading running +2023-08-22,18:06:19.790 - INFO - threading running +2023-08-22,18:06:19.800 - INFO - threading running +2023-08-22,18:06:19.811 - INFO - threading running +2023-08-22,18:06:19.820 - INFO - threading running +2023-08-22,18:06:19.830 - INFO - threading running +2023-08-22,18:06:19.840 - INFO - threading running +2023-08-22,18:06:19.850 - INFO - threading running +2023-08-22,18:06:19.860 - INFO - threading running +2023-08-22,18:06:19.870 - INFO - threading running +2023-08-22,18:06:19.881 - INFO - threading running +2023-08-22,18:06:19.890 - INFO - threading running +2023-08-22,18:06:19.900 - INFO - threading running +2023-08-22,18:06:19.911 - INFO - threading running +2023-08-22,18:06:19.920 - INFO - threading running +2023-08-22,18:06:19.930 - INFO - threading running +2023-08-22,18:06:19.940 - INFO - threading running +2023-08-22,18:06:19.950 - INFO - threading running +2023-08-22,18:06:19.960 - INFO - threading running +2023-08-22,18:06:19.970 - INFO - threading running +2023-08-22,18:06:19.981 - INFO - threading running +2023-08-22,18:06:19.990 - INFO - threading running +2023-08-22,18:06:20.001 - INFO - threading running +2023-08-22,18:06:20.010 - INFO - threading running +2023-08-22,18:06:20.020 - INFO - threading running +2023-08-22,18:06:20.030 - INFO - threading running +2023-08-22,18:06:20.040 - INFO - threading running +2023-08-22,18:06:20.050 - INFO - threading running +2023-08-22,18:06:20.060 - INFO - threading running +2023-08-22,18:06:20.070 - INFO - threading running +2023-08-22,18:06:20.081 - INFO - threading running +2023-08-22,18:06:20.090 - INFO - threading running +2023-08-22,18:06:20.100 - INFO - threading running +2023-08-22,18:06:20.110 - INFO - threading running +2023-08-22,18:06:20.120 - INFO - threading running +2023-08-22,18:06:20.130 - INFO - threading running +2023-08-22,18:06:20.141 - INFO - threading running +2023-08-22,18:06:20.150 - INFO - threading running +2023-08-22,18:06:20.160 - INFO - threading running +2023-08-22,18:06:20.170 - INFO - threading running +2023-08-22,18:06:20.180 - INFO - threading running +2023-08-22,18:06:20.190 - INFO - threading running +2023-08-22,18:06:20.200 - INFO - threading running +2023-08-22,18:06:20.210 - INFO - threading running +2023-08-22,18:06:20.220 - INFO - threading running +2023-08-22,18:06:20.230 - INFO - threading running +2023-08-22,18:06:20.240 - INFO - threading running +2023-08-22,18:06:20.250 - INFO - threading running +2023-08-22,18:06:20.260 - INFO - threading running +2023-08-22,18:06:20.270 - INFO - threading running +2023-08-22,18:06:20.280 - INFO - threading running +2023-08-22,18:06:20.290 - INFO - threading running +2023-08-22,18:06:20.300 - INFO - threading running +2023-08-22,18:06:20.305 - INFO - ---------------------------------------------------- +2023-08-22,18:06:20.305 - INFO - 39th iteration +2023-08-22,18:06:20.305 - INFO - average ll reward: 0.1011239419 +2023-08-22,18:06:20.305 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:20.310 - INFO - updating finished +2023-08-22,18:06:24.357 - INFO - threading running +2023-08-22,18:06:24.370 - INFO - threading running +2023-08-22,18:06:24.380 - INFO - threading running +2023-08-22,18:06:24.390 - INFO - threading running +2023-08-22,18:06:24.400 - INFO - threading running +2023-08-22,18:06:24.411 - INFO - threading running +2023-08-22,18:06:24.421 - INFO - threading running +2023-08-22,18:06:24.431 - INFO - threading running +2023-08-22,18:06:24.441 - INFO - threading running +2023-08-22,18:06:24.451 - INFO - threading running +2023-08-22,18:06:24.461 - INFO - threading running +2023-08-22,18:06:24.471 - INFO - threading running +2023-08-22,18:06:24.481 - INFO - threading running +2023-08-22,18:06:24.491 - INFO - threading running +2023-08-22,18:06:24.502 - INFO - threading running +2023-08-22,18:06:24.511 - INFO - threading running +2023-08-22,18:06:24.521 - INFO - threading running +2023-08-22,18:06:24.531 - INFO - threading running +2023-08-22,18:06:24.541 - INFO - threading running +2023-08-22,18:06:24.551 - INFO - threading running +2023-08-22,18:06:24.561 - INFO - threading running +2023-08-22,18:06:24.571 - INFO - threading running +2023-08-22,18:06:24.581 - INFO - threading running +2023-08-22,18:06:24.592 - INFO - threading running +2023-08-22,18:06:24.601 - INFO - threading running +2023-08-22,18:06:24.611 - INFO - threading running +2023-08-22,18:06:24.622 - INFO - threading running +2023-08-22,18:06:24.632 - INFO - threading running +2023-08-22,18:06:24.642 - INFO - threading running +2023-08-22,18:06:24.653 - INFO - threading running +2023-08-22,18:06:24.663 - INFO - threading running +2023-08-22,18:06:24.673 - INFO - threading running +2023-08-22,18:06:24.683 - INFO - threading running +2023-08-22,18:06:24.693 - INFO - threading running +2023-08-22,18:06:24.704 - INFO - threading running +2023-08-22,18:06:24.714 - INFO - threading running +2023-08-22,18:06:24.724 - INFO - threading running +2023-08-22,18:06:24.734 - INFO - threading running +2023-08-22,18:06:24.744 - INFO - threading running +2023-08-22,18:06:24.754 - INFO - threading running +2023-08-22,18:06:24.764 - INFO - threading running +2023-08-22,18:06:24.775 - INFO - threading running +2023-08-22,18:06:24.785 - INFO - threading running +2023-08-22,18:06:24.795 - INFO - threading running +2023-08-22,18:06:24.805 - INFO - threading running +2023-08-22,18:06:24.815 - INFO - threading running +2023-08-22,18:06:24.825 - INFO - threading running +2023-08-22,18:06:24.835 - INFO - threading running +2023-08-22,18:06:24.846 - INFO - threading running +2023-08-22,18:06:24.855 - INFO - threading running +2023-08-22,18:06:24.865 - INFO - threading running +2023-08-22,18:06:24.875 - INFO - threading running +2023-08-22,18:06:24.885 - INFO - threading running +2023-08-22,18:06:24.895 - INFO - threading running +2023-08-22,18:06:24.905 - INFO - threading running +2023-08-22,18:06:24.915 - INFO - threading running +2023-08-22,18:06:24.925 - INFO - threading running +2023-08-22,18:06:24.935 - INFO - threading running +2023-08-22,18:06:24.947 - INFO - threading running +2023-08-22,18:06:24.960 - INFO - threading running +2023-08-22,18:06:24.971 - INFO - threading running +2023-08-22,18:06:24.980 - INFO - threading running +2023-08-22,18:06:24.990 - INFO - threading running +2023-08-22,18:06:25.003 - INFO - threading running +2023-08-22,18:06:25.016 - INFO - threading running +2023-08-22,18:06:25.064 - INFO - threading running +2023-08-22,18:06:25.099 - INFO - threading running +2023-08-22,18:06:25.111 - INFO - threading running +2023-08-22,18:06:25.155 - INFO - threading running +2023-08-22,18:06:25.197 - INFO - threading running +2023-08-22,18:06:25.207 - INFO - threading running +2023-08-22,18:06:25.218 - INFO - threading running +2023-08-22,18:06:25.289 - INFO - threading running +2023-08-22,18:06:25.300 - INFO - threading running +2023-08-22,18:06:25.311 - INFO - threading running +2023-08-22,18:06:25.380 - INFO - threading running +2023-08-22,18:06:25.390 - INFO - threading running +2023-08-22,18:06:25.407 - INFO - threading running +2023-08-22,18:06:25.450 - INFO - threading running +2023-08-22,18:06:25.490 - INFO - threading running +2023-08-22,18:06:25.500 - INFO - threading running +2023-08-22,18:06:25.510 - INFO - threading running +2023-08-22,18:06:25.531 - INFO - threading running +2023-08-22,18:06:25.546 - INFO - threading running +2023-08-22,18:06:25.556 - INFO - threading running +2023-08-22,18:06:25.566 - INFO - threading running +2023-08-22,18:06:25.570 - INFO - ---------------------------------------------------- +2023-08-22,18:06:25.570 - INFO - 40th iteration +2023-08-22,18:06:25.570 - INFO - average ll reward: 0.1098724256 +2023-08-22,18:06:25.570 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:25.576 - INFO - updating finished +2023-08-22,18:06:29.633 - INFO - threading running +2023-08-22,18:06:29.646 - INFO - threading running +2023-08-22,18:06:29.656 - INFO - threading running +2023-08-22,18:06:29.666 - INFO - threading running +2023-08-22,18:06:29.677 - INFO - threading running +2023-08-22,18:06:29.687 - INFO - threading running +2023-08-22,18:06:29.697 - INFO - threading running +2023-08-22,18:06:29.707 - INFO - threading running +2023-08-22,18:06:29.718 - INFO - threading running +2023-08-22,18:06:29.728 - INFO - threading running +2023-08-22,18:06:29.738 - INFO - threading running +2023-08-22,18:06:29.748 - INFO - threading running +2023-08-22,18:06:29.758 - INFO - threading running +2023-08-22,18:06:29.768 - INFO - threading running +2023-08-22,18:06:29.779 - INFO - threading running +2023-08-22,18:06:29.790 - INFO - threading running +2023-08-22,18:06:29.800 - INFO - threading running +2023-08-22,18:06:29.810 - INFO - threading running +2023-08-22,18:06:29.820 - INFO - threading running +2023-08-22,18:06:29.831 - INFO - threading running +2023-08-22,18:06:29.842 - INFO - threading running +2023-08-22,18:06:29.852 - INFO - threading running +2023-08-22,18:06:29.862 - INFO - threading running +2023-08-22,18:06:29.872 - INFO - threading running +2023-08-22,18:06:29.883 - INFO - threading running +2023-08-22,18:06:29.893 - INFO - threading running +2023-08-22,18:06:29.902 - INFO - threading running +2023-08-22,18:06:29.912 - INFO - threading running +2023-08-22,18:06:29.922 - INFO - threading running +2023-08-22,18:06:29.933 - INFO - threading running +2023-08-22,18:06:29.942 - INFO - threading running +2023-08-22,18:06:29.953 - INFO - threading running +2023-08-22,18:06:29.964 - INFO - threading running +2023-08-22,18:06:29.974 - INFO - threading running +2023-08-22,18:06:29.984 - INFO - threading running +2023-08-22,18:06:29.993 - INFO - threading running +2023-08-22,18:06:30.003 - INFO - threading running +2023-08-22,18:06:30.013 - INFO - threading running +2023-08-22,18:06:30.023 - INFO - threading running +2023-08-22,18:06:30.033 - INFO - threading running +2023-08-22,18:06:30.043 - INFO - threading running +2023-08-22,18:06:30.053 - INFO - threading running +2023-08-22,18:06:30.064 - INFO - threading running +2023-08-22,18:06:30.073 - INFO - threading running +2023-08-22,18:06:30.083 - INFO - threading running +2023-08-22,18:06:30.093 - INFO - threading running +2023-08-22,18:06:30.104 - INFO - threading running +2023-08-22,18:06:30.114 - INFO - threading running +2023-08-22,18:06:30.124 - INFO - threading running +2023-08-22,18:06:30.134 - INFO - threading running +2023-08-22,18:06:30.144 - INFO - threading running +2023-08-22,18:06:30.154 - INFO - threading running +2023-08-22,18:06:30.159 - INFO - ---------------------------------------------------- +2023-08-22,18:06:30.159 - INFO - 41th iteration +2023-08-22,18:06:30.159 - INFO - average ll reward: 0.0971744745 +2023-08-22,18:06:30.159 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:30.164 - INFO - updating finished +2023-08-22,18:06:34.268 - INFO - threading running +2023-08-22,18:06:34.281 - INFO - threading running +2023-08-22,18:06:34.292 - INFO - threading running +2023-08-22,18:06:34.303 - INFO - threading running +2023-08-22,18:06:34.312 - INFO - threading running +2023-08-22,18:06:34.322 - INFO - threading running +2023-08-22,18:06:34.333 - INFO - threading running +2023-08-22,18:06:34.343 - INFO - threading running +2023-08-22,18:06:34.352 - INFO - threading running +2023-08-22,18:06:34.362 - INFO - threading running +2023-08-22,18:06:34.372 - INFO - threading running +2023-08-22,18:06:34.382 - INFO - threading running +2023-08-22,18:06:34.392 - INFO - threading running +2023-08-22,18:06:34.402 - INFO - threading running +2023-08-22,18:06:34.412 - INFO - threading running +2023-08-22,18:06:34.422 - INFO - threading running +2023-08-22,18:06:34.432 - INFO - threading running +2023-08-22,18:06:34.442 - INFO - threading running +2023-08-22,18:06:34.452 - INFO - threading running +2023-08-22,18:06:34.462 - INFO - threading running +2023-08-22,18:06:34.472 - INFO - threading running +2023-08-22,18:06:34.482 - INFO - threading running +2023-08-22,18:06:34.492 - INFO - threading running +2023-08-22,18:06:34.502 - INFO - threading running +2023-08-22,18:06:34.513 - INFO - threading running +2023-08-22,18:06:34.523 - INFO - threading running +2023-08-22,18:06:34.533 - INFO - threading running +2023-08-22,18:06:34.543 - INFO - threading running +2023-08-22,18:06:34.553 - INFO - threading running +2023-08-22,18:06:34.563 - INFO - threading running +2023-08-22,18:06:34.573 - INFO - threading running +2023-08-22,18:06:34.583 - INFO - threading running +2023-08-22,18:06:34.593 - INFO - threading running +2023-08-22,18:06:34.603 - INFO - threading running +2023-08-22,18:06:34.613 - INFO - threading running +2023-08-22,18:06:34.624 - INFO - threading running +2023-08-22,18:06:34.634 - INFO - threading running +2023-08-22,18:06:34.645 - INFO - threading running +2023-08-22,18:06:34.656 - INFO - threading running +2023-08-22,18:06:34.666 - INFO - threading running +2023-08-22,18:06:34.676 - INFO - threading running +2023-08-22,18:06:34.687 - INFO - threading running +2023-08-22,18:06:34.696 - INFO - threading running +2023-08-22,18:06:34.707 - INFO - threading running +2023-08-22,18:06:34.717 - INFO - threading running +2023-08-22,18:06:34.727 - INFO - threading running +2023-08-22,18:06:34.737 - INFO - threading running +2023-08-22,18:06:34.747 - INFO - threading running +2023-08-22,18:06:34.757 - INFO - threading running +2023-08-22,18:06:34.767 - INFO - threading running +2023-08-22,18:06:34.777 - INFO - threading running +2023-08-22,18:06:34.787 - INFO - threading running +2023-08-22,18:06:34.798 - INFO - threading running +2023-08-22,18:06:34.807 - INFO - threading running +2023-08-22,18:06:34.817 - INFO - threading running +2023-08-22,18:06:34.827 - INFO - threading running +2023-08-22,18:06:34.838 - INFO - threading running +2023-08-22,18:06:34.847 - INFO - ---------------------------------------------------- +2023-08-22,18:06:34.847 - INFO - 42th iteration +2023-08-22,18:06:34.847 - INFO - average ll reward: 0.1344720458 +2023-08-22,18:06:34.847 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:34.849 - INFO - updating finished +2023-08-22,18:06:39.005 - INFO - threading running +2023-08-22,18:06:39.019 - INFO - threading running +2023-08-22,18:06:39.030 - INFO - threading running +2023-08-22,18:06:39.039 - INFO - threading running +2023-08-22,18:06:39.049 - INFO - threading running +2023-08-22,18:06:39.059 - INFO - threading running +2023-08-22,18:06:39.070 - INFO - threading running +2023-08-22,18:06:39.081 - INFO - threading running +2023-08-22,18:06:39.092 - INFO - threading running +2023-08-22,18:06:39.101 - INFO - threading running +2023-08-22,18:06:39.111 - INFO - threading running +2023-08-22,18:06:39.121 - INFO - threading running +2023-08-22,18:06:39.131 - INFO - threading running +2023-08-22,18:06:39.141 - INFO - threading running +2023-08-22,18:06:39.152 - INFO - threading running +2023-08-22,18:06:39.161 - INFO - threading running +2023-08-22,18:06:39.171 - INFO - threading running +2023-08-22,18:06:39.182 - INFO - threading running +2023-08-22,18:06:39.192 - INFO - threading running +2023-08-22,18:06:39.202 - INFO - threading running +2023-08-22,18:06:39.212 - INFO - threading running +2023-08-22,18:06:39.222 - INFO - threading running +2023-08-22,18:06:39.232 - INFO - threading running +2023-08-22,18:06:39.242 - INFO - threading running +2023-08-22,18:06:39.252 - INFO - threading running +2023-08-22,18:06:39.262 - INFO - threading running +2023-08-22,18:06:39.272 - INFO - threading running +2023-08-22,18:06:39.282 - INFO - threading running +2023-08-22,18:06:39.292 - INFO - threading running +2023-08-22,18:06:39.302 - INFO - threading running +2023-08-22,18:06:39.313 - INFO - threading running +2023-08-22,18:06:39.324 - INFO - threading running +2023-08-22,18:06:39.333 - INFO - threading running +2023-08-22,18:06:39.344 - INFO - threading running +2023-08-22,18:06:39.353 - INFO - threading running +2023-08-22,18:06:39.363 - INFO - threading running +2023-08-22,18:06:39.374 - INFO - threading running +2023-08-22,18:06:39.384 - INFO - threading running +2023-08-22,18:06:39.393 - INFO - threading running +2023-08-22,18:06:39.403 - INFO - threading running +2023-08-22,18:06:39.414 - INFO - threading running +2023-08-22,18:06:39.423 - INFO - threading running +2023-08-22,18:06:39.433 - INFO - threading running +2023-08-22,18:06:39.444 - INFO - threading running +2023-08-22,18:06:39.453 - INFO - threading running +2023-08-22,18:06:39.463 - INFO - threading running +2023-08-22,18:06:39.473 - INFO - threading running +2023-08-22,18:06:39.484 - INFO - threading running +2023-08-22,18:06:39.495 - INFO - threading running +2023-08-22,18:06:39.505 - INFO - threading running +2023-08-22,18:06:39.515 - INFO - threading running +2023-08-22,18:06:39.525 - INFO - threading running +2023-08-22,18:06:39.535 - INFO - threading running +2023-08-22,18:06:39.542 - INFO - ---------------------------------------------------- +2023-08-22,18:06:39.542 - INFO - 43th iteration +2023-08-22,18:06:39.542 - INFO - average ll reward: 0.0792593901 +2023-08-22,18:06:39.542 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:39.545 - INFO - updating finished +2023-08-22,18:06:43.705 - INFO - threading running +2023-08-22,18:06:43.712 - INFO - threading running +2023-08-22,18:06:43.722 - INFO - threading running +2023-08-22,18:06:43.732 - INFO - threading running +2023-08-22,18:06:43.742 - INFO - threading running +2023-08-22,18:06:43.752 - INFO - threading running +2023-08-22,18:06:43.762 - INFO - threading running +2023-08-22,18:06:43.773 - INFO - threading running +2023-08-22,18:06:43.782 - INFO - threading running +2023-08-22,18:06:43.792 - INFO - threading running +2023-08-22,18:06:43.802 - INFO - threading running +2023-08-22,18:06:43.813 - INFO - threading running +2023-08-22,18:06:43.823 - INFO - threading running +2023-08-22,18:06:43.834 - INFO - threading running +2023-08-22,18:06:43.843 - INFO - threading running +2023-08-22,18:06:43.853 - INFO - threading running +2023-08-22,18:06:43.863 - INFO - threading running +2023-08-22,18:06:43.874 - INFO - threading running +2023-08-22,18:06:43.883 - INFO - threading running +2023-08-22,18:06:43.893 - INFO - threading running +2023-08-22,18:06:43.903 - INFO - threading running +2023-08-22,18:06:43.913 - INFO - threading running +2023-08-22,18:06:43.923 - INFO - threading running +2023-08-22,18:06:43.933 - INFO - threading running +2023-08-22,18:06:43.943 - INFO - threading running +2023-08-22,18:06:43.954 - INFO - threading running +2023-08-22,18:06:43.964 - INFO - threading running +2023-08-22,18:06:43.974 - INFO - threading running +2023-08-22,18:06:43.984 - INFO - threading running +2023-08-22,18:06:43.995 - INFO - threading running +2023-08-22,18:06:44.006 - INFO - threading running +2023-08-22,18:06:44.016 - INFO - threading running +2023-08-22,18:06:44.027 - INFO - threading running +2023-08-22,18:06:44.036 - INFO - threading running +2023-08-22,18:06:44.047 - INFO - threading running +2023-08-22,18:06:44.057 - INFO - threading running +2023-08-22,18:06:44.068 - INFO - threading running +2023-08-22,18:06:44.078 - INFO - threading running +2023-08-22,18:06:44.088 - INFO - threading running +2023-08-22,18:06:44.098 - INFO - threading running +2023-08-22,18:06:44.108 - INFO - threading running +2023-08-22,18:06:44.118 - INFO - threading running +2023-08-22,18:06:44.128 - INFO - threading running +2023-08-22,18:06:44.138 - INFO - threading running +2023-08-22,18:06:44.148 - INFO - threading running +2023-08-22,18:06:44.158 - INFO - threading running +2023-08-22,18:06:44.168 - INFO - threading running +2023-08-22,18:06:44.178 - INFO - threading running +2023-08-22,18:06:44.188 - INFO - threading running +2023-08-22,18:06:44.199 - INFO - threading running +2023-08-22,18:06:44.202 - INFO - ---------------------------------------------------- +2023-08-22,18:06:44.202 - INFO - 44th iteration +2023-08-22,18:06:44.202 - INFO - average ll reward: 0.0964261261 +2023-08-22,18:06:44.203 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:44.208 - INFO - updating finished +2023-08-22,18:06:48.286 - INFO - threading running +2023-08-22,18:06:48.298 - INFO - threading running +2023-08-22,18:06:48.309 - INFO - threading running +2023-08-22,18:06:48.320 - INFO - threading running +2023-08-22,18:06:48.331 - INFO - threading running +2023-08-22,18:06:48.340 - INFO - threading running +2023-08-22,18:06:48.350 - INFO - threading running +2023-08-22,18:06:48.360 - INFO - threading running +2023-08-22,18:06:48.370 - INFO - threading running +2023-08-22,18:06:48.380 - INFO - threading running +2023-08-22,18:06:48.390 - INFO - threading running +2023-08-22,18:06:48.400 - INFO - threading running +2023-08-22,18:06:48.410 - INFO - threading running +2023-08-22,18:06:48.421 - INFO - threading running +2023-08-22,18:06:48.430 - INFO - threading running +2023-08-22,18:06:48.440 - INFO - threading running +2023-08-22,18:06:48.451 - INFO - threading running +2023-08-22,18:06:48.462 - INFO - threading running +2023-08-22,18:06:48.471 - INFO - threading running +2023-08-22,18:06:48.482 - INFO - threading running +2023-08-22,18:06:48.491 - INFO - threading running +2023-08-22,18:06:48.501 - INFO - threading running +2023-08-22,18:06:48.511 - INFO - threading running +2023-08-22,18:06:48.521 - INFO - threading running +2023-08-22,18:06:48.532 - INFO - threading running +2023-08-22,18:06:48.541 - INFO - threading running +2023-08-22,18:06:48.551 - INFO - threading running +2023-08-22,18:06:48.561 - INFO - threading running +2023-08-22,18:06:48.571 - INFO - threading running +2023-08-22,18:06:48.581 - INFO - threading running +2023-08-22,18:06:48.591 - INFO - threading running +2023-08-22,18:06:48.601 - INFO - threading running +2023-08-22,18:06:48.611 - INFO - threading running +2023-08-22,18:06:48.621 - INFO - threading running +2023-08-22,18:06:48.631 - INFO - threading running +2023-08-22,18:06:48.641 - INFO - threading running +2023-08-22,18:06:48.651 - INFO - threading running +2023-08-22,18:06:48.661 - INFO - threading running +2023-08-22,18:06:48.671 - INFO - threading running +2023-08-22,18:06:48.682 - INFO - threading running +2023-08-22,18:06:48.691 - INFO - threading running +2023-08-22,18:06:48.701 - INFO - threading running +2023-08-22,18:06:48.712 - INFO - threading running +2023-08-22,18:06:48.723 - INFO - threading running +2023-08-22,18:06:48.732 - INFO - threading running +2023-08-22,18:06:48.743 - INFO - threading running +2023-08-22,18:06:48.752 - INFO - threading running +2023-08-22,18:06:48.763 - INFO - threading running +2023-08-22,18:06:48.773 - INFO - threading running +2023-08-22,18:06:48.782 - INFO - threading running +2023-08-22,18:06:48.792 - INFO - threading running +2023-08-22,18:06:48.802 - INFO - threading running +2023-08-22,18:06:48.812 - INFO - threading running +2023-08-22,18:06:48.816 - INFO - ---------------------------------------------------- +2023-08-22,18:06:48.816 - INFO - 45th iteration +2023-08-22,18:06:48.816 - INFO - average ll reward: 0.1179684342 +2023-08-22,18:06:48.816 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:48.823 - INFO - updating finished +2023-08-22,18:06:52.937 - INFO - threading running +2023-08-22,18:06:52.949 - INFO - threading running +2023-08-22,18:06:52.959 - INFO - threading running +2023-08-22,18:06:52.969 - INFO - threading running +2023-08-22,18:06:52.979 - INFO - threading running +2023-08-22,18:06:52.990 - INFO - threading running +2023-08-22,18:06:53.001 - INFO - threading running +2023-08-22,18:06:53.012 - INFO - threading running +2023-08-22,18:06:53.022 - INFO - threading running +2023-08-22,18:06:53.031 - INFO - threading running +2023-08-22,18:06:53.042 - INFO - threading running +2023-08-22,18:06:53.052 - INFO - threading running +2023-08-22,18:06:53.062 - INFO - threading running +2023-08-22,18:06:53.072 - INFO - threading running +2023-08-22,18:06:53.083 - INFO - threading running +2023-08-22,18:06:53.093 - INFO - threading running +2023-08-22,18:06:53.103 - INFO - threading running +2023-08-22,18:06:53.114 - INFO - threading running +2023-08-22,18:06:53.124 - INFO - threading running +2023-08-22,18:06:53.135 - INFO - threading running +2023-08-22,18:06:53.144 - INFO - threading running +2023-08-22,18:06:53.154 - INFO - threading running +2023-08-22,18:06:53.164 - INFO - threading running +2023-08-22,18:06:53.174 - INFO - threading running +2023-08-22,18:06:53.184 - INFO - threading running +2023-08-22,18:06:53.195 - INFO - threading running +2023-08-22,18:06:53.205 - INFO - threading running +2023-08-22,18:06:53.215 - INFO - threading running +2023-08-22,18:06:53.225 - INFO - threading running +2023-08-22,18:06:53.236 - INFO - threading running +2023-08-22,18:06:53.245 - INFO - threading running +2023-08-22,18:06:53.256 - INFO - threading running +2023-08-22,18:06:53.266 - INFO - threading running +2023-08-22,18:06:53.276 - INFO - threading running +2023-08-22,18:06:53.286 - INFO - threading running +2023-08-22,18:06:53.296 - INFO - threading running +2023-08-22,18:06:53.306 - INFO - threading running +2023-08-22,18:06:53.316 - INFO - threading running +2023-08-22,18:06:53.326 - INFO - threading running +2023-08-22,18:06:53.336 - INFO - threading running +2023-08-22,18:06:53.346 - INFO - threading running +2023-08-22,18:06:53.356 - INFO - threading running +2023-08-22,18:06:53.366 - INFO - threading running +2023-08-22,18:06:53.376 - INFO - threading running +2023-08-22,18:06:53.386 - INFO - threading running +2023-08-22,18:06:53.396 - INFO - threading running +2023-08-22,18:06:53.407 - INFO - threading running +2023-08-22,18:06:53.417 - INFO - threading running +2023-08-22,18:06:53.427 - INFO - threading running +2023-08-22,18:06:53.436 - INFO - threading running +2023-08-22,18:06:53.446 - INFO - threading running +2023-08-22,18:06:53.456 - INFO - threading running +2023-08-22,18:06:53.466 - INFO - threading running +2023-08-22,18:06:53.476 - INFO - threading running +2023-08-22,18:06:53.486 - INFO - threading running +2023-08-22,18:06:53.497 - INFO - threading running +2023-08-22,18:06:53.506 - INFO - threading running +2023-08-22,18:06:53.517 - INFO - threading running +2023-08-22,18:06:53.528 - INFO - threading running +2023-08-22,18:06:53.537 - INFO - threading running +2023-08-22,18:06:53.547 - INFO - threading running +2023-08-22,18:06:53.558 - INFO - threading running +2023-08-22,18:06:53.567 - INFO - threading running +2023-08-22,18:06:53.578 - INFO - threading running +2023-08-22,18:06:53.581 - INFO - ---------------------------------------------------- +2023-08-22,18:06:53.582 - INFO - 46th iteration +2023-08-22,18:06:53.582 - INFO - average ll reward: 0.1116753856 +2023-08-22,18:06:53.582 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:53.587 - INFO - updating finished +2023-08-22,18:06:57.668 - INFO - threading running +2023-08-22,18:06:57.683 - INFO - threading running +2023-08-22,18:06:57.693 - INFO - threading running +2023-08-22,18:06:57.703 - INFO - threading running +2023-08-22,18:06:57.713 - INFO - threading running +2023-08-22,18:06:57.723 - INFO - threading running +2023-08-22,18:06:57.733 - INFO - threading running +2023-08-22,18:06:57.743 - INFO - threading running +2023-08-22,18:06:57.753 - INFO - threading running +2023-08-22,18:06:57.763 - INFO - threading running +2023-08-22,18:06:57.773 - INFO - threading running +2023-08-22,18:06:57.784 - INFO - threading running +2023-08-22,18:06:57.795 - INFO - threading running +2023-08-22,18:06:57.804 - INFO - threading running +2023-08-22,18:06:57.814 - INFO - threading running +2023-08-22,18:06:57.824 - INFO - threading running +2023-08-22,18:06:57.834 - INFO - threading running +2023-08-22,18:06:57.845 - INFO - threading running +2023-08-22,18:06:57.855 - INFO - threading running +2023-08-22,18:06:57.865 - INFO - threading running +2023-08-22,18:06:57.875 - INFO - threading running +2023-08-22,18:06:57.886 - INFO - threading running +2023-08-22,18:06:57.896 - INFO - threading running +2023-08-22,18:06:57.907 - INFO - threading running +2023-08-22,18:06:57.917 - INFO - threading running +2023-08-22,18:06:57.928 - INFO - threading running +2023-08-22,18:06:57.938 - INFO - threading running +2023-08-22,18:06:57.949 - INFO - threading running +2023-08-22,18:06:57.959 - INFO - threading running +2023-08-22,18:06:57.969 - INFO - threading running +2023-08-22,18:06:57.978 - INFO - threading running +2023-08-22,18:06:57.988 - INFO - threading running +2023-08-22,18:06:57.999 - INFO - threading running +2023-08-22,18:06:58.008 - INFO - threading running +2023-08-22,18:06:58.018 - INFO - threading running +2023-08-22,18:06:58.028 - INFO - threading running +2023-08-22,18:06:58.038 - INFO - threading running +2023-08-22,18:06:58.048 - INFO - threading running +2023-08-22,18:06:58.058 - INFO - threading running +2023-08-22,18:06:58.068 - INFO - threading running +2023-08-22,18:06:58.078 - INFO - threading running +2023-08-22,18:06:58.088 - INFO - threading running +2023-08-22,18:06:58.098 - INFO - threading running +2023-08-22,18:06:58.108 - INFO - threading running +2023-08-22,18:06:58.118 - INFO - threading running +2023-08-22,18:06:58.128 - INFO - threading running +2023-08-22,18:06:58.138 - INFO - threading running +2023-08-22,18:06:58.149 - INFO - threading running +2023-08-22,18:06:58.159 - INFO - threading running +2023-08-22,18:06:58.169 - INFO - threading running +2023-08-22,18:06:58.179 - INFO - threading running +2023-08-22,18:06:58.189 - INFO - threading running +2023-08-22,18:06:58.199 - INFO - threading running +2023-08-22,18:06:58.209 - INFO - threading running +2023-08-22,18:06:58.219 - INFO - ---------------------------------------------------- +2023-08-22,18:06:58.219 - INFO - 47th iteration +2023-08-22,18:06:58.219 - INFO - average ll reward: 0.0998030153 +2023-08-22,18:06:58.219 - INFO - ---------------------------------------------------- + +2023-08-22,18:06:58.220 - INFO - updating finished +2023-08-22,18:07:02.251 - INFO - threading running +2023-08-22,18:07:02.262 - INFO - threading running +2023-08-22,18:07:02.273 - INFO - threading running +2023-08-22,18:07:02.282 - INFO - threading running +2023-08-22,18:07:02.292 - INFO - threading running +2023-08-22,18:07:02.302 - INFO - threading running +2023-08-22,18:07:02.313 - INFO - threading running +2023-08-22,18:07:02.322 - INFO - threading running +2023-08-22,18:07:02.332 - INFO - threading running +2023-08-22,18:07:02.342 - INFO - threading running +2023-08-22,18:07:02.353 - INFO - threading running +2023-08-22,18:07:02.363 - INFO - threading running +2023-08-22,18:07:02.373 - INFO - threading running +2023-08-22,18:07:02.383 - INFO - threading running +2023-08-22,18:07:02.393 - INFO - threading running +2023-08-22,18:07:02.403 - INFO - threading running +2023-08-22,18:07:02.413 - INFO - threading running +2023-08-22,18:07:02.423 - INFO - threading running +2023-08-22,18:07:02.433 - INFO - threading running +2023-08-22,18:07:02.443 - INFO - threading running +2023-08-22,18:07:02.453 - INFO - threading running +2023-08-22,18:07:02.463 - INFO - threading running +2023-08-22,18:07:02.473 - INFO - threading running +2023-08-22,18:07:02.484 - INFO - threading running +2023-08-22,18:07:02.493 - INFO - threading running +2023-08-22,18:07:02.503 - INFO - threading running +2023-08-22,18:07:02.513 - INFO - threading running +2023-08-22,18:07:02.523 - INFO - threading running +2023-08-22,18:07:02.533 - INFO - threading running +2023-08-22,18:07:02.543 - INFO - threading running +2023-08-22,18:07:02.553 - INFO - threading running +2023-08-22,18:07:02.563 - INFO - threading running +2023-08-22,18:07:02.573 - INFO - threading running +2023-08-22,18:07:02.584 - INFO - threading running +2023-08-22,18:07:02.594 - INFO - threading running +2023-08-22,18:07:02.604 - INFO - threading running +2023-08-22,18:07:02.614 - INFO - threading running +2023-08-22,18:07:02.625 - INFO - threading running +2023-08-22,18:07:02.635 - INFO - threading running +2023-08-22,18:07:02.646 - INFO - threading running +2023-08-22,18:07:02.657 - INFO - threading running +2023-08-22,18:07:02.667 - INFO - threading running +2023-08-22,18:07:02.677 - INFO - threading running +2023-08-22,18:07:02.687 - INFO - threading running +2023-08-22,18:07:02.697 - INFO - threading running +2023-08-22,18:07:02.707 - INFO - threading running +2023-08-22,18:07:02.717 - INFO - threading running +2023-08-22,18:07:02.727 - INFO - threading running +2023-08-22,18:07:02.737 - INFO - threading running +2023-08-22,18:07:02.747 - INFO - threading running +2023-08-22,18:07:02.758 - INFO - threading running +2023-08-22,18:07:02.768 - INFO - threading running +2023-08-22,18:07:02.777 - INFO - threading running +2023-08-22,18:07:02.787 - INFO - threading running +2023-08-22,18:07:02.797 - INFO - threading running +2023-08-22,18:07:02.807 - INFO - threading running +2023-08-22,18:07:02.817 - INFO - threading running +2023-08-22,18:07:02.827 - INFO - ---------------------------------------------------- +2023-08-22,18:07:02.827 - INFO - 48th iteration +2023-08-22,18:07:02.827 - INFO - average ll reward: 0.1170523074 +2023-08-22,18:07:02.827 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:02.828 - INFO - updating finished +2023-08-22,18:07:06.880 - INFO - threading running +2023-08-22,18:07:06.887 - INFO - threading running +2023-08-22,18:07:06.898 - INFO - threading running +2023-08-22,18:07:06.907 - INFO - threading running +2023-08-22,18:07:06.917 - INFO - threading running +2023-08-22,18:07:06.928 - INFO - threading running +2023-08-22,18:07:06.937 - INFO - threading running +2023-08-22,18:07:06.947 - INFO - threading running +2023-08-22,18:07:06.957 - INFO - threading running +2023-08-22,18:07:06.967 - INFO - threading running +2023-08-22,18:07:06.978 - INFO - threading running +2023-08-22,18:07:06.988 - INFO - threading running +2023-08-22,18:07:06.999 - INFO - threading running +2023-08-22,18:07:07.008 - INFO - threading running +2023-08-22,18:07:07.018 - INFO - threading running +2023-08-22,18:07:07.028 - INFO - threading running +2023-08-22,18:07:07.039 - INFO - threading running +2023-08-22,18:07:07.049 - INFO - threading running +2023-08-22,18:07:07.059 - INFO - threading running +2023-08-22,18:07:07.070 - INFO - threading running +2023-08-22,18:07:07.079 - INFO - threading running +2023-08-22,18:07:07.089 - INFO - threading running +2023-08-22,18:07:07.099 - INFO - threading running +2023-08-22,18:07:07.110 - INFO - threading running +2023-08-22,18:07:07.120 - INFO - threading running +2023-08-22,18:07:07.130 - INFO - threading running +2023-08-22,18:07:07.140 - INFO - threading running +2023-08-22,18:07:07.150 - INFO - threading running +2023-08-22,18:07:07.160 - INFO - threading running +2023-08-22,18:07:07.170 - INFO - threading running +2023-08-22,18:07:07.180 - INFO - threading running +2023-08-22,18:07:07.191 - INFO - threading running +2023-08-22,18:07:07.202 - INFO - threading running +2023-08-22,18:07:07.213 - INFO - threading running +2023-08-22,18:07:07.222 - INFO - threading running +2023-08-22,18:07:07.232 - INFO - threading running +2023-08-22,18:07:07.242 - INFO - threading running +2023-08-22,18:07:07.253 - INFO - threading running +2023-08-22,18:07:07.263 - INFO - threading running +2023-08-22,18:07:07.273 - INFO - threading running +2023-08-22,18:07:07.283 - INFO - threading running +2023-08-22,18:07:07.293 - INFO - threading running +2023-08-22,18:07:07.303 - INFO - threading running +2023-08-22,18:07:07.313 - INFO - threading running +2023-08-22,18:07:07.323 - INFO - threading running +2023-08-22,18:07:07.333 - INFO - threading running +2023-08-22,18:07:07.343 - INFO - threading running +2023-08-22,18:07:07.353 - INFO - threading running +2023-08-22,18:07:07.363 - INFO - threading running +2023-08-22,18:07:07.374 - INFO - threading running +2023-08-22,18:07:07.383 - INFO - threading running +2023-08-22,18:07:07.394 - INFO - threading running +2023-08-22,18:07:07.403 - INFO - threading running +2023-08-22,18:07:07.413 - INFO - threading running +2023-08-22,18:07:07.423 - INFO - threading running +2023-08-22,18:07:07.433 - INFO - threading running +2023-08-22,18:07:07.443 - INFO - threading running +2023-08-22,18:07:07.453 - INFO - threading running +2023-08-22,18:07:07.459 - INFO - ---------------------------------------------------- +2023-08-22,18:07:07.459 - INFO - 49th iteration +2023-08-22,18:07:07.459 - INFO - average ll reward: 0.1165702759 +2023-08-22,18:07:07.459 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:07.463 - INFO - updating finished +2023-08-22,18:07:11.528 - INFO - threading running +2023-08-22,18:07:11.539 - INFO - threading running +2023-08-22,18:07:11.549 - INFO - threading running +2023-08-22,18:07:11.559 - INFO - threading running +2023-08-22,18:07:11.569 - INFO - threading running +2023-08-22,18:07:11.579 - INFO - threading running +2023-08-22,18:07:11.590 - INFO - threading running +2023-08-22,18:07:11.600 - INFO - threading running +2023-08-22,18:07:11.611 - INFO - threading running +2023-08-22,18:07:11.621 - INFO - threading running +2023-08-22,18:07:11.631 - INFO - threading running +2023-08-22,18:07:11.641 - INFO - threading running +2023-08-22,18:07:11.651 - INFO - threading running +2023-08-22,18:07:11.662 - INFO - threading running +2023-08-22,18:07:11.672 - INFO - threading running +2023-08-22,18:07:11.682 - INFO - threading running +2023-08-22,18:07:11.692 - INFO - threading running +2023-08-22,18:07:11.702 - INFO - threading running +2023-08-22,18:07:11.712 - INFO - threading running +2023-08-22,18:07:11.722 - INFO - threading running +2023-08-22,18:07:11.732 - INFO - threading running +2023-08-22,18:07:11.742 - INFO - threading running +2023-08-22,18:07:11.752 - INFO - threading running +2023-08-22,18:07:11.762 - INFO - threading running +2023-08-22,18:07:11.772 - INFO - threading running +2023-08-22,18:07:11.782 - INFO - threading running +2023-08-22,18:07:11.793 - INFO - threading running +2023-08-22,18:07:11.802 - INFO - threading running +2023-08-22,18:07:11.813 - INFO - threading running +2023-08-22,18:07:11.823 - INFO - threading running +2023-08-22,18:07:11.834 - INFO - threading running +2023-08-22,18:07:11.845 - INFO - threading running +2023-08-22,18:07:11.854 - INFO - threading running +2023-08-22,18:07:11.864 - INFO - threading running +2023-08-22,18:07:11.874 - INFO - threading running +2023-08-22,18:07:11.884 - INFO - threading running +2023-08-22,18:07:11.894 - INFO - threading running +2023-08-22,18:07:11.904 - INFO - threading running +2023-08-22,18:07:11.915 - INFO - threading running +2023-08-22,18:07:11.924 - INFO - threading running +2023-08-22,18:07:11.934 - INFO - threading running +2023-08-22,18:07:11.944 - INFO - threading running +2023-08-22,18:07:11.955 - INFO - threading running +2023-08-22,18:07:11.965 - INFO - threading running +2023-08-22,18:07:11.975 - INFO - threading running +2023-08-22,18:07:11.985 - INFO - threading running +2023-08-22,18:07:11.995 - INFO - threading running +2023-08-22,18:07:12.005 - INFO - threading running +2023-08-22,18:07:12.015 - INFO - threading running +2023-08-22,18:07:12.025 - INFO - threading running +2023-08-22,18:07:12.036 - INFO - threading running +2023-08-22,18:07:12.045 - INFO - threading running +2023-08-22,18:07:12.055 - INFO - threading running +2023-08-22,18:07:12.065 - INFO - threading running +2023-08-22,18:07:12.076 - INFO - threading running +2023-08-22,18:07:12.086 - INFO - threading running +2023-08-22,18:07:12.097 - INFO - threading running +2023-08-22,18:07:12.101 - INFO - ---------------------------------------------------- +2023-08-22,18:07:12.101 - INFO - 50th iteration +2023-08-22,18:07:12.101 - INFO - average ll reward: 0.0894086967 +2023-08-22,18:07:12.101 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:12.107 - INFO - updating finished +2023-08-22,18:07:16.155 - INFO - threading running +2023-08-22,18:07:16.168 - INFO - threading running +2023-08-22,18:07:16.179 - INFO - threading running +2023-08-22,18:07:16.190 - INFO - threading running +2023-08-22,18:07:16.199 - INFO - threading running +2023-08-22,18:07:16.209 - INFO - threading running +2023-08-22,18:07:16.219 - INFO - threading running +2023-08-22,18:07:16.229 - INFO - threading running +2023-08-22,18:07:16.239 - INFO - threading running +2023-08-22,18:07:16.249 - INFO - threading running +2023-08-22,18:07:16.259 - INFO - threading running +2023-08-22,18:07:16.269 - INFO - threading running +2023-08-22,18:07:16.279 - INFO - threading running +2023-08-22,18:07:16.290 - INFO - threading running +2023-08-22,18:07:16.300 - INFO - threading running +2023-08-22,18:07:16.310 - INFO - threading running +2023-08-22,18:07:16.320 - INFO - threading running +2023-08-22,18:07:16.330 - INFO - threading running +2023-08-22,18:07:16.340 - INFO - threading running +2023-08-22,18:07:16.351 - INFO - threading running +2023-08-22,18:07:16.361 - INFO - threading running +2023-08-22,18:07:16.372 - INFO - threading running +2023-08-22,18:07:16.382 - INFO - threading running +2023-08-22,18:07:16.391 - INFO - threading running +2023-08-22,18:07:16.401 - INFO - threading running +2023-08-22,18:07:16.411 - INFO - threading running +2023-08-22,18:07:16.421 - INFO - threading running +2023-08-22,18:07:16.431 - INFO - threading running +2023-08-22,18:07:16.441 - INFO - threading running +2023-08-22,18:07:16.451 - INFO - threading running +2023-08-22,18:07:16.462 - INFO - threading running +2023-08-22,18:07:16.471 - INFO - threading running +2023-08-22,18:07:16.481 - INFO - threading running +2023-08-22,18:07:16.492 - INFO - threading running +2023-08-22,18:07:16.502 - INFO - threading running +2023-08-22,18:07:16.512 - INFO - threading running +2023-08-22,18:07:16.522 - INFO - threading running +2023-08-22,18:07:16.532 - INFO - threading running +2023-08-22,18:07:16.542 - INFO - threading running +2023-08-22,18:07:16.552 - INFO - threading running +2023-08-22,18:07:16.563 - INFO - threading running +2023-08-22,18:07:16.572 - INFO - threading running +2023-08-22,18:07:16.582 - INFO - threading running +2023-08-22,18:07:16.593 - INFO - threading running +2023-08-22,18:07:16.603 - INFO - threading running +2023-08-22,18:07:16.613 - INFO - threading running +2023-08-22,18:07:16.623 - INFO - threading running +2023-08-22,18:07:16.633 - INFO - threading running +2023-08-22,18:07:16.643 - INFO - threading running +2023-08-22,18:07:16.654 - INFO - threading running +2023-08-22,18:07:16.660 - INFO - ---------------------------------------------------- +2023-08-22,18:07:16.660 - INFO - 51th iteration +2023-08-22,18:07:16.660 - INFO - average ll reward: 0.0976032444 +2023-08-22,18:07:16.660 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:16.665 - INFO - updating finished +2023-08-22,18:07:20.707 - INFO - threading running +2023-08-22,18:07:20.719 - INFO - threading running +2023-08-22,18:07:20.730 - INFO - threading running +2023-08-22,18:07:20.739 - INFO - threading running +2023-08-22,18:07:20.749 - INFO - threading running +2023-08-22,18:07:20.759 - INFO - threading running +2023-08-22,18:07:20.769 - INFO - threading running +2023-08-22,18:07:20.779 - INFO - threading running +2023-08-22,18:07:20.789 - INFO - threading running +2023-08-22,18:07:20.799 - INFO - threading running +2023-08-22,18:07:20.810 - INFO - threading running +2023-08-22,18:07:20.821 - INFO - threading running +2023-08-22,18:07:20.831 - INFO - threading running +2023-08-22,18:07:20.842 - INFO - threading running +2023-08-22,18:07:20.852 - INFO - threading running +2023-08-22,18:07:20.861 - INFO - threading running +2023-08-22,18:07:20.871 - INFO - threading running +2023-08-22,18:07:20.881 - INFO - threading running +2023-08-22,18:07:20.891 - INFO - threading running +2023-08-22,18:07:20.901 - INFO - threading running +2023-08-22,18:07:20.911 - INFO - threading running +2023-08-22,18:07:20.922 - INFO - threading running +2023-08-22,18:07:20.931 - INFO - threading running +2023-08-22,18:07:20.941 - INFO - threading running +2023-08-22,18:07:20.951 - INFO - threading running +2023-08-22,18:07:20.962 - INFO - threading running +2023-08-22,18:07:20.973 - INFO - threading running +2023-08-22,18:07:20.982 - INFO - threading running +2023-08-22,18:07:20.993 - INFO - threading running +2023-08-22,18:07:21.002 - INFO - threading running +2023-08-22,18:07:21.012 - INFO - threading running +2023-08-22,18:07:21.023 - INFO - threading running +2023-08-22,18:07:21.033 - INFO - threading running +2023-08-22,18:07:21.042 - INFO - threading running +2023-08-22,18:07:21.052 - INFO - threading running +2023-08-22,18:07:21.063 - INFO - threading running +2023-08-22,18:07:21.074 - INFO - threading running +2023-08-22,18:07:21.085 - INFO - threading running +2023-08-22,18:07:21.094 - INFO - threading running +2023-08-22,18:07:21.104 - INFO - threading running +2023-08-22,18:07:21.114 - INFO - threading running +2023-08-22,18:07:21.125 - INFO - threading running +2023-08-22,18:07:21.135 - INFO - threading running +2023-08-22,18:07:21.144 - INFO - threading running +2023-08-22,18:07:21.155 - INFO - threading running +2023-08-22,18:07:21.165 - INFO - threading running +2023-08-22,18:07:21.176 - INFO - threading running +2023-08-22,18:07:21.186 - INFO - threading running +2023-08-22,18:07:21.195 - INFO - threading running +2023-08-22,18:07:21.205 - INFO - threading running +2023-08-22,18:07:21.212 - INFO - ---------------------------------------------------- +2023-08-22,18:07:21.213 - INFO - 52th iteration +2023-08-22,18:07:21.213 - INFO - average ll reward: 0.0906870161 +2023-08-22,18:07:21.213 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:21.216 - INFO - updating finished +2023-08-22,18:07:25.278 - INFO - threading running +2023-08-22,18:07:25.292 - INFO - threading running +2023-08-22,18:07:25.303 - INFO - threading running +2023-08-22,18:07:25.312 - INFO - threading running +2023-08-22,18:07:25.322 - INFO - threading running +2023-08-22,18:07:25.332 - INFO - threading running +2023-08-22,18:07:25.342 - INFO - threading running +2023-08-22,18:07:25.352 - INFO - threading running +2023-08-22,18:07:25.363 - INFO - threading running +2023-08-22,18:07:25.373 - INFO - threading running +2023-08-22,18:07:25.384 - INFO - threading running +2023-08-22,18:07:25.394 - INFO - threading running +2023-08-22,18:07:25.404 - INFO - threading running +2023-08-22,18:07:25.415 - INFO - threading running +2023-08-22,18:07:25.425 - INFO - threading running +2023-08-22,18:07:25.435 - INFO - threading running +2023-08-22,18:07:25.446 - INFO - threading running +2023-08-22,18:07:25.455 - INFO - threading running +2023-08-22,18:07:25.465 - INFO - threading running +2023-08-22,18:07:25.475 - INFO - threading running +2023-08-22,18:07:25.485 - INFO - threading running +2023-08-22,18:07:25.495 - INFO - threading running +2023-08-22,18:07:25.505 - INFO - threading running +2023-08-22,18:07:25.516 - INFO - threading running +2023-08-22,18:07:25.525 - INFO - threading running +2023-08-22,18:07:25.535 - INFO - threading running +2023-08-22,18:07:25.545 - INFO - threading running +2023-08-22,18:07:25.556 - INFO - threading running +2023-08-22,18:07:25.566 - INFO - threading running +2023-08-22,18:07:25.575 - INFO - threading running +2023-08-22,18:07:25.585 - INFO - threading running +2023-08-22,18:07:25.596 - INFO - threading running +2023-08-22,18:07:25.606 - INFO - threading running +2023-08-22,18:07:25.616 - INFO - threading running +2023-08-22,18:07:25.627 - INFO - threading running +2023-08-22,18:07:25.636 - INFO - threading running +2023-08-22,18:07:25.646 - INFO - threading running +2023-08-22,18:07:25.656 - INFO - threading running +2023-08-22,18:07:25.666 - INFO - threading running +2023-08-22,18:07:25.677 - INFO - threading running +2023-08-22,18:07:25.687 - INFO - threading running +2023-08-22,18:07:25.698 - INFO - threading running +2023-08-22,18:07:25.708 - INFO - threading running +2023-08-22,18:07:25.718 - INFO - threading running +2023-08-22,18:07:25.728 - INFO - threading running +2023-08-22,18:07:25.738 - INFO - threading running +2023-08-22,18:07:25.748 - INFO - threading running +2023-08-22,18:07:25.758 - INFO - threading running +2023-08-22,18:07:25.768 - INFO - threading running +2023-08-22,18:07:25.778 - INFO - threading running +2023-08-22,18:07:25.788 - INFO - threading running +2023-08-22,18:07:25.799 - INFO - threading running +2023-08-22,18:07:25.809 - INFO - threading running +2023-08-22,18:07:25.820 - INFO - threading running +2023-08-22,18:07:25.829 - INFO - threading running +2023-08-22,18:07:25.839 - INFO - threading running +2023-08-22,18:07:25.843 - INFO - ---------------------------------------------------- +2023-08-22,18:07:25.843 - INFO - 53th iteration +2023-08-22,18:07:25.843 - INFO - average ll reward: 0.0856376623 +2023-08-22,18:07:25.843 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:25.850 - INFO - updating finished +2023-08-22,18:07:29.917 - INFO - threading running +2023-08-22,18:07:29.930 - INFO - threading running +2023-08-22,18:07:29.939 - INFO - threading running +2023-08-22,18:07:29.949 - INFO - threading running +2023-08-22,18:07:29.960 - INFO - threading running +2023-08-22,18:07:29.970 - INFO - threading running +2023-08-22,18:07:29.980 - INFO - threading running +2023-08-22,18:07:29.990 - INFO - threading running +2023-08-22,18:07:30.000 - INFO - threading running +2023-08-22,18:07:30.010 - INFO - threading running +2023-08-22,18:07:30.020 - INFO - threading running +2023-08-22,18:07:30.031 - INFO - threading running +2023-08-22,18:07:30.041 - INFO - threading running +2023-08-22,18:07:30.051 - INFO - threading running +2023-08-22,18:07:30.061 - INFO - threading running +2023-08-22,18:07:30.072 - INFO - threading running +2023-08-22,18:07:30.083 - INFO - threading running +2023-08-22,18:07:30.092 - INFO - threading running +2023-08-22,18:07:30.102 - INFO - threading running +2023-08-22,18:07:30.112 - INFO - threading running +2023-08-22,18:07:30.122 - INFO - threading running +2023-08-22,18:07:30.132 - INFO - threading running +2023-08-22,18:07:30.142 - INFO - threading running +2023-08-22,18:07:30.152 - INFO - threading running +2023-08-22,18:07:30.162 - INFO - threading running +2023-08-22,18:07:30.172 - INFO - threading running +2023-08-22,18:07:30.182 - INFO - threading running +2023-08-22,18:07:30.192 - INFO - threading running +2023-08-22,18:07:30.203 - INFO - threading running +2023-08-22,18:07:30.212 - INFO - threading running +2023-08-22,18:07:30.223 - INFO - threading running +2023-08-22,18:07:30.233 - INFO - threading running +2023-08-22,18:07:30.243 - INFO - threading running +2023-08-22,18:07:30.254 - INFO - threading running +2023-08-22,18:07:30.264 - INFO - threading running +2023-08-22,18:07:30.274 - INFO - threading running +2023-08-22,18:07:30.284 - INFO - threading running +2023-08-22,18:07:30.294 - INFO - threading running +2023-08-22,18:07:30.305 - INFO - threading running +2023-08-22,18:07:30.314 - INFO - threading running +2023-08-22,18:07:30.324 - INFO - threading running +2023-08-22,18:07:30.334 - INFO - threading running +2023-08-22,18:07:30.344 - INFO - threading running +2023-08-22,18:07:30.354 - INFO - threading running +2023-08-22,18:07:30.364 - INFO - threading running +2023-08-22,18:07:30.374 - INFO - threading running +2023-08-22,18:07:30.384 - INFO - threading running +2023-08-22,18:07:30.394 - INFO - threading running +2023-08-22,18:07:30.405 - INFO - threading running +2023-08-22,18:07:30.415 - INFO - threading running +2023-08-22,18:07:30.425 - INFO - threading running +2023-08-22,18:07:30.435 - INFO - threading running +2023-08-22,18:07:30.446 - INFO - threading running +2023-08-22,18:07:30.457 - INFO - threading running +2023-08-22,18:07:30.467 - INFO - threading running +2023-08-22,18:07:30.473 - INFO - ---------------------------------------------------- +2023-08-22,18:07:30.473 - INFO - 54th iteration +2023-08-22,18:07:30.474 - INFO - average ll reward: 0.0873154542 +2023-08-22,18:07:30.474 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:30.477 - INFO - updating finished +2023-08-22,18:07:34.585 - INFO - threading running +2023-08-22,18:07:34.600 - INFO - threading running +2023-08-22,18:07:34.610 - INFO - threading running +2023-08-22,18:07:34.621 - INFO - threading running +2023-08-22,18:07:34.631 - INFO - threading running +2023-08-22,18:07:34.640 - INFO - threading running +2023-08-22,18:07:34.650 - INFO - threading running +2023-08-22,18:07:34.660 - INFO - threading running +2023-08-22,18:07:34.670 - INFO - threading running +2023-08-22,18:07:34.680 - INFO - threading running +2023-08-22,18:07:34.690 - INFO - threading running +2023-08-22,18:07:34.700 - INFO - threading running +2023-08-22,18:07:34.710 - INFO - threading running +2023-08-22,18:07:34.720 - INFO - threading running +2023-08-22,18:07:34.730 - INFO - threading running +2023-08-22,18:07:34.740 - INFO - threading running +2023-08-22,18:07:34.751 - INFO - threading running +2023-08-22,18:07:34.760 - INFO - threading running +2023-08-22,18:07:34.771 - INFO - threading running +2023-08-22,18:07:34.780 - INFO - threading running +2023-08-22,18:07:34.790 - INFO - threading running +2023-08-22,18:07:34.800 - INFO - threading running +2023-08-22,18:07:34.811 - INFO - threading running +2023-08-22,18:07:34.821 - INFO - threading running +2023-08-22,18:07:34.832 - INFO - threading running +2023-08-22,18:07:34.842 - INFO - threading running +2023-08-22,18:07:34.852 - INFO - threading running +2023-08-22,18:07:34.862 - INFO - threading running +2023-08-22,18:07:34.872 - INFO - threading running +2023-08-22,18:07:34.883 - INFO - threading running +2023-08-22,18:07:34.892 - INFO - threading running +2023-08-22,18:07:34.903 - INFO - threading running +2023-08-22,18:07:34.912 - INFO - threading running +2023-08-22,18:07:34.922 - INFO - threading running +2023-08-22,18:07:34.932 - INFO - threading running +2023-08-22,18:07:34.943 - INFO - threading running +2023-08-22,18:07:34.953 - INFO - threading running +2023-08-22,18:07:34.963 - INFO - threading running +2023-08-22,18:07:34.973 - INFO - threading running +2023-08-22,18:07:34.983 - INFO - threading running +2023-08-22,18:07:34.994 - INFO - threading running +2023-08-22,18:07:35.004 - INFO - threading running +2023-08-22,18:07:35.014 - INFO - threading running +2023-08-22,18:07:35.025 - INFO - threading running +2023-08-22,18:07:35.034 - INFO - threading running +2023-08-22,18:07:35.044 - INFO - threading running +2023-08-22,18:07:35.054 - INFO - threading running +2023-08-22,18:07:35.064 - INFO - threading running +2023-08-22,18:07:35.074 - INFO - threading running +2023-08-22,18:07:35.085 - INFO - threading running +2023-08-22,18:07:35.095 - INFO - threading running +2023-08-22,18:07:35.105 - INFO - threading running +2023-08-22,18:07:35.115 - INFO - threading running +2023-08-22,18:07:35.125 - INFO - threading running +2023-08-22,18:07:35.135 - INFO - threading running +2023-08-22,18:07:35.146 - INFO - threading running +2023-08-22,18:07:35.156 - INFO - threading running +2023-08-22,18:07:35.166 - INFO - threading running +2023-08-22,18:07:35.177 - INFO - threading running +2023-08-22,18:07:35.177 - INFO - ---------------------------------------------------- +2023-08-22,18:07:35.178 - INFO - 55th iteration +2023-08-22,18:07:35.178 - INFO - average ll reward: 0.0858587038 +2023-08-22,18:07:35.178 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:35.186 - INFO - updating finished +2023-08-22,18:07:39.351 - INFO - threading running +2023-08-22,18:07:39.363 - INFO - threading running +2023-08-22,18:07:39.372 - INFO - threading running +2023-08-22,18:07:39.383 - INFO - threading running +2023-08-22,18:07:39.394 - INFO - threading running +2023-08-22,18:07:39.403 - INFO - threading running +2023-08-22,18:07:39.414 - INFO - threading running +2023-08-22,18:07:39.423 - INFO - threading running +2023-08-22,18:07:39.434 - INFO - threading running +2023-08-22,18:07:39.444 - INFO - threading running +2023-08-22,18:07:39.455 - INFO - threading running +2023-08-22,18:07:39.465 - INFO - threading running +2023-08-22,18:07:39.476 - INFO - threading running +2023-08-22,18:07:39.485 - INFO - threading running +2023-08-22,18:07:39.495 - INFO - threading running +2023-08-22,18:07:39.505 - INFO - threading running +2023-08-22,18:07:39.516 - INFO - threading running +2023-08-22,18:07:39.525 - INFO - threading running +2023-08-22,18:07:39.535 - INFO - threading running +2023-08-22,18:07:39.545 - INFO - threading running +2023-08-22,18:07:39.556 - INFO - threading running +2023-08-22,18:07:39.567 - INFO - threading running +2023-08-22,18:07:39.577 - INFO - threading running +2023-08-22,18:07:39.587 - INFO - threading running +2023-08-22,18:07:39.597 - INFO - threading running +2023-08-22,18:07:39.607 - INFO - threading running +2023-08-22,18:07:39.617 - INFO - threading running +2023-08-22,18:07:39.627 - INFO - threading running +2023-08-22,18:07:39.637 - INFO - threading running +2023-08-22,18:07:39.647 - INFO - threading running +2023-08-22,18:07:39.657 - INFO - threading running +2023-08-22,18:07:39.667 - INFO - threading running +2023-08-22,18:07:39.677 - INFO - threading running +2023-08-22,18:07:39.687 - INFO - threading running +2023-08-22,18:07:39.697 - INFO - threading running +2023-08-22,18:07:39.707 - INFO - threading running +2023-08-22,18:07:39.718 - INFO - threading running +2023-08-22,18:07:39.727 - INFO - threading running +2023-08-22,18:07:39.738 - INFO - threading running +2023-08-22,18:07:39.748 - INFO - threading running +2023-08-22,18:07:39.758 - INFO - threading running +2023-08-22,18:07:39.768 - INFO - threading running +2023-08-22,18:07:39.778 - INFO - threading running +2023-08-22,18:07:39.788 - INFO - threading running +2023-08-22,18:07:39.799 - INFO - threading running +2023-08-22,18:07:39.809 - INFO - threading running +2023-08-22,18:07:39.819 - INFO - threading running +2023-08-22,18:07:39.829 - INFO - threading running +2023-08-22,18:07:39.840 - INFO - threading running +2023-08-22,18:07:39.849 - INFO - threading running +2023-08-22,18:07:39.860 - INFO - threading running +2023-08-22,18:07:39.871 - INFO - threading running +2023-08-22,18:07:39.881 - INFO - threading running +2023-08-22,18:07:39.891 - INFO - threading running +2023-08-22,18:07:39.901 - INFO - threading running +2023-08-22,18:07:39.910 - INFO - threading running +2023-08-22,18:07:39.920 - INFO - threading running +2023-08-22,18:07:39.931 - INFO - threading running +2023-08-22,18:07:39.933 - INFO - ---------------------------------------------------- +2023-08-22,18:07:39.933 - INFO - 56th iteration +2023-08-22,18:07:39.933 - INFO - average ll reward: 0.1288660903 +2023-08-22,18:07:39.933 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:39.940 - INFO - updating finished +2023-08-22,18:07:44.122 - INFO - threading running +2023-08-22,18:07:44.130 - INFO - threading running +2023-08-22,18:07:44.141 - INFO - threading running +2023-08-22,18:07:44.150 - INFO - threading running +2023-08-22,18:07:44.161 - INFO - threading running +2023-08-22,18:07:44.171 - INFO - threading running +2023-08-22,18:07:44.181 - INFO - threading running +2023-08-22,18:07:44.191 - INFO - threading running +2023-08-22,18:07:44.202 - INFO - threading running +2023-08-22,18:07:44.212 - INFO - threading running +2023-08-22,18:07:44.221 - INFO - threading running +2023-08-22,18:07:44.231 - INFO - threading running +2023-08-22,18:07:44.241 - INFO - threading running +2023-08-22,18:07:44.251 - INFO - threading running +2023-08-22,18:07:44.261 - INFO - threading running +2023-08-22,18:07:44.271 - INFO - threading running +2023-08-22,18:07:44.281 - INFO - threading running +2023-08-22,18:07:44.292 - INFO - threading running +2023-08-22,18:07:44.301 - INFO - threading running +2023-08-22,18:07:44.311 - INFO - threading running +2023-08-22,18:07:44.321 - INFO - threading running +2023-08-22,18:07:44.331 - INFO - threading running +2023-08-22,18:07:44.342 - INFO - threading running +2023-08-22,18:07:44.351 - INFO - threading running +2023-08-22,18:07:44.361 - INFO - threading running +2023-08-22,18:07:44.371 - INFO - threading running +2023-08-22,18:07:44.382 - INFO - threading running +2023-08-22,18:07:44.391 - INFO - threading running +2023-08-22,18:07:44.402 - INFO - threading running +2023-08-22,18:07:44.413 - INFO - threading running +2023-08-22,18:07:44.424 - INFO - threading running +2023-08-22,18:07:44.434 - INFO - threading running +2023-08-22,18:07:44.444 - INFO - threading running +2023-08-22,18:07:44.454 - INFO - threading running +2023-08-22,18:07:44.464 - INFO - threading running +2023-08-22,18:07:44.474 - INFO - threading running +2023-08-22,18:07:44.484 - INFO - threading running +2023-08-22,18:07:44.494 - INFO - threading running +2023-08-22,18:07:44.504 - INFO - threading running +2023-08-22,18:07:44.514 - INFO - threading running +2023-08-22,18:07:44.524 - INFO - threading running +2023-08-22,18:07:44.534 - INFO - threading running +2023-08-22,18:07:44.544 - INFO - threading running +2023-08-22,18:07:44.555 - INFO - threading running +2023-08-22,18:07:44.565 - INFO - threading running +2023-08-22,18:07:44.576 - INFO - threading running +2023-08-22,18:07:44.586 - INFO - threading running +2023-08-22,18:07:44.596 - INFO - threading running +2023-08-22,18:07:44.605 - INFO - threading running +2023-08-22,18:07:44.615 - INFO - threading running +2023-08-22,18:07:44.626 - INFO - threading running +2023-08-22,18:07:44.635 - INFO - threading running +2023-08-22,18:07:44.646 - INFO - threading running +2023-08-22,18:07:44.657 - INFO - threading running +2023-08-22,18:07:44.666 - INFO - threading running +2023-08-22,18:07:44.676 - INFO - threading running +2023-08-22,18:07:44.687 - INFO - threading running +2023-08-22,18:07:44.690 - INFO - ---------------------------------------------------- +2023-08-22,18:07:44.690 - INFO - 57th iteration +2023-08-22,18:07:44.690 - INFO - average ll reward: 0.1236915687 +2023-08-22,18:07:44.690 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:44.697 - INFO - updating finished +2023-08-22,18:07:48.842 - INFO - threading running +2023-08-22,18:07:48.854 - INFO - threading running +2023-08-22,18:07:48.864 - INFO - threading running +2023-08-22,18:07:48.874 - INFO - threading running +2023-08-22,18:07:48.884 - INFO - threading running +2023-08-22,18:07:48.894 - INFO - threading running +2023-08-22,18:07:48.904 - INFO - threading running +2023-08-22,18:07:48.914 - INFO - threading running +2023-08-22,18:07:48.924 - INFO - threading running +2023-08-22,18:07:48.934 - INFO - threading running +2023-08-22,18:07:48.945 - INFO - threading running +2023-08-22,18:07:48.955 - INFO - threading running +2023-08-22,18:07:48.965 - INFO - threading running +2023-08-22,18:07:48.975 - INFO - threading running +2023-08-22,18:07:48.985 - INFO - threading running +2023-08-22,18:07:48.995 - INFO - threading running +2023-08-22,18:07:49.005 - INFO - threading running +2023-08-22,18:07:49.015 - INFO - threading running +2023-08-22,18:07:49.025 - INFO - threading running +2023-08-22,18:07:49.035 - INFO - threading running +2023-08-22,18:07:49.045 - INFO - threading running +2023-08-22,18:07:49.055 - INFO - threading running +2023-08-22,18:07:49.066 - INFO - threading running +2023-08-22,18:07:49.076 - INFO - threading running +2023-08-22,18:07:49.087 - INFO - threading running +2023-08-22,18:07:49.097 - INFO - threading running +2023-08-22,18:07:49.107 - INFO - threading running +2023-08-22,18:07:49.118 - INFO - threading running +2023-08-22,18:07:49.128 - INFO - threading running +2023-08-22,18:07:49.139 - INFO - threading running +2023-08-22,18:07:49.148 - INFO - threading running +2023-08-22,18:07:49.158 - INFO - threading running +2023-08-22,18:07:49.168 - INFO - threading running +2023-08-22,18:07:49.179 - INFO - threading running +2023-08-22,18:07:49.189 - INFO - threading running +2023-08-22,18:07:49.200 - INFO - threading running +2023-08-22,18:07:49.209 - INFO - threading running +2023-08-22,18:07:49.219 - INFO - threading running +2023-08-22,18:07:49.229 - INFO - threading running +2023-08-22,18:07:49.239 - INFO - threading running +2023-08-22,18:07:49.249 - INFO - threading running +2023-08-22,18:07:49.260 - INFO - threading running +2023-08-22,18:07:49.269 - INFO - threading running +2023-08-22,18:07:49.279 - INFO - threading running +2023-08-22,18:07:49.289 - INFO - threading running +2023-08-22,18:07:49.299 - INFO - threading running +2023-08-22,18:07:49.309 - INFO - threading running +2023-08-22,18:07:49.319 - INFO - threading running +2023-08-22,18:07:49.330 - INFO - threading running +2023-08-22,18:07:49.339 - INFO - threading running +2023-08-22,18:07:49.349 - INFO - threading running +2023-08-22,18:07:49.359 - INFO - threading running +2023-08-22,18:07:49.369 - INFO - threading running +2023-08-22,18:07:49.380 - INFO - threading running +2023-08-22,18:07:49.390 - INFO - threading running +2023-08-22,18:07:49.398 - INFO - ---------------------------------------------------- +2023-08-22,18:07:49.398 - INFO - 58th iteration +2023-08-22,18:07:49.398 - INFO - average ll reward: 0.1212148281 +2023-08-22,18:07:49.398 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:49.400 - INFO - updating finished +2023-08-22,18:07:53.516 - INFO - threading running +2023-08-22,18:07:53.523 - INFO - threading running +2023-08-22,18:07:53.533 - INFO - threading running +2023-08-22,18:07:53.543 - INFO - threading running +2023-08-22,18:07:53.553 - INFO - threading running +2023-08-22,18:07:53.563 - INFO - threading running +2023-08-22,18:07:53.573 - INFO - threading running +2023-08-22,18:07:53.583 - INFO - threading running +2023-08-22,18:07:53.593 - INFO - threading running +2023-08-22,18:07:53.603 - INFO - threading running +2023-08-22,18:07:53.614 - INFO - threading running +2023-08-22,18:07:53.624 - INFO - threading running +2023-08-22,18:07:53.633 - INFO - threading running +2023-08-22,18:07:53.643 - INFO - threading running +2023-08-22,18:07:53.653 - INFO - threading running +2023-08-22,18:07:53.663 - INFO - threading running +2023-08-22,18:07:53.674 - INFO - threading running +2023-08-22,18:07:53.684 - INFO - threading running +2023-08-22,18:07:53.695 - INFO - threading running +2023-08-22,18:07:53.704 - INFO - threading running +2023-08-22,18:07:53.715 - INFO - threading running +2023-08-22,18:07:53.725 - INFO - threading running +2023-08-22,18:07:53.736 - INFO - threading running +2023-08-22,18:07:53.746 - INFO - threading running +2023-08-22,18:07:53.756 - INFO - threading running +2023-08-22,18:07:53.767 - INFO - threading running +2023-08-22,18:07:53.776 - INFO - threading running +2023-08-22,18:07:53.787 - INFO - threading running +2023-08-22,18:07:53.797 - INFO - threading running +2023-08-22,18:07:53.807 - INFO - threading running +2023-08-22,18:07:53.816 - INFO - threading running +2023-08-22,18:07:53.827 - INFO - threading running +2023-08-22,18:07:53.838 - INFO - threading running +2023-08-22,18:07:53.847 - INFO - threading running +2023-08-22,18:07:53.857 - INFO - threading running +2023-08-22,18:07:53.867 - INFO - threading running +2023-08-22,18:07:53.878 - INFO - threading running +2023-08-22,18:07:53.887 - INFO - threading running +2023-08-22,18:07:53.897 - INFO - threading running +2023-08-22,18:07:53.907 - INFO - threading running +2023-08-22,18:07:53.918 - INFO - threading running +2023-08-22,18:07:53.927 - INFO - threading running +2023-08-22,18:07:53.937 - INFO - threading running +2023-08-22,18:07:53.947 - INFO - threading running +2023-08-22,18:07:53.957 - INFO - threading running +2023-08-22,18:07:53.967 - INFO - threading running +2023-08-22,18:07:53.977 - INFO - threading running +2023-08-22,18:07:53.988 - INFO - threading running +2023-08-22,18:07:53.997 - INFO - threading running +2023-08-22,18:07:54.007 - INFO - threading running +2023-08-22,18:07:54.017 - INFO - threading running +2023-08-22,18:07:54.028 - INFO - threading running +2023-08-22,18:07:54.037 - INFO - threading running +2023-08-22,18:07:54.047 - INFO - threading running +2023-08-22,18:07:54.057 - INFO - threading running +2023-08-22,18:07:54.065 - INFO - ---------------------------------------------------- +2023-08-22,18:07:54.065 - INFO - 59th iteration +2023-08-22,18:07:54.065 - INFO - average ll reward: 0.1111853654 +2023-08-22,18:07:54.066 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:54.067 - INFO - updating finished +2023-08-22,18:07:58.157 - INFO - threading running +2023-08-22,18:07:58.171 - INFO - threading running +2023-08-22,18:07:58.182 - INFO - threading running +2023-08-22,18:07:58.193 - INFO - threading running +2023-08-22,18:07:58.202 - INFO - threading running +2023-08-22,18:07:58.212 - INFO - threading running +2023-08-22,18:07:58.222 - INFO - threading running +2023-08-22,18:07:58.232 - INFO - threading running +2023-08-22,18:07:58.243 - INFO - threading running +2023-08-22,18:07:58.253 - INFO - threading running +2023-08-22,18:07:58.264 - INFO - threading running +2023-08-22,18:07:58.275 - INFO - threading running +2023-08-22,18:07:58.285 - INFO - threading running +2023-08-22,18:07:58.295 - INFO - threading running +2023-08-22,18:07:58.305 - INFO - threading running +2023-08-22,18:07:58.315 - INFO - threading running +2023-08-22,18:07:58.326 - INFO - threading running +2023-08-22,18:07:58.336 - INFO - threading running +2023-08-22,18:07:58.345 - INFO - threading running +2023-08-22,18:07:58.355 - INFO - threading running +2023-08-22,18:07:58.366 - INFO - threading running +2023-08-22,18:07:58.375 - INFO - threading running +2023-08-22,18:07:58.385 - INFO - threading running +2023-08-22,18:07:58.395 - INFO - threading running +2023-08-22,18:07:58.405 - INFO - threading running +2023-08-22,18:07:58.415 - INFO - threading running +2023-08-22,18:07:58.426 - INFO - threading running +2023-08-22,18:07:58.436 - INFO - threading running +2023-08-22,18:07:58.446 - INFO - threading running +2023-08-22,18:07:58.456 - INFO - threading running +2023-08-22,18:07:58.467 - INFO - threading running +2023-08-22,18:07:58.476 - INFO - threading running +2023-08-22,18:07:58.486 - INFO - threading running +2023-08-22,18:07:58.496 - INFO - threading running +2023-08-22,18:07:58.507 - INFO - threading running +2023-08-22,18:07:58.517 - INFO - threading running +2023-08-22,18:07:58.527 - INFO - threading running +2023-08-22,18:07:58.537 - INFO - threading running +2023-08-22,18:07:58.547 - INFO - threading running +2023-08-22,18:07:58.557 - INFO - threading running +2023-08-22,18:07:58.567 - INFO - threading running +2023-08-22,18:07:58.577 - INFO - threading running +2023-08-22,18:07:58.587 - INFO - threading running +2023-08-22,18:07:58.597 - INFO - threading running +2023-08-22,18:07:58.607 - INFO - threading running +2023-08-22,18:07:58.617 - INFO - threading running +2023-08-22,18:07:58.628 - INFO - threading running +2023-08-22,18:07:58.637 - INFO - threading running +2023-08-22,18:07:58.647 - INFO - threading running +2023-08-22,18:07:58.657 - INFO - threading running +2023-08-22,18:07:58.667 - INFO - threading running +2023-08-22,18:07:58.678 - INFO - threading running +2023-08-22,18:07:58.687 - INFO - threading running +2023-08-22,18:07:58.697 - INFO - threading running +2023-08-22,18:07:58.707 - INFO - threading running +2023-08-22,18:07:58.717 - INFO - threading running +2023-08-22,18:07:58.727 - INFO - threading running +2023-08-22,18:07:58.737 - INFO - threading running +2023-08-22,18:07:58.747 - INFO - threading running +2023-08-22,18:07:58.754 - INFO - ---------------------------------------------------- +2023-08-22,18:07:58.754 - INFO - 60th iteration +2023-08-22,18:07:58.754 - INFO - average ll reward: 0.0932303344 +2023-08-22,18:07:58.754 - INFO - ---------------------------------------------------- + +2023-08-22,18:07:58.757 - INFO - updating finished +2023-08-22,18:08:02.816 - INFO - threading running +2023-08-22,18:08:02.826 - INFO - threading running +2023-08-22,18:08:02.836 - INFO - threading running +2023-08-22,18:08:02.846 - INFO - threading running +2023-08-22,18:08:02.856 - INFO - threading running +2023-08-22,18:08:02.866 - INFO - threading running +2023-08-22,18:08:02.876 - INFO - threading running +2023-08-22,18:08:02.887 - INFO - threading running +2023-08-22,18:08:02.896 - INFO - threading running +2023-08-22,18:08:02.906 - INFO - threading running +2023-08-22,18:08:02.916 - INFO - threading running +2023-08-22,18:08:02.926 - INFO - threading running +2023-08-22,18:08:02.936 - INFO - threading running +2023-08-22,18:08:02.946 - INFO - threading running +2023-08-22,18:08:02.956 - INFO - threading running +2023-08-22,18:08:02.966 - INFO - threading running +2023-08-22,18:08:02.977 - INFO - threading running +2023-08-22,18:08:02.987 - INFO - threading running +2023-08-22,18:08:02.996 - INFO - threading running +2023-08-22,18:08:03.006 - INFO - threading running +2023-08-22,18:08:03.016 - INFO - threading running +2023-08-22,18:08:03.026 - INFO - threading running +2023-08-22,18:08:03.036 - INFO - threading running +2023-08-22,18:08:03.046 - INFO - threading running +2023-08-22,18:08:03.056 - INFO - threading running +2023-08-22,18:08:03.066 - INFO - threading running +2023-08-22,18:08:03.076 - INFO - threading running +2023-08-22,18:08:03.086 - INFO - threading running +2023-08-22,18:08:03.096 - INFO - threading running +2023-08-22,18:08:03.107 - INFO - threading running +2023-08-22,18:08:03.117 - INFO - threading running +2023-08-22,18:08:03.127 - INFO - threading running +2023-08-22,18:08:03.136 - INFO - threading running +2023-08-22,18:08:03.146 - INFO - threading running +2023-08-22,18:08:03.157 - INFO - threading running +2023-08-22,18:08:03.167 - INFO - threading running +2023-08-22,18:08:03.177 - INFO - threading running +2023-08-22,18:08:03.187 - INFO - threading running +2023-08-22,18:08:03.197 - INFO - threading running +2023-08-22,18:08:03.207 - INFO - threading running +2023-08-22,18:08:03.217 - INFO - threading running +2023-08-22,18:08:03.228 - INFO - threading running +2023-08-22,18:08:03.238 - INFO - threading running +2023-08-22,18:08:03.247 - INFO - threading running +2023-08-22,18:08:03.257 - INFO - threading running +2023-08-22,18:08:03.267 - INFO - threading running +2023-08-22,18:08:03.278 - INFO - threading running +2023-08-22,18:08:03.288 - INFO - threading running +2023-08-22,18:08:03.298 - INFO - threading running +2023-08-22,18:08:03.308 - INFO - threading running +2023-08-22,18:08:03.319 - INFO - threading running +2023-08-22,18:08:03.328 - INFO - threading running +2023-08-22,18:08:03.338 - INFO - threading running +2023-08-22,18:08:03.348 - INFO - threading running +2023-08-22,18:08:03.358 - INFO - threading running +2023-08-22,18:08:03.368 - INFO - threading running +2023-08-22,18:08:03.378 - INFO - threading running +2023-08-22,18:08:03.388 - INFO - threading running +2023-08-22,18:08:03.398 - INFO - threading running +2023-08-22,18:08:03.409 - INFO - threading running +2023-08-22,18:08:03.419 - INFO - threading running +2023-08-22,18:08:03.429 - INFO - threading running +2023-08-22,18:08:03.439 - INFO - threading running +2023-08-22,18:08:03.441 - INFO - ---------------------------------------------------- +2023-08-22,18:08:03.441 - INFO - 61th iteration +2023-08-22,18:08:03.441 - INFO - average ll reward: 0.1033583346 +2023-08-22,18:08:03.441 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:03.449 - INFO - updating finished +2023-08-22,18:08:07.520 - INFO - threading running +2023-08-22,18:08:07.531 - INFO - threading running +2023-08-22,18:08:07.540 - INFO - threading running +2023-08-22,18:08:07.551 - INFO - threading running +2023-08-22,18:08:07.561 - INFO - threading running +2023-08-22,18:08:07.572 - INFO - threading running +2023-08-22,18:08:07.583 - INFO - threading running +2023-08-22,18:08:07.594 - INFO - threading running +2023-08-22,18:08:07.604 - INFO - threading running +2023-08-22,18:08:07.614 - INFO - threading running +2023-08-22,18:08:07.624 - INFO - threading running +2023-08-22,18:08:07.634 - INFO - threading running +2023-08-22,18:08:07.644 - INFO - threading running +2023-08-22,18:08:07.654 - INFO - threading running +2023-08-22,18:08:07.665 - INFO - threading running +2023-08-22,18:08:07.675 - INFO - threading running +2023-08-22,18:08:07.685 - INFO - threading running +2023-08-22,18:08:07.695 - INFO - threading running +2023-08-22,18:08:07.705 - INFO - threading running +2023-08-22,18:08:07.715 - INFO - threading running +2023-08-22,18:08:07.725 - INFO - threading running +2023-08-22,18:08:07.735 - INFO - threading running +2023-08-22,18:08:07.745 - INFO - threading running +2023-08-22,18:08:07.756 - INFO - threading running +2023-08-22,18:08:07.767 - INFO - threading running +2023-08-22,18:08:07.778 - INFO - threading running +2023-08-22,18:08:07.788 - INFO - threading running +2023-08-22,18:08:07.797 - INFO - threading running +2023-08-22,18:08:07.807 - INFO - threading running +2023-08-22,18:08:07.817 - INFO - threading running +2023-08-22,18:08:07.828 - INFO - threading running +2023-08-22,18:08:07.837 - INFO - threading running +2023-08-22,18:08:07.847 - INFO - threading running +2023-08-22,18:08:07.857 - INFO - threading running +2023-08-22,18:08:07.867 - INFO - threading running +2023-08-22,18:08:07.877 - INFO - threading running +2023-08-22,18:08:07.887 - INFO - threading running +2023-08-22,18:08:07.897 - INFO - threading running +2023-08-22,18:08:07.907 - INFO - threading running +2023-08-22,18:08:07.917 - INFO - threading running +2023-08-22,18:08:07.928 - INFO - threading running +2023-08-22,18:08:07.938 - INFO - threading running +2023-08-22,18:08:07.947 - INFO - threading running +2023-08-22,18:08:07.957 - INFO - threading running +2023-08-22,18:08:07.967 - INFO - threading running +2023-08-22,18:08:07.977 - INFO - threading running +2023-08-22,18:08:07.988 - INFO - threading running +2023-08-22,18:08:07.997 - INFO - threading running +2023-08-22,18:08:08.007 - INFO - threading running +2023-08-22,18:08:08.017 - INFO - threading running +2023-08-22,18:08:08.022 - INFO - ---------------------------------------------------- +2023-08-22,18:08:08.022 - INFO - 62th iteration +2023-08-22,18:08:08.022 - INFO - average ll reward: 0.0916777122 +2023-08-22,18:08:08.022 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:08.027 - INFO - updating finished +2023-08-22,18:08:12.085 - INFO - threading running +2023-08-22,18:08:12.100 - INFO - threading running +2023-08-22,18:08:12.111 - INFO - threading running +2023-08-22,18:08:12.120 - INFO - threading running +2023-08-22,18:08:12.130 - INFO - threading running +2023-08-22,18:08:12.140 - INFO - threading running +2023-08-22,18:08:12.150 - INFO - threading running +2023-08-22,18:08:12.161 - INFO - threading running +2023-08-22,18:08:12.171 - INFO - threading running +2023-08-22,18:08:12.182 - INFO - threading running +2023-08-22,18:08:12.191 - INFO - threading running +2023-08-22,18:08:12.201 - INFO - threading running +2023-08-22,18:08:12.211 - INFO - threading running +2023-08-22,18:08:12.221 - INFO - threading running +2023-08-22,18:08:12.231 - INFO - threading running +2023-08-22,18:08:12.241 - INFO - threading running +2023-08-22,18:08:12.252 - INFO - threading running +2023-08-22,18:08:12.262 - INFO - threading running +2023-08-22,18:08:12.271 - INFO - threading running +2023-08-22,18:08:12.281 - INFO - threading running +2023-08-22,18:08:12.291 - INFO - threading running +2023-08-22,18:08:12.301 - INFO - threading running +2023-08-22,18:08:12.311 - INFO - threading running +2023-08-22,18:08:12.322 - INFO - threading running +2023-08-22,18:08:12.332 - INFO - threading running +2023-08-22,18:08:12.343 - INFO - threading running +2023-08-22,18:08:12.352 - INFO - threading running +2023-08-22,18:08:12.362 - INFO - threading running +2023-08-22,18:08:12.372 - INFO - threading running +2023-08-22,18:08:12.382 - INFO - threading running +2023-08-22,18:08:12.392 - INFO - threading running +2023-08-22,18:08:12.402 - INFO - threading running +2023-08-22,18:08:12.413 - INFO - threading running +2023-08-22,18:08:12.423 - INFO - threading running +2023-08-22,18:08:12.433 - INFO - threading running +2023-08-22,18:08:12.442 - INFO - threading running +2023-08-22,18:08:12.452 - INFO - threading running +2023-08-22,18:08:12.462 - INFO - threading running +2023-08-22,18:08:12.472 - INFO - threading running +2023-08-22,18:08:12.483 - INFO - threading running +2023-08-22,18:08:12.492 - INFO - threading running +2023-08-22,18:08:12.503 - INFO - threading running +2023-08-22,18:08:12.512 - INFO - threading running +2023-08-22,18:08:12.523 - INFO - threading running +2023-08-22,18:08:12.532 - INFO - threading running +2023-08-22,18:08:12.543 - INFO - threading running +2023-08-22,18:08:12.554 - INFO - threading running +2023-08-22,18:08:12.564 - INFO - threading running +2023-08-22,18:08:12.574 - INFO - threading running +2023-08-22,18:08:12.584 - INFO - threading running +2023-08-22,18:08:12.594 - INFO - threading running +2023-08-22,18:08:12.605 - INFO - threading running +2023-08-22,18:08:12.614 - INFO - threading running +2023-08-22,18:08:12.625 - INFO - threading running +2023-08-22,18:08:12.635 - INFO - threading running +2023-08-22,18:08:12.646 - INFO - threading running +2023-08-22,18:08:12.657 - INFO - threading running +2023-08-22,18:08:12.664 - INFO - ---------------------------------------------------- +2023-08-22,18:08:12.664 - INFO - 63th iteration +2023-08-22,18:08:12.664 - INFO - average ll reward: 0.0889453081 +2023-08-22,18:08:12.664 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:12.666 - INFO - updating finished +2023-08-22,18:08:16.730 - INFO - threading running +2023-08-22,18:08:16.742 - INFO - threading running +2023-08-22,18:08:16.753 - INFO - threading running +2023-08-22,18:08:16.763 - INFO - threading running +2023-08-22,18:08:16.773 - INFO - threading running +2023-08-22,18:08:16.783 - INFO - threading running +2023-08-22,18:08:16.793 - INFO - threading running +2023-08-22,18:08:16.804 - INFO - threading running +2023-08-22,18:08:16.813 - INFO - threading running +2023-08-22,18:08:16.823 - INFO - threading running +2023-08-22,18:08:16.833 - INFO - threading running +2023-08-22,18:08:16.843 - INFO - threading running +2023-08-22,18:08:16.854 - INFO - threading running +2023-08-22,18:08:16.863 - INFO - threading running +2023-08-22,18:08:16.873 - INFO - threading running +2023-08-22,18:08:16.884 - INFO - threading running +2023-08-22,18:08:16.893 - INFO - threading running +2023-08-22,18:08:16.903 - INFO - threading running +2023-08-22,18:08:16.913 - INFO - threading running +2023-08-22,18:08:16.923 - INFO - threading running +2023-08-22,18:08:16.933 - INFO - threading running +2023-08-22,18:08:16.943 - INFO - threading running +2023-08-22,18:08:16.953 - INFO - threading running +2023-08-22,18:08:16.963 - INFO - threading running +2023-08-22,18:08:16.973 - INFO - threading running +2023-08-22,18:08:16.983 - INFO - threading running +2023-08-22,18:08:16.993 - INFO - threading running +2023-08-22,18:08:17.003 - INFO - threading running +2023-08-22,18:08:17.014 - INFO - threading running +2023-08-22,18:08:17.024 - INFO - threading running +2023-08-22,18:08:17.035 - INFO - threading running +2023-08-22,18:08:17.046 - INFO - threading running +2023-08-22,18:08:17.055 - INFO - threading running +2023-08-22,18:08:17.066 - INFO - threading running +2023-08-22,18:08:17.075 - INFO - threading running +2023-08-22,18:08:17.085 - INFO - threading running +2023-08-22,18:08:17.095 - INFO - threading running +2023-08-22,18:08:17.105 - INFO - threading running +2023-08-22,18:08:17.115 - INFO - threading running +2023-08-22,18:08:17.125 - INFO - threading running +2023-08-22,18:08:17.136 - INFO - threading running +2023-08-22,18:08:17.146 - INFO - threading running +2023-08-22,18:08:17.157 - INFO - threading running +2023-08-22,18:08:17.168 - INFO - threading running +2023-08-22,18:08:17.178 - INFO - threading running +2023-08-22,18:08:17.187 - INFO - threading running +2023-08-22,18:08:17.198 - INFO - threading running +2023-08-22,18:08:17.208 - INFO - threading running +2023-08-22,18:08:17.218 - INFO - threading running +2023-08-22,18:08:17.229 - INFO - threading running +2023-08-22,18:08:17.238 - INFO - threading running +2023-08-22,18:08:17.248 - INFO - threading running +2023-08-22,18:08:17.259 - INFO - threading running +2023-08-22,18:08:17.268 - INFO - threading running +2023-08-22,18:08:17.279 - INFO - threading running +2023-08-22,18:08:17.288 - INFO - threading running +2023-08-22,18:08:17.298 - INFO - threading running +2023-08-22,18:08:17.309 - INFO - threading running +2023-08-22,18:08:17.315 - INFO - ---------------------------------------------------- +2023-08-22,18:08:17.315 - INFO - 64th iteration +2023-08-22,18:08:17.315 - INFO - average ll reward: 0.0876856323 +2023-08-22,18:08:17.315 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:17.319 - INFO - updating finished +2023-08-22,18:08:21.359 - INFO - threading running +2023-08-22,18:08:21.372 - INFO - threading running +2023-08-22,18:08:21.383 - INFO - threading running +2023-08-22,18:08:21.392 - INFO - threading running +2023-08-22,18:08:21.402 - INFO - threading running +2023-08-22,18:08:21.412 - INFO - threading running +2023-08-22,18:08:21.423 - INFO - threading running +2023-08-22,18:08:21.432 - INFO - threading running +2023-08-22,18:08:21.442 - INFO - threading running +2023-08-22,18:08:21.452 - INFO - threading running +2023-08-22,18:08:21.463 - INFO - threading running +2023-08-22,18:08:21.472 - INFO - threading running +2023-08-22,18:08:21.482 - INFO - threading running +2023-08-22,18:08:21.493 - INFO - threading running +2023-08-22,18:08:21.502 - INFO - threading running +2023-08-22,18:08:21.512 - INFO - threading running +2023-08-22,18:08:21.523 - INFO - threading running +2023-08-22,18:08:21.532 - INFO - threading running +2023-08-22,18:08:21.542 - INFO - threading running +2023-08-22,18:08:21.553 - INFO - threading running +2023-08-22,18:08:21.562 - INFO - threading running +2023-08-22,18:08:21.572 - INFO - threading running +2023-08-22,18:08:21.582 - INFO - threading running +2023-08-22,18:08:21.592 - INFO - threading running +2023-08-22,18:08:21.602 - INFO - threading running +2023-08-22,18:08:21.613 - INFO - threading running +2023-08-22,18:08:21.623 - INFO - threading running +2023-08-22,18:08:21.633 - INFO - threading running +2023-08-22,18:08:21.643 - INFO - threading running +2023-08-22,18:08:21.653 - INFO - threading running +2023-08-22,18:08:21.663 - INFO - threading running +2023-08-22,18:08:21.673 - INFO - threading running +2023-08-22,18:08:21.684 - INFO - threading running +2023-08-22,18:08:21.694 - INFO - threading running +2023-08-22,18:08:21.705 - INFO - threading running +2023-08-22,18:08:21.715 - INFO - threading running +2023-08-22,18:08:21.725 - INFO - threading running +2023-08-22,18:08:21.735 - INFO - threading running +2023-08-22,18:08:21.745 - INFO - threading running +2023-08-22,18:08:21.755 - INFO - threading running +2023-08-22,18:08:21.765 - INFO - threading running +2023-08-22,18:08:21.775 - INFO - threading running +2023-08-22,18:08:21.785 - INFO - threading running +2023-08-22,18:08:21.795 - INFO - threading running +2023-08-22,18:08:21.805 - INFO - threading running +2023-08-22,18:08:21.816 - INFO - threading running +2023-08-22,18:08:21.826 - INFO - threading running +2023-08-22,18:08:21.836 - INFO - threading running +2023-08-22,18:08:21.846 - INFO - threading running +2023-08-22,18:08:21.857 - INFO - threading running +2023-08-22,18:08:21.868 - INFO - threading running +2023-08-22,18:08:21.871 - INFO - ---------------------------------------------------- +2023-08-22,18:08:21.872 - INFO - 65th iteration +2023-08-22,18:08:21.872 - INFO - average ll reward: 0.1113211861 +2023-08-22,18:08:21.872 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:21.878 - INFO - updating finished +2023-08-22,18:08:25.914 - INFO - threading running +2023-08-22,18:08:25.921 - INFO - threading running +2023-08-22,18:08:25.931 - INFO - threading running +2023-08-22,18:08:25.941 - INFO - threading running +2023-08-22,18:08:25.951 - INFO - threading running +2023-08-22,18:08:25.961 - INFO - threading running +2023-08-22,18:08:25.971 - INFO - threading running +2023-08-22,18:08:25.982 - INFO - threading running +2023-08-22,18:08:25.992 - INFO - threading running +2023-08-22,18:08:26.002 - INFO - threading running +2023-08-22,18:08:26.012 - INFO - threading running +2023-08-22,18:08:26.022 - INFO - threading running +2023-08-22,18:08:26.032 - INFO - threading running +2023-08-22,18:08:26.042 - INFO - threading running +2023-08-22,18:08:26.053 - INFO - threading running +2023-08-22,18:08:26.064 - INFO - threading running +2023-08-22,18:08:26.075 - INFO - threading running +2023-08-22,18:08:26.085 - INFO - threading running +2023-08-22,18:08:26.096 - INFO - threading running +2023-08-22,18:08:26.105 - INFO - threading running +2023-08-22,18:08:26.115 - INFO - threading running +2023-08-22,18:08:26.125 - INFO - threading running +2023-08-22,18:08:26.135 - INFO - threading running +2023-08-22,18:08:26.145 - INFO - threading running +2023-08-22,18:08:26.155 - INFO - threading running +2023-08-22,18:08:26.166 - INFO - threading running +2023-08-22,18:08:26.175 - INFO - threading running +2023-08-22,18:08:26.185 - INFO - threading running +2023-08-22,18:08:26.196 - INFO - threading running +2023-08-22,18:08:26.206 - INFO - threading running +2023-08-22,18:08:26.216 - INFO - threading running +2023-08-22,18:08:26.226 - INFO - threading running +2023-08-22,18:08:26.236 - INFO - threading running +2023-08-22,18:08:26.246 - INFO - threading running +2023-08-22,18:08:26.257 - INFO - threading running +2023-08-22,18:08:26.266 - INFO - threading running +2023-08-22,18:08:26.276 - INFO - threading running +2023-08-22,18:08:26.286 - INFO - threading running +2023-08-22,18:08:26.296 - INFO - threading running +2023-08-22,18:08:26.306 - INFO - threading running +2023-08-22,18:08:26.316 - INFO - threading running +2023-08-22,18:08:26.327 - INFO - threading running +2023-08-22,18:08:26.336 - INFO - threading running +2023-08-22,18:08:26.346 - INFO - threading running +2023-08-22,18:08:26.356 - INFO - threading running +2023-08-22,18:08:26.366 - INFO - threading running +2023-08-22,18:08:26.376 - INFO - threading running +2023-08-22,18:08:26.386 - INFO - threading running +2023-08-22,18:08:26.396 - INFO - threading running +2023-08-22,18:08:26.406 - INFO - threading running +2023-08-22,18:08:26.416 - INFO - threading running +2023-08-22,18:08:26.427 - INFO - threading running +2023-08-22,18:08:26.437 - INFO - threading running +2023-08-22,18:08:26.445 - INFO - ---------------------------------------------------- +2023-08-22,18:08:26.445 - INFO - 66th iteration +2023-08-22,18:08:26.445 - INFO - average ll reward: 0.1253480547 +2023-08-22,18:08:26.445 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:26.448 - INFO - updating finished +2023-08-22,18:08:30.494 - INFO - threading running +2023-08-22,18:08:30.510 - INFO - threading running +2023-08-22,18:08:30.520 - INFO - threading running +2023-08-22,18:08:30.530 - INFO - threading running +2023-08-22,18:08:30.540 - INFO - threading running +2023-08-22,18:08:30.551 - INFO - threading running +2023-08-22,18:08:30.560 - INFO - threading running +2023-08-22,18:08:30.570 - INFO - threading running +2023-08-22,18:08:30.580 - INFO - threading running +2023-08-22,18:08:30.591 - INFO - threading running +2023-08-22,18:08:30.601 - INFO - threading running +2023-08-22,18:08:30.611 - INFO - threading running +2023-08-22,18:08:30.621 - INFO - threading running +2023-08-22,18:08:30.631 - INFO - threading running +2023-08-22,18:08:30.641 - INFO - threading running +2023-08-22,18:08:30.651 - INFO - threading running +2023-08-22,18:08:30.661 - INFO - threading running +2023-08-22,18:08:30.671 - INFO - threading running +2023-08-22,18:08:30.681 - INFO - threading running +2023-08-22,18:08:30.691 - INFO - threading running +2023-08-22,18:08:30.701 - INFO - threading running +2023-08-22,18:08:30.711 - INFO - threading running +2023-08-22,18:08:30.721 - INFO - threading running +2023-08-22,18:08:30.731 - INFO - threading running +2023-08-22,18:08:30.741 - INFO - threading running +2023-08-22,18:08:30.751 - INFO - threading running +2023-08-22,18:08:30.761 - INFO - threading running +2023-08-22,18:08:30.771 - INFO - threading running +2023-08-22,18:08:30.781 - INFO - threading running +2023-08-22,18:08:30.792 - INFO - threading running +2023-08-22,18:08:30.803 - INFO - threading running +2023-08-22,18:08:30.814 - INFO - threading running +2023-08-22,18:08:30.824 - INFO - threading running +2023-08-22,18:08:30.835 - INFO - threading running +2023-08-22,18:08:30.845 - INFO - threading running +2023-08-22,18:08:30.855 - INFO - threading running +2023-08-22,18:08:30.866 - INFO - threading running +2023-08-22,18:08:30.876 - INFO - threading running +2023-08-22,18:08:30.886 - INFO - threading running +2023-08-22,18:08:30.897 - INFO - threading running +2023-08-22,18:08:30.906 - INFO - threading running +2023-08-22,18:08:30.916 - INFO - threading running +2023-08-22,18:08:30.927 - INFO - threading running +2023-08-22,18:08:30.937 - INFO - threading running +2023-08-22,18:08:30.946 - INFO - threading running +2023-08-22,18:08:30.956 - INFO - threading running +2023-08-22,18:08:30.967 - INFO - threading running +2023-08-22,18:08:30.976 - INFO - threading running +2023-08-22,18:08:30.986 - INFO - threading running +2023-08-22,18:08:30.996 - INFO - threading running +2023-08-22,18:08:31.007 - INFO - threading running +2023-08-22,18:08:31.016 - INFO - threading running +2023-08-22,18:08:31.026 - INFO - threading running +2023-08-22,18:08:31.036 - INFO - threading running +2023-08-22,18:08:31.046 - INFO - threading running +2023-08-22,18:08:31.056 - INFO - threading running +2023-08-22,18:08:31.066 - INFO - threading running +2023-08-22,18:08:31.077 - INFO - threading running +2023-08-22,18:08:31.086 - INFO - threading running +2023-08-22,18:08:31.096 - INFO - threading running +2023-08-22,18:08:31.106 - INFO - threading running +2023-08-22,18:08:31.108 - INFO - ---------------------------------------------------- +2023-08-22,18:08:31.109 - INFO - 67th iteration +2023-08-22,18:08:31.109 - INFO - average ll reward: 0.1014062391 +2023-08-22,18:08:31.109 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:31.117 - INFO - updating finished +2023-08-22,18:08:35.162 - INFO - threading running +2023-08-22,18:08:35.174 - INFO - threading running +2023-08-22,18:08:35.183 - INFO - threading running +2023-08-22,18:08:35.193 - INFO - threading running +2023-08-22,18:08:35.203 - INFO - threading running +2023-08-22,18:08:35.213 - INFO - threading running +2023-08-22,18:08:35.223 - INFO - threading running +2023-08-22,18:08:35.234 - INFO - threading running +2023-08-22,18:08:35.244 - INFO - threading running +2023-08-22,18:08:35.254 - INFO - threading running +2023-08-22,18:08:35.264 - INFO - threading running +2023-08-22,18:08:35.274 - INFO - threading running +2023-08-22,18:08:35.284 - INFO - threading running +2023-08-22,18:08:35.294 - INFO - threading running +2023-08-22,18:08:35.305 - INFO - threading running +2023-08-22,18:08:35.315 - INFO - threading running +2023-08-22,18:08:35.326 - INFO - threading running +2023-08-22,18:08:35.336 - INFO - threading running +2023-08-22,18:08:35.346 - INFO - threading running +2023-08-22,18:08:35.356 - INFO - threading running +2023-08-22,18:08:35.367 - INFO - threading running +2023-08-22,18:08:35.378 - INFO - threading running +2023-08-22,18:08:35.389 - INFO - threading running +2023-08-22,18:08:35.399 - INFO - threading running +2023-08-22,18:08:35.409 - INFO - threading running +2023-08-22,18:08:35.419 - INFO - threading running +2023-08-22,18:08:35.429 - INFO - threading running +2023-08-22,18:08:35.439 - INFO - threading running +2023-08-22,18:08:35.449 - INFO - threading running +2023-08-22,18:08:35.460 - INFO - threading running +2023-08-22,18:08:35.469 - INFO - threading running +2023-08-22,18:08:35.479 - INFO - threading running +2023-08-22,18:08:35.489 - INFO - threading running +2023-08-22,18:08:35.499 - INFO - threading running +2023-08-22,18:08:35.509 - INFO - threading running +2023-08-22,18:08:35.520 - INFO - threading running +2023-08-22,18:08:35.530 - INFO - threading running +2023-08-22,18:08:35.540 - INFO - threading running +2023-08-22,18:08:35.550 - INFO - threading running +2023-08-22,18:08:35.560 - INFO - threading running +2023-08-22,18:08:35.570 - INFO - threading running +2023-08-22,18:08:35.580 - INFO - threading running +2023-08-22,18:08:35.590 - INFO - threading running +2023-08-22,18:08:35.600 - INFO - threading running +2023-08-22,18:08:35.611 - INFO - threading running +2023-08-22,18:08:35.621 - INFO - threading running +2023-08-22,18:08:35.631 - INFO - threading running +2023-08-22,18:08:35.641 - INFO - threading running +2023-08-22,18:08:35.652 - INFO - threading running +2023-08-22,18:08:35.661 - INFO - threading running +2023-08-22,18:08:35.671 - INFO - threading running +2023-08-22,18:08:35.682 - INFO - threading running +2023-08-22,18:08:35.691 - INFO - threading running +2023-08-22,18:08:35.701 - INFO - threading running +2023-08-22,18:08:35.711 - INFO - threading running +2023-08-22,18:08:35.721 - INFO - threading running +2023-08-22,18:08:35.731 - INFO - threading running +2023-08-22,18:08:35.741 - INFO - threading running +2023-08-22,18:08:35.751 - INFO - threading running +2023-08-22,18:08:35.761 - INFO - threading running +2023-08-22,18:08:35.772 - INFO - threading running +2023-08-22,18:08:35.781 - INFO - threading running +2023-08-22,18:08:35.789 - INFO - ---------------------------------------------------- +2023-08-22,18:08:35.789 - INFO - 68th iteration +2023-08-22,18:08:35.789 - INFO - average ll reward: 0.0753285667 +2023-08-22,18:08:35.789 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:35.791 - INFO - updating finished +2023-08-22,18:08:39.939 - INFO - threading running +2023-08-22,18:08:39.953 - INFO - threading running +2023-08-22,18:08:39.964 - INFO - threading running +2023-08-22,18:08:39.974 - INFO - threading running +2023-08-22,18:08:39.983 - INFO - threading running +2023-08-22,18:08:39.994 - INFO - threading running +2023-08-22,18:08:40.004 - INFO - threading running +2023-08-22,18:08:40.013 - INFO - threading running +2023-08-22,18:08:40.023 - INFO - threading running +2023-08-22,18:08:40.033 - INFO - threading running +2023-08-22,18:08:40.043 - INFO - threading running +2023-08-22,18:08:40.053 - INFO - threading running +2023-08-22,18:08:40.064 - INFO - threading running +2023-08-22,18:08:40.074 - INFO - threading running +2023-08-22,18:08:40.085 - INFO - threading running +2023-08-22,18:08:40.095 - INFO - threading running +2023-08-22,18:08:40.106 - INFO - threading running +2023-08-22,18:08:40.116 - INFO - threading running +2023-08-22,18:08:40.127 - INFO - threading running +2023-08-22,18:08:40.138 - INFO - threading running +2023-08-22,18:08:40.148 - INFO - threading running +2023-08-22,18:08:40.157 - INFO - threading running +2023-08-22,18:08:40.167 - INFO - threading running +2023-08-22,18:08:40.178 - INFO - threading running +2023-08-22,18:08:40.188 - INFO - threading running +2023-08-22,18:08:40.199 - INFO - threading running +2023-08-22,18:08:40.208 - INFO - threading running +2023-08-22,18:08:40.218 - INFO - threading running +2023-08-22,18:08:40.228 - INFO - threading running +2023-08-22,18:08:40.239 - INFO - threading running +2023-08-22,18:08:40.248 - INFO - threading running +2023-08-22,18:08:40.258 - INFO - threading running +2023-08-22,18:08:40.268 - INFO - threading running +2023-08-22,18:08:40.278 - INFO - threading running +2023-08-22,18:08:40.288 - INFO - threading running +2023-08-22,18:08:40.298 - INFO - threading running +2023-08-22,18:08:40.308 - INFO - threading running +2023-08-22,18:08:40.318 - INFO - threading running +2023-08-22,18:08:40.328 - INFO - threading running +2023-08-22,18:08:40.339 - INFO - threading running +2023-08-22,18:08:40.348 - INFO - threading running +2023-08-22,18:08:40.358 - INFO - threading running +2023-08-22,18:08:40.369 - INFO - threading running +2023-08-22,18:08:40.380 - INFO - threading running +2023-08-22,18:08:40.390 - INFO - threading running +2023-08-22,18:08:40.399 - INFO - threading running +2023-08-22,18:08:40.409 - INFO - threading running +2023-08-22,18:08:40.420 - INFO - threading running +2023-08-22,18:08:40.429 - INFO - threading running +2023-08-22,18:08:40.439 - INFO - threading running +2023-08-22,18:08:40.449 - INFO - threading running +2023-08-22,18:08:40.459 - INFO - threading running +2023-08-22,18:08:40.469 - INFO - threading running +2023-08-22,18:08:40.479 - INFO - threading running +2023-08-22,18:08:40.484 - INFO - ---------------------------------------------------- +2023-08-22,18:08:40.485 - INFO - 69th iteration +2023-08-22,18:08:40.485 - INFO - average ll reward: 0.0786415392 +2023-08-22,18:08:40.485 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:40.490 - INFO - updating finished +2023-08-22,18:08:44.667 - INFO - threading running +2023-08-22,18:08:44.681 - INFO - threading running +2023-08-22,18:08:44.691 - INFO - threading running +2023-08-22,18:08:44.701 - INFO - threading running +2023-08-22,18:08:44.711 - INFO - threading running +2023-08-22,18:08:44.721 - INFO - threading running +2023-08-22,18:08:44.732 - INFO - threading running +2023-08-22,18:08:44.743 - INFO - threading running +2023-08-22,18:08:44.752 - INFO - threading running +2023-08-22,18:08:44.763 - INFO - threading running +2023-08-22,18:08:44.773 - INFO - threading running +2023-08-22,18:08:44.783 - INFO - threading running +2023-08-22,18:08:44.792 - INFO - threading running +2023-08-22,18:08:44.802 - INFO - threading running +2023-08-22,18:08:44.813 - INFO - threading running +2023-08-22,18:08:44.822 - INFO - threading running +2023-08-22,18:08:44.833 - INFO - threading running +2023-08-22,18:08:44.843 - INFO - threading running +2023-08-22,18:08:44.853 - INFO - threading running +2023-08-22,18:08:44.863 - INFO - threading running +2023-08-22,18:08:44.873 - INFO - threading running +2023-08-22,18:08:44.883 - INFO - threading running +2023-08-22,18:08:44.893 - INFO - threading running +2023-08-22,18:08:44.903 - INFO - threading running +2023-08-22,18:08:44.913 - INFO - threading running +2023-08-22,18:08:44.924 - INFO - threading running +2023-08-22,18:08:44.933 - INFO - threading running +2023-08-22,18:08:44.943 - INFO - threading running +2023-08-22,18:08:44.953 - INFO - threading running +2023-08-22,18:08:44.963 - INFO - threading running +2023-08-22,18:08:44.973 - INFO - threading running +2023-08-22,18:08:44.983 - INFO - threading running +2023-08-22,18:08:44.993 - INFO - threading running +2023-08-22,18:08:45.004 - INFO - threading running +2023-08-22,18:08:45.015 - INFO - threading running +2023-08-22,18:08:45.024 - INFO - threading running +2023-08-22,18:08:45.035 - INFO - threading running +2023-08-22,18:08:45.045 - INFO - threading running +2023-08-22,18:08:45.054 - INFO - threading running +2023-08-22,18:08:45.064 - INFO - threading running +2023-08-22,18:08:45.074 - INFO - threading running +2023-08-22,18:08:45.085 - INFO - threading running +2023-08-22,18:08:45.094 - INFO - threading running +2023-08-22,18:08:45.104 - INFO - threading running +2023-08-22,18:08:45.114 - INFO - threading running +2023-08-22,18:08:45.124 - INFO - threading running +2023-08-22,18:08:45.134 - INFO - threading running +2023-08-22,18:08:45.145 - INFO - threading running +2023-08-22,18:08:45.147 - INFO - ---------------------------------------------------- +2023-08-22,18:08:45.147 - INFO - 70th iteration +2023-08-22,18:08:45.147 - INFO - average ll reward: 0.0864845469 +2023-08-22,18:08:45.148 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:45.155 - INFO - updating finished +2023-08-22,18:08:49.308 - INFO - threading running +2023-08-22,18:08:49.321 - INFO - threading running +2023-08-22,18:08:49.331 - INFO - threading running +2023-08-22,18:08:49.341 - INFO - threading running +2023-08-22,18:08:49.352 - INFO - threading running +2023-08-22,18:08:49.362 - INFO - threading running +2023-08-22,18:08:49.372 - INFO - threading running +2023-08-22,18:08:49.383 - INFO - threading running +2023-08-22,18:08:49.393 - INFO - threading running +2023-08-22,18:08:49.403 - INFO - threading running +2023-08-22,18:08:49.414 - INFO - threading running +2023-08-22,18:08:49.425 - INFO - threading running +2023-08-22,18:08:49.436 - INFO - threading running +2023-08-22,18:08:49.445 - INFO - threading running +2023-08-22,18:08:49.455 - INFO - threading running +2023-08-22,18:08:49.466 - INFO - threading running +2023-08-22,18:08:49.476 - INFO - threading running +2023-08-22,18:08:49.487 - INFO - threading running +2023-08-22,18:08:49.496 - INFO - threading running +2023-08-22,18:08:49.507 - INFO - threading running +2023-08-22,18:08:49.517 - INFO - threading running +2023-08-22,18:08:49.527 - INFO - threading running +2023-08-22,18:08:49.537 - INFO - threading running +2023-08-22,18:08:49.548 - INFO - threading running +2023-08-22,18:08:49.557 - INFO - threading running +2023-08-22,18:08:49.567 - INFO - threading running +2023-08-22,18:08:49.578 - INFO - threading running +2023-08-22,18:08:49.588 - INFO - threading running +2023-08-22,18:08:49.598 - INFO - threading running +2023-08-22,18:08:49.609 - INFO - threading running +2023-08-22,18:08:49.618 - INFO - threading running +2023-08-22,18:08:49.629 - INFO - threading running +2023-08-22,18:08:49.640 - INFO - threading running +2023-08-22,18:08:49.649 - INFO - threading running +2023-08-22,18:08:49.659 - INFO - threading running +2023-08-22,18:08:49.669 - INFO - threading running +2023-08-22,18:08:49.679 - INFO - threading running +2023-08-22,18:08:49.690 - INFO - threading running +2023-08-22,18:08:49.700 - INFO - threading running +2023-08-22,18:08:49.710 - INFO - threading running +2023-08-22,18:08:49.720 - INFO - threading running +2023-08-22,18:08:49.730 - INFO - threading running +2023-08-22,18:08:49.740 - INFO - threading running +2023-08-22,18:08:49.750 - INFO - threading running +2023-08-22,18:08:49.761 - INFO - threading running +2023-08-22,18:08:49.770 - INFO - threading running +2023-08-22,18:08:49.780 - INFO - threading running +2023-08-22,18:08:49.790 - INFO - threading running +2023-08-22,18:08:49.800 - INFO - threading running +2023-08-22,18:08:49.811 - INFO - threading running +2023-08-22,18:08:49.820 - INFO - threading running +2023-08-22,18:08:49.831 - INFO - threading running +2023-08-22,18:08:49.841 - INFO - threading running +2023-08-22,18:08:49.851 - INFO - threading running +2023-08-22,18:08:49.861 - INFO - threading running +2023-08-22,18:08:49.871 - INFO - threading running +2023-08-22,18:08:49.881 - INFO - threading running +2023-08-22,18:08:49.891 - INFO - ---------------------------------------------------- +2023-08-22,18:08:49.891 - INFO - threading running +2023-08-22,18:08:49.891 - INFO - 71th iteration +2023-08-22,18:08:49.892 - INFO - average ll reward: 0.0770143460 +2023-08-22,18:08:49.893 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:49.902 - INFO - updating finished +2023-08-22,18:08:54.015 - INFO - threading running +2023-08-22,18:08:54.028 - INFO - threading running +2023-08-22,18:08:54.038 - INFO - threading running +2023-08-22,18:08:54.048 - INFO - threading running +2023-08-22,18:08:54.058 - INFO - threading running +2023-08-22,18:08:54.068 - INFO - threading running +2023-08-22,18:08:54.079 - INFO - threading running +2023-08-22,18:08:54.088 - INFO - threading running +2023-08-22,18:08:54.098 - INFO - threading running +2023-08-22,18:08:54.108 - INFO - threading running +2023-08-22,18:08:54.118 - INFO - threading running +2023-08-22,18:08:54.128 - INFO - threading running +2023-08-22,18:08:54.138 - INFO - threading running +2023-08-22,18:08:54.149 - INFO - threading running +2023-08-22,18:08:54.160 - INFO - threading running +2023-08-22,18:08:54.171 - INFO - threading running +2023-08-22,18:08:54.181 - INFO - threading running +2023-08-22,18:08:54.192 - INFO - threading running +2023-08-22,18:08:54.202 - INFO - threading running +2023-08-22,18:08:54.212 - INFO - threading running +2023-08-22,18:08:54.222 - INFO - threading running +2023-08-22,18:08:54.232 - INFO - threading running +2023-08-22,18:08:54.243 - INFO - threading running +2023-08-22,18:08:54.252 - INFO - threading running +2023-08-22,18:08:54.262 - INFO - threading running +2023-08-22,18:08:54.273 - INFO - threading running +2023-08-22,18:08:54.284 - INFO - threading running +2023-08-22,18:08:54.293 - INFO - threading running +2023-08-22,18:08:54.303 - INFO - threading running +2023-08-22,18:08:54.313 - INFO - threading running +2023-08-22,18:08:54.323 - INFO - threading running +2023-08-22,18:08:54.333 - INFO - threading running +2023-08-22,18:08:54.343 - INFO - threading running +2023-08-22,18:08:54.353 - INFO - threading running +2023-08-22,18:08:54.363 - INFO - threading running +2023-08-22,18:08:54.374 - INFO - threading running +2023-08-22,18:08:54.384 - INFO - threading running +2023-08-22,18:08:54.394 - INFO - threading running +2023-08-22,18:08:54.404 - INFO - threading running +2023-08-22,18:08:54.414 - INFO - threading running +2023-08-22,18:08:54.424 - INFO - threading running +2023-08-22,18:08:54.434 - INFO - threading running +2023-08-22,18:08:54.444 - INFO - threading running +2023-08-22,18:08:54.455 - INFO - threading running +2023-08-22,18:08:54.465 - INFO - threading running +2023-08-22,18:08:54.474 - INFO - threading running +2023-08-22,18:08:54.485 - INFO - threading running +2023-08-22,18:08:54.495 - INFO - threading running +2023-08-22,18:08:54.506 - INFO - threading running +2023-08-22,18:08:54.516 - INFO - threading running +2023-08-22,18:08:54.526 - INFO - threading running +2023-08-22,18:08:54.536 - INFO - threading running +2023-08-22,18:08:54.547 - INFO - threading running +2023-08-22,18:08:54.557 - INFO - threading running +2023-08-22,18:08:54.567 - INFO - threading running +2023-08-22,18:08:54.577 - INFO - threading running +2023-08-22,18:08:54.581 - INFO - ---------------------------------------------------- +2023-08-22,18:08:54.581 - INFO - 72th iteration +2023-08-22,18:08:54.581 - INFO - average ll reward: 0.0835737115 +2023-08-22,18:08:54.581 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:54.587 - INFO - updating finished +2023-08-22,18:08:58.653 - INFO - threading running +2023-08-22,18:08:58.666 - INFO - threading running +2023-08-22,18:08:58.676 - INFO - threading running +2023-08-22,18:08:58.686 - INFO - threading running +2023-08-22,18:08:58.697 - INFO - threading running +2023-08-22,18:08:58.707 - INFO - threading running +2023-08-22,18:08:58.717 - INFO - threading running +2023-08-22,18:08:58.727 - INFO - threading running +2023-08-22,18:08:58.737 - INFO - threading running +2023-08-22,18:08:58.747 - INFO - threading running +2023-08-22,18:08:58.757 - INFO - threading running +2023-08-22,18:08:58.768 - INFO - threading running +2023-08-22,18:08:58.777 - INFO - threading running +2023-08-22,18:08:58.787 - INFO - threading running +2023-08-22,18:08:58.797 - INFO - threading running +2023-08-22,18:08:58.807 - INFO - threading running +2023-08-22,18:08:58.817 - INFO - threading running +2023-08-22,18:08:58.827 - INFO - threading running +2023-08-22,18:08:58.838 - INFO - threading running +2023-08-22,18:08:58.847 - INFO - threading running +2023-08-22,18:08:58.858 - INFO - threading running +2023-08-22,18:08:58.867 - INFO - threading running +2023-08-22,18:08:58.877 - INFO - threading running +2023-08-22,18:08:58.887 - INFO - threading running +2023-08-22,18:08:58.897 - INFO - threading running +2023-08-22,18:08:58.907 - INFO - threading running +2023-08-22,18:08:58.917 - INFO - threading running +2023-08-22,18:08:58.927 - INFO - threading running +2023-08-22,18:08:58.937 - INFO - threading running +2023-08-22,18:08:58.947 - INFO - threading running +2023-08-22,18:08:58.957 - INFO - threading running +2023-08-22,18:08:58.968 - INFO - threading running +2023-08-22,18:08:58.978 - INFO - threading running +2023-08-22,18:08:58.987 - INFO - threading running +2023-08-22,18:08:58.997 - INFO - threading running +2023-08-22,18:08:59.007 - INFO - threading running +2023-08-22,18:08:59.017 - INFO - threading running +2023-08-22,18:08:59.027 - INFO - threading running +2023-08-22,18:08:59.037 - INFO - threading running +2023-08-22,18:08:59.047 - INFO - threading running +2023-08-22,18:08:59.057 - INFO - threading running +2023-08-22,18:08:59.067 - INFO - threading running +2023-08-22,18:08:59.078 - INFO - threading running +2023-08-22,18:08:59.089 - INFO - threading running +2023-08-22,18:08:59.098 - INFO - threading running +2023-08-22,18:08:59.108 - INFO - threading running +2023-08-22,18:08:59.118 - INFO - threading running +2023-08-22,18:08:59.129 - INFO - threading running +2023-08-22,18:08:59.138 - INFO - threading running +2023-08-22,18:08:59.149 - INFO - threading running +2023-08-22,18:08:59.152 - INFO - ---------------------------------------------------- +2023-08-22,18:08:59.152 - INFO - 73th iteration +2023-08-22,18:08:59.152 - INFO - average ll reward: 0.0846496291 +2023-08-22,18:08:59.152 - INFO - ---------------------------------------------------- + +2023-08-22,18:08:59.159 - INFO - updating finished +2023-08-22,18:09:03.238 - INFO - threading running +2023-08-22,18:09:03.250 - INFO - threading running +2023-08-22,18:09:03.261 - INFO - threading running +2023-08-22,18:09:03.270 - INFO - threading running +2023-08-22,18:09:03.281 - INFO - threading running +2023-08-22,18:09:03.290 - INFO - threading running +2023-08-22,18:09:03.300 - INFO - threading running +2023-08-22,18:09:03.310 - INFO - threading running +2023-08-22,18:09:03.320 - INFO - threading running +2023-08-22,18:09:03.330 - INFO - threading running +2023-08-22,18:09:03.340 - INFO - threading running +2023-08-22,18:09:03.350 - INFO - threading running +2023-08-22,18:09:03.360 - INFO - threading running +2023-08-22,18:09:03.371 - INFO - threading running +2023-08-22,18:09:03.381 - INFO - threading running +2023-08-22,18:09:03.391 - INFO - threading running +2023-08-22,18:09:03.402 - INFO - threading running +2023-08-22,18:09:03.412 - INFO - threading running +2023-08-22,18:09:03.422 - INFO - threading running +2023-08-22,18:09:03.432 - INFO - threading running +2023-08-22,18:09:03.442 - INFO - threading running +2023-08-22,18:09:03.452 - INFO - threading running +2023-08-22,18:09:03.462 - INFO - threading running +2023-08-22,18:09:03.472 - INFO - threading running +2023-08-22,18:09:03.482 - INFO - threading running +2023-08-22,18:09:03.492 - INFO - threading running +2023-08-22,18:09:03.502 - INFO - threading running +2023-08-22,18:09:03.512 - INFO - threading running +2023-08-22,18:09:03.522 - INFO - threading running +2023-08-22,18:09:03.532 - INFO - threading running +2023-08-22,18:09:03.542 - INFO - threading running +2023-08-22,18:09:03.552 - INFO - threading running +2023-08-22,18:09:03.562 - INFO - threading running +2023-08-22,18:09:03.572 - INFO - threading running +2023-08-22,18:09:03.582 - INFO - threading running +2023-08-22,18:09:03.593 - INFO - threading running +2023-08-22,18:09:03.603 - INFO - threading running +2023-08-22,18:09:03.612 - INFO - threading running +2023-08-22,18:09:03.623 - INFO - threading running +2023-08-22,18:09:03.632 - INFO - threading running +2023-08-22,18:09:03.642 - INFO - threading running +2023-08-22,18:09:03.653 - INFO - threading running +2023-08-22,18:09:03.663 - INFO - threading running +2023-08-22,18:09:03.673 - INFO - threading running +2023-08-22,18:09:03.683 - INFO - threading running +2023-08-22,18:09:03.693 - INFO - threading running +2023-08-22,18:09:03.703 - INFO - threading running +2023-08-22,18:09:03.714 - INFO - threading running +2023-08-22,18:09:03.724 - INFO - threading running +2023-08-22,18:09:03.735 - INFO - threading running +2023-08-22,18:09:03.740 - INFO - ---------------------------------------------------- +2023-08-22,18:09:03.740 - INFO - 74th iteration +2023-08-22,18:09:03.740 - INFO - average ll reward: 0.0805190675 +2023-08-22,18:09:03.740 - INFO - ---------------------------------------------------- + +2023-08-22,18:09:03.744 - INFO - updating finished +2023-08-22,18:09:07.796 - INFO - threading running +2023-08-22,18:09:07.803 - INFO - threading running +2023-08-22,18:09:07.813 - INFO - threading running +2023-08-22,18:09:07.823 - INFO - threading running +2023-08-22,18:09:07.834 - INFO - threading running +2023-08-22,18:09:07.845 - INFO - threading running +2023-08-22,18:09:07.856 - INFO - threading running +2023-08-22,18:09:07.865 - INFO - threading running +2023-08-22,18:09:07.875 - INFO - threading running +2023-08-22,18:09:07.885 - INFO - threading running +2023-08-22,18:09:07.895 - INFO - threading running +2023-08-22,18:09:07.905 - INFO - threading running +2023-08-22,18:09:07.915 - INFO - threading running +2023-08-22,18:09:07.925 - INFO - threading running +2023-08-22,18:09:07.935 - INFO - threading running +2023-08-22,18:09:07.946 - INFO - threading running +2023-08-22,18:09:07.956 - INFO - threading running +2023-08-22,18:09:07.967 - INFO - threading running +2023-08-22,18:09:07.976 - INFO - threading running +2023-08-22,18:09:07.986 - INFO - threading running +2023-08-22,18:09:07.997 - INFO - threading running +2023-08-22,18:09:08.007 - INFO - threading running +2023-08-22,18:09:08.017 - INFO - threading running +2023-08-22,18:09:08.027 - INFO - threading running +2023-08-22,18:09:08.037 - INFO - threading running +2023-08-22,18:09:08.047 - INFO - threading running +2023-08-22,18:09:08.058 - INFO - threading running +2023-08-22,18:09:08.067 - INFO - threading running +2023-08-22,18:09:08.077 - INFO - threading running +2023-08-22,18:09:08.087 - INFO - threading running +2023-08-22,18:09:08.097 - INFO - threading running +2023-08-22,18:09:08.107 - INFO - threading running +2023-08-22,18:09:08.117 - INFO - threading running +2023-08-22,18:09:08.127 - INFO - threading running +2023-08-22,18:09:08.138 - INFO - threading running +2023-08-22,18:09:08.148 - INFO - threading running +2023-08-22,18:09:08.158 - INFO - threading running +2023-08-22,18:09:08.167 - INFO - threading running +2023-08-22,18:09:08.177 - INFO - threading running +2023-08-22,18:09:08.187 - INFO - threading running +2023-08-22,18:09:08.197 - INFO - threading running +2023-08-22,18:09:08.207 - INFO - threading running +2023-08-22,18:09:08.217 - INFO - threading running +2023-08-22,18:09:08.227 - INFO - threading running +2023-08-22,18:09:08.238 - INFO - threading running +2023-08-22,18:09:08.247 - INFO - threading running +2023-08-22,18:09:08.257 - INFO - threading running +2023-08-22,18:09:08.267 - INFO - threading running +2023-08-22,18:09:08.278 - INFO - threading running +2023-08-22,18:09:08.287 - INFO - threading running +2023-08-22,18:09:08.298 - INFO - threading running +2023-08-22,18:09:08.309 - INFO - threading running +2023-08-22,18:09:08.320 - INFO - threading running +2023-08-22,18:09:08.329 - INFO - threading running +2023-08-22,18:09:08.339 - INFO - threading running +2023-08-22,18:09:08.347 - INFO - ---------------------------------------------------- +2023-08-22,18:09:08.347 - INFO - 75th iteration +2023-08-22,18:09:08.347 - INFO - average ll reward: 0.0822874046 +2023-08-22,18:09:08.347 - INFO - ---------------------------------------------------- + +2023-08-22,18:09:08.350 - INFO - updating finished +2023-08-22,18:09:12.413 - INFO - threading running +2023-08-22,18:09:12.420 - INFO - threading running +2023-08-22,18:09:12.430 - INFO - threading running +2023-08-22,18:09:12.440 - INFO - threading running +2023-08-22,18:09:12.451 - INFO - threading running +2023-08-22,18:09:12.461 - INFO - threading running +2023-08-22,18:09:12.471 - INFO - threading running +2023-08-22,18:09:12.481 - INFO - threading running +2023-08-22,18:09:12.491 - INFO - threading running +2023-08-22,18:09:12.502 - INFO - threading running +2023-08-22,18:09:12.511 - INFO - threading running +2023-08-22,18:09:12.521 - INFO - threading running +2023-08-22,18:09:12.532 - INFO - threading running +2023-08-22,18:09:12.542 - INFO - threading running +2023-08-22,18:09:12.551 - INFO - threading running +2023-08-22,18:09:12.561 - INFO - threading running +2023-08-22,18:09:12.571 - INFO - threading running +2023-08-22,18:09:12.581 - INFO - threading running +2023-08-22,18:09:12.591 - INFO - threading running +2023-08-22,18:09:12.601 - INFO - threading running +2023-08-22,18:09:12.612 - INFO - threading running +2023-08-22,18:09:12.622 - INFO - threading running +2023-08-22,18:09:12.632 - INFO - threading running +2023-08-22,18:09:12.642 - INFO - threading running +2023-08-22,18:09:12.652 - INFO - threading running +2023-08-22,18:09:12.662 - INFO - threading running +2023-08-22,18:09:12.673 - INFO - threading running +2023-08-22,18:09:12.683 - INFO - threading running +2023-08-22,18:09:12.693 - INFO - threading running +2023-08-22,18:09:12.703 - INFO - threading running +2023-08-22,18:09:12.713 - INFO - threading running +2023-08-22,18:09:12.724 - INFO - threading running +2023-08-22,18:09:12.734 - INFO - threading running +2023-08-22,18:09:12.744 - INFO - threading running +2023-08-22,18:09:12.754 - INFO - threading running +2023-08-22,18:09:12.764 - INFO - threading running +2023-08-22,18:09:12.774 - INFO - threading running +2023-08-22,18:09:12.785 - INFO - threading running +2023-08-22,18:09:12.795 - INFO - threading running +2023-08-22,18:09:12.805 - INFO - threading running +2023-08-22,18:09:12.815 - INFO - threading running +2023-08-22,18:09:12.825 - INFO - threading running +2023-08-22,18:09:12.836 - INFO - threading running +2023-08-22,18:09:12.847 - INFO - threading running +2023-08-22,18:09:12.858 - INFO - threading running +2023-08-22,18:09:12.868 - INFO - threading running +2023-08-22,18:09:12.879 - INFO - threading running +2023-08-22,18:09:12.889 - INFO - threading running +2023-08-22,18:09:12.899 - INFO - threading running +2023-08-22,18:09:12.910 - INFO - threading running +2023-08-22,18:09:12.921 - INFO - threading running +2023-08-22,18:09:12.931 - INFO - threading running +2023-08-22,18:09:12.941 - INFO - threading running +2023-08-22,18:09:12.951 - INFO - threading running +2023-08-22,18:09:12.961 - INFO - threading running +2023-08-22,18:09:12.971 - INFO - threading running +2023-08-22,18:09:12.981 - INFO - threading running +2023-08-22,18:09:12.991 - INFO - threading running +2023-08-22,18:09:13.001 - INFO - threading running +2023-08-22,18:09:13.011 - INFO - threading running +2023-08-22,18:09:13.021 - INFO - threading running +2023-08-22,18:09:13.026 - INFO - ---------------------------------------------------- +2023-08-22,18:09:13.027 - INFO - 76th iteration +2023-08-22,18:09:13.027 - INFO - average ll reward: 0.0896750129 +2023-08-22,18:09:13.027 - INFO - ---------------------------------------------------- + +2023-08-22,18:09:13.032 - INFO - updating finished +2023-08-22,18:09:17.092 - INFO - threading running +2023-08-22,18:09:17.108 - INFO - threading running +2023-08-22,18:09:17.118 - INFO - threading running +2023-08-22,18:09:17.128 - INFO - threading running +2023-08-22,18:09:17.138 - INFO - threading running +2023-08-22,18:09:17.148 - INFO - threading running +2023-08-22,18:09:17.158 - INFO - threading running +2023-08-22,18:09:17.168 - INFO - threading running +2023-08-22,18:09:17.178 - INFO - threading running +2023-08-22,18:09:17.188 - INFO - threading running +2023-08-22,18:09:17.198 - INFO - threading running +2023-08-22,18:09:17.208 - INFO - threading running +2023-08-22,18:09:17.219 - INFO - threading running +2023-08-22,18:09:17.230 - INFO - threading running +2023-08-22,18:09:17.239 - INFO - threading running +2023-08-22,18:09:17.249 - INFO - threading running +2023-08-22,18:09:17.259 - INFO - threading running +2023-08-22,18:09:17.270 - INFO - threading running +2023-08-22,18:09:17.280 - INFO - threading running +2023-08-22,18:09:17.291 - INFO - threading running +2023-08-22,18:09:17.301 - INFO - threading running +2023-08-22,18:09:17.310 - INFO - threading running +2023-08-22,18:09:17.320 - INFO - threading running +2023-08-22,18:09:17.330 - INFO - threading running +2023-08-22,18:09:17.340 - INFO - threading running +2023-08-22,18:09:17.351 - INFO - threading running +2023-08-22,18:09:17.361 - INFO - threading running +2023-08-22,18:09:17.372 - INFO - threading running +2023-08-22,18:09:17.381 - INFO - threading running +2023-08-22,18:09:17.391 - INFO - threading running +2023-08-22,18:09:17.401 - INFO - threading running +2023-08-22,18:09:17.412 - INFO - threading running +2023-08-22,18:09:17.423 - INFO - threading running +2023-08-22,18:09:17.432 - INFO - threading running +2023-08-22,18:09:17.443 - INFO - threading running +2023-08-22,18:09:17.453 - INFO - threading running +2023-08-22,18:09:17.463 - INFO - threading running +2023-08-22,18:09:17.473 - INFO - threading running +2023-08-22,18:09:17.483 - INFO - threading running +2023-08-22,18:09:17.494 - INFO - threading running +2023-08-22,18:09:17.503 - INFO - threading running +2023-08-22,18:09:17.513 - INFO - threading running +2023-08-22,18:09:17.523 - INFO - threading running +2023-08-22,18:09:17.533 - INFO - threading running +2023-08-22,18:09:17.544 - INFO - threading running +2023-08-22,18:09:17.554 - INFO - threading running +2023-08-22,18:09:17.563 - INFO - threading running +2023-08-22,18:09:17.573 - INFO - threading running +2023-08-22,18:09:17.583 - INFO - threading running +2023-08-22,18:09:17.593 - INFO - threading running +2023-08-22,18:09:17.600 - INFO - ---------------------------------------------------- +2023-08-22,18:09:17.600 - INFO - 77th iteration +2023-08-22,18:09:17.601 - INFO - average ll reward: 0.0933208793 +2023-08-22,18:09:17.601 - INFO - ---------------------------------------------------- + +2023-08-22,18:09:17.603 - INFO - updating finished +2023-08-22,18:09:21.659 - INFO - threading running +2023-08-22,18:09:21.674 - INFO - threading running +2023-08-22,18:09:21.683 - INFO - threading running +2023-08-22,18:09:21.693 - INFO - threading running +2023-08-22,18:09:21.703 - INFO - threading running +2023-08-22,18:09:21.714 - INFO - threading running +2023-08-22,18:09:21.723 - INFO - threading running +2023-08-22,18:09:21.733 - INFO - threading running +2023-08-22,18:09:21.743 - INFO - threading running +2023-08-22,18:09:21.753 - INFO - threading running +2023-08-22,18:09:21.763 - INFO - threading running +2023-08-22,18:09:21.773 - INFO - threading running +2023-08-22,18:09:21.783 - INFO - threading running +2023-08-22,18:09:21.793 - INFO - threading running +2023-08-22,18:09:21.803 - INFO - threading running +2023-08-22,18:09:21.813 - INFO - threading running +2023-08-22,18:09:21.823 - INFO - threading running +2023-08-22,18:09:21.834 - INFO - threading running +2023-08-22,18:09:21.843 - INFO - threading running +2023-08-22,18:09:21.854 - INFO - threading running +2023-08-22,18:09:21.863 - INFO - threading running +2023-08-22,18:09:21.873 - INFO - threading running +2023-08-22,18:09:21.883 - INFO - threading running +2023-08-22,18:09:21.893 - INFO - threading running +2023-08-22,18:09:21.903 - INFO - threading running +2023-08-22,18:09:21.913 - INFO - threading running +2023-08-22,18:09:21.923 - INFO - threading running +2023-08-22,18:09:21.934 - INFO - threading running +2023-08-22,18:09:21.944 - INFO - threading running +2023-08-22,18:09:21.954 - INFO - threading running +2023-08-22,18:09:21.964 - INFO - threading running +2023-08-22,18:09:21.974 - INFO - threading running +2023-08-22,18:09:21.984 - INFO - threading running +2023-08-22,18:09:21.994 - INFO - threading running +2023-08-22,18:09:22.005 - INFO - threading running +2023-08-22,18:09:22.015 - INFO - threading running +2023-08-22,18:09:22.025 - INFO - threading running +2023-08-22,18:09:22.035 - INFO - threading running +2023-08-22,18:09:22.046 - INFO - threading running +2023-08-22,18:09:22.056 - INFO - threading running +2023-08-22,18:09:22.067 - INFO - threading running +2023-08-22,18:09:22.078 - INFO - threading running +2023-08-22,18:09:22.088 - INFO - threading running +2023-08-22,18:09:22.098 - INFO - threading running +2023-08-22,18:09:22.107 - INFO - threading running +2023-08-22,18:09:22.118 - INFO - threading running +2023-08-22,18:09:22.127 - INFO - threading running +2023-08-22,18:09:22.137 - INFO - threading running +2023-08-22,18:09:22.147 - INFO - threading running +2023-08-22,18:09:22.157 - INFO - threading running +2023-08-22,18:09:22.168 - INFO - threading running +2023-08-22,18:09:22.171 - INFO - ---------------------------------------------------- +2023-08-22,18:09:22.171 - INFO - 78th iteration +2023-08-22,18:09:22.171 - INFO - average ll reward: 0.0808519627 +2023-08-22,18:09:22.171 - INFO - ---------------------------------------------------- + +2023-08-22,18:09:22.179 - INFO - updating finished +2023-08-22,18:09:26.213 - INFO - threading running +2023-08-22,18:09:26.228 - INFO - threading running +2023-08-22,18:09:26.239 - INFO - threading running +2023-08-22,18:09:26.250 - INFO - threading running +2023-08-22,18:09:26.261 - INFO - threading running +2023-08-22,18:09:26.271 - INFO - threading running +2023-08-22,18:09:26.280 - INFO - threading running +2023-08-22,18:09:26.291 - INFO - threading running +2023-08-22,18:09:26.301 - INFO - threading running +2023-08-22,18:09:26.312 - INFO - threading running +2023-08-22,18:09:26.323 - INFO - threading running +2023-08-22,18:09:26.333 - INFO - threading running +2023-08-22,18:09:26.343 - INFO - threading running +2023-08-22,18:09:26.353 - INFO - threading running +2023-08-22,18:09:26.364 - INFO - threading running +2023-08-22,18:09:26.373 - INFO - threading running +2023-08-22,18:09:26.384 - INFO - threading running +2023-08-22,18:09:26.394 - INFO - threading running +2023-08-22,18:09:26.404 - INFO - threading running +2023-08-22,18:09:26.414 - INFO - threading running +2023-08-22,18:09:26.424 - INFO - threading running +2023-08-22,18:09:26.434 - INFO - threading running +2023-08-22,18:09:26.445 - INFO - threading running +2023-08-22,18:09:26.454 - INFO - threading running +2023-08-22,18:09:26.464 - INFO - threading running +2023-08-22,18:09:26.474 - INFO - threading running +2023-08-22,18:09:26.484 - INFO - threading running +2023-08-22,18:09:26.494 - INFO - threading running +2023-08-22,18:09:26.504 - INFO - threading running +2023-08-22,18:09:26.514 - INFO - threading running +2023-08-22,18:09:26.524 - INFO - threading running +2023-08-22,18:09:26.534 - INFO - threading running +2023-08-22,18:09:26.545 - INFO - threading running +2023-08-22,18:09:26.554 - INFO - threading running +2023-08-22,18:09:26.564 - INFO - threading running +2023-08-22,18:09:26.574 - INFO - threading running +2023-08-22,18:09:26.584 - INFO - threading running +2023-08-22,18:09:26.594 - INFO - threading running +2023-08-22,18:09:26.604 - INFO - threading running +2023-08-22,18:09:26.614 - INFO - threading running +2023-08-22,18:09:26.624 - INFO - threading running +2023-08-22,18:09:26.634 - INFO - threading running +2023-08-22,18:09:26.645 - INFO - threading running +2023-08-22,18:09:26.654 - INFO - threading running +2023-08-22,18:09:26.664 - INFO - threading running +2023-08-22,18:09:26.674 - INFO - threading running +2023-08-22,18:09:26.684 - INFO - threading running +2023-08-22,18:09:26.694 - INFO - threading running +2023-08-22,18:09:26.704 - INFO - threading running +2023-08-22,18:09:26.714 - INFO - threading running +2023-08-22,18:09:26.724 - INFO - threading running +2023-08-22,18:09:26.734 - INFO - threading running +2023-08-22,18:09:26.745 - INFO - threading running +2023-08-22,18:09:26.756 - INFO - threading running +2023-08-22,18:09:26.765 - INFO - threading running +2023-08-22,18:09:26.775 - INFO - threading running +2023-08-22,18:09:26.786 - INFO - threading running +2023-08-22,18:09:26.795 - INFO - threading running +2023-08-22,18:09:26.805 - INFO - threading running +2023-08-22,18:09:26.815 - INFO - threading running +2023-08-22,18:09:26.825 - INFO - ---------------------------------------------------- +2023-08-22,18:09:26.825 - INFO - 79th iteration +2023-08-22,18:09:26.825 - INFO - average ll reward: 0.1020800184 +2023-08-22,18:09:26.825 - INFO - ---------------------------------------------------- + +2023-08-22,18:09:26.825 - INFO - threading running +2023-08-22,18:09:26.835 - INFO - updating finished +2023-08-22,18:09:30.896 - INFO - threading running +2023-08-22,18:09:30.911 - INFO - threading running +2023-08-22,18:09:30.922 - INFO - threading running +2023-08-22,18:09:30.933 - INFO - threading running +2023-08-22,18:09:30.942 - INFO - threading running +2023-08-22,18:09:30.952 - INFO - threading running +2023-08-22,18:09:30.962 - INFO - threading running +2023-08-22,18:09:30.972 - INFO - threading running +2023-08-22,18:09:30.982 - INFO - threading running +2023-08-22,18:09:30.992 - INFO - threading running +2023-08-22,18:09:31.002 - INFO - threading running +2023-08-22,18:09:31.012 - INFO - threading running +2023-08-22,18:09:31.022 - INFO - threading running +2023-08-22,18:09:31.032 - INFO - threading running +2023-08-22,18:09:31.043 - INFO - threading running +2023-08-22,18:09:31.052 - INFO - threading running +2023-08-22,18:09:31.063 - INFO - threading running +2023-08-22,18:09:31.072 - INFO - threading running +2023-08-22,18:09:31.082 - INFO - threading running +2023-08-22,18:09:31.092 - INFO - threading running +2023-08-22,18:09:31.102 - INFO - threading running +2023-08-22,18:09:31.112 - INFO - threading running +2023-08-22,18:09:31.123 - INFO - threading running +2023-08-22,18:09:31.133 - INFO - threading running +2023-08-22,18:09:31.143 - INFO - threading running +2023-08-22,18:09:31.154 - INFO - threading running +2023-08-22,18:09:31.163 - INFO - threading running +2023-08-22,18:09:31.173 - INFO - threading running +2023-08-22,18:09:31.183 - INFO - threading running +2023-08-22,18:09:31.193 - INFO - threading running +2023-08-22,18:09:31.203 - INFO - threading running +2023-08-22,18:09:31.214 - INFO - threading running +2023-08-22,18:09:31.224 - INFO - threading running +2023-08-22,18:09:31.234 - INFO - threading running +2023-08-22,18:09:31.244 - INFO - threading running +2023-08-22,18:09:31.255 - INFO - threading running +2023-08-22,18:09:31.265 - INFO - threading running +2023-08-22,18:09:31.275 - INFO - threading running +2023-08-22,18:09:31.285 - INFO - threading running +2023-08-22,18:09:31.295 - INFO - threading running +2023-08-22,18:09:31.306 - INFO - threading running +2023-08-22,18:09:31.315 - INFO - threading running +2023-08-22,18:09:31.326 - INFO - threading running +2023-08-22,18:09:31.337 - INFO - threading running +2023-08-22,18:09:31.347 - INFO - threading running +2023-08-22,18:09:31.358 - INFO - threading running +2023-08-22,18:09:31.369 - INFO - threading running +2023-08-22,18:09:31.378 - INFO - threading running +2023-08-22,18:09:31.388 - INFO - threading running +2023-08-22,18:09:31.398 - INFO - threading running +2023-08-22,18:09:31.408 - INFO - threading running +2023-08-22,18:09:31.418 - INFO - threading running +2023-08-22,18:09:31.428 - INFO - threading running +2023-08-22,18:09:31.439 - INFO - threading running +2023-08-22,18:09:31.457 - INFO - threading running +2023-08-22,18:09:31.472 - INFO - threading running +2023-08-22,18:09:31.483 - INFO - threading running +2023-08-22,18:09:31.494 - INFO - threading running +2023-08-22,18:09:31.509 - INFO - threading running +2023-08-22,18:09:31.527 - INFO - threading running +2023-08-22,18:09:31.538 - INFO - threading running +2023-08-22,18:09:31.549 - INFO - threading running +2023-08-22,18:09:31.564 - INFO - threading running +2023-08-22,18:09:31.577 - INFO - threading running +2023-08-22,18:09:31.588 - INFO - threading running +2023-08-22,18:09:31.603 - INFO - threading running +2023-08-22,18:09:31.619 - INFO - threading running +2023-08-22,18:09:31.666 - INFO - threading running +2023-08-22,18:09:31.710 - INFO - threading running +2023-08-22,18:09:31.721 - INFO - threading running +2023-08-22,18:09:31.735 - INFO - threading running +2023-08-22,18:09:31.779 - INFO - threading running +2023-08-22,18:09:31.817 - INFO - threading running +2023-08-22,18:09:31.828 - INFO - threading running +2023-08-22,18:09:31.838 - INFO - threading running +2023-08-22,18:09:31.881 - INFO - threading running +2023-08-22,18:09:31.924 - INFO - threading running +2023-08-22,18:09:31.935 - INFO - threading running +2023-08-22,18:09:31.945 - INFO - threading running +2023-08-22,18:09:31.983 - INFO - threading running +2023-08-22,18:09:32.029 - INFO - threading running +2023-08-22,18:09:32.039 - INFO - threading running +2023-08-22,18:09:32.049 - INFO - threading running +2023-08-22,18:09:32.088 - INFO - threading running +2023-08-22,18:09:32.137 - INFO - threading running +2023-08-22,18:09:32.147 - INFO - threading running +2023-08-22,18:09:32.157 - INFO - threading running +2023-08-22,18:09:32.194 - INFO - threading running +2023-08-22,18:09:32.236 - INFO - threading running +2023-08-22,18:09:32.246 - INFO - threading running +2023-08-22,18:09:32.256 - INFO - threading running +2023-08-22,18:09:32.293 - INFO - threading running +2023-08-22,18:09:32.334 - INFO - threading running +2023-08-22,18:09:32.345 - INFO - threading running +2023-08-22,18:09:32.354 - INFO - threading running +2023-08-22,18:09:32.392 - INFO - threading running +2023-08-22,18:09:32.433 - INFO - threading running +2023-08-22,18:09:32.443 - INFO - threading running +2023-08-22,18:09:32.453 - INFO - threading running +2023-08-22,18:09:32.498 - INFO - threading running +2023-08-22,18:09:32.540 - INFO - threading running +2023-08-22,18:09:32.550 - INFO - threading running +2023-08-22,18:09:32.561 - INFO - threading running +2023-08-22,18:09:32.599 - INFO - threading running +2023-08-22,18:09:32.644 - INFO - threading running +2023-08-22,18:09:32.654 - INFO - threading running +2023-08-22,18:09:32.664 - INFO - threading running +2023-08-22,18:09:32.688 - INFO - threading running +2023-08-22,18:09:32.727 - INFO - threading running +2023-08-22,18:09:32.741 - INFO - threading running +2023-08-22,18:09:32.752 - INFO - threading running +2023-08-22,18:09:32.762 - INFO - threading running +2023-08-22,18:09:32.773 - INFO - threading running +2023-08-22,18:09:32.777 - INFO - ---------------------------------------------------- +2023-08-22,18:09:32.778 - INFO - 80th iteration +2023-08-22,18:09:32.778 - INFO - average ll reward: 0.1109243739 +2023-08-22,18:09:32.778 - INFO - ---------------------------------------------------- + +2023-08-22,18:09:32.783 - INFO - updating finished +2023-08-22,18:09:36.877 - INFO - threading running +2023-08-22,18:09:36.889 - INFO - threading running +2023-08-22,18:09:36.899 - INFO - threading running +2023-08-22,18:09:36.909 - INFO - threading running +2023-08-22,18:09:36.919 - INFO - threading running +2023-08-22,18:09:36.930 - INFO - threading running +2023-08-22,18:09:36.940 - INFO - threading running +2023-08-22,18:09:36.950 - INFO - threading running +2023-08-22,18:09:36.960 - INFO - threading running +2023-08-22,18:09:36.970 - INFO - threading running +2023-08-22,18:09:36.980 - INFO - threading running +2023-08-22,18:09:36.991 - INFO - threading running +2023-08-22,18:09:37.001 - INFO - threading running +2023-08-22,18:09:37.011 - INFO - threading running +2023-08-22,18:09:37.021 - INFO - threading running +2023-08-22,18:09:37.032 - INFO - threading running +2023-08-22,18:09:37.042 - INFO - threading running +2023-08-22,18:09:37.052 - INFO - threading running +2023-08-22,18:09:37.062 - INFO - threading running +2023-08-22,18:09:37.072 - INFO - threading running +2023-08-22,18:09:37.082 - INFO - threading running +2023-08-22,18:09:37.092 - INFO - threading running +2023-08-22,18:09:37.102 - INFO - threading running +2023-08-22,18:09:37.113 - INFO - threading running +2023-08-22,18:09:37.124 - INFO - threading running +2023-08-22,18:09:37.134 - INFO - threading running +2023-08-22,18:09:37.145 - INFO - threading running +2023-08-22,18:09:37.155 - INFO - threading running +2023-08-22,18:09:37.165 - INFO - threading running +2023-08-22,18:09:37.175 - INFO - threading running +2023-08-22,18:09:37.185 - INFO - threading running +2023-08-22,18:09:37.195 - INFO - threading running +2023-08-22,18:09:37.206 - INFO - threading running +2023-08-22,18:09:37.215 - INFO - threading running +2023-08-22,18:09:37.225 - INFO - threading running +2023-08-22,18:09:37.235 - INFO - threading running +2023-08-22,18:09:37.245 - INFO - threading running +2023-08-22,18:09:37.255 - INFO - threading running +2023-08-22,18:09:37.265 - INFO - threading running +2023-08-22,18:09:37.275 - INFO - threading running +2023-08-22,18:09:37.285 - INFO - threading running +2023-08-22,18:09:37.295 - INFO - threading running +2023-08-22,18:09:37.305 - INFO - threading running +2023-08-22,18:09:37.315 - INFO - threading running +2023-08-22,18:09:37.325 - INFO - threading running +2023-08-22,18:09:37.335 - INFO - threading running +2023-08-22,18:09:37.345 - INFO - threading running +2023-08-22,18:09:37.356 - INFO - threading running +2023-08-22,18:09:37.367 - INFO - threading running +2023-08-22,18:09:37.377 - INFO - threading running +2023-08-22,18:09:37.386 - INFO - threading running +2023-08-22,18:09:37.396 - INFO - threading running +2023-08-22,18:09:37.407 - INFO - threading running +2023-08-22,18:09:37.417 - INFO - threading running +2023-08-22,18:09:37.428 - INFO - threading running +2023-08-22,18:09:37.433 - INFO - ---------------------------------------------------- +2023-08-22,18:09:37.433 - INFO - 81th iteration +2023-08-22,18:09:37.433 - INFO - average ll reward: 0.1231243163 +2023-08-22,18:09:37.433 - INFO - ---------------------------------------------------- + +2023-08-22,18:09:37.438 - INFO - updating finished +2023-08-22,18:09:41.588 - INFO - threading running +2023-08-22,18:09:41.595 - INFO - threading running +2023-08-22,18:09:41.606 - INFO - threading running +2023-08-22,18:09:41.617 - INFO - threading running +2023-08-22,18:09:41.627 - INFO - threading running +2023-08-22,18:09:41.636 - INFO - threading running +2023-08-22,18:09:41.646 - INFO - threading running +2023-08-22,18:09:41.656 - INFO - threading running +2023-08-22,18:09:41.666 - INFO - threading running +2023-08-22,18:09:41.676 - INFO - threading running +2023-08-22,18:09:41.687 - INFO - threading running +2023-08-22,18:09:41.697 - INFO - threading running +2023-08-22,18:09:41.708 - INFO - threading running +2023-08-22,18:09:41.718 - INFO - threading running +2023-08-22,18:09:41.728 - INFO - threading running +2023-08-22,18:09:41.738 - INFO - threading running +2023-08-22,18:09:41.749 - INFO - threading running +2023-08-22,18:09:41.758 - INFO - threading running +2023-08-22,18:09:41.768 - INFO - threading running +2023-08-22,18:09:41.778 - INFO - threading running +2023-08-22,18:09:41.788 - INFO - threading running +2023-08-22,18:09:41.798 - INFO - threading running +2023-08-22,18:09:41.808 - INFO - threading running +2023-08-22,18:09:41.818 - INFO - threading running +2023-08-22,18:09:41.828 - INFO - threading running +2023-08-22,18:09:41.838 - INFO - threading running +2023-08-22,18:09:41.848 - INFO - threading running +2023-08-22,18:09:41.858 - INFO - threading running +2023-08-22,18:09:41.868 - INFO - threading running +2023-08-22,18:09:41.878 - INFO - threading running +2023-08-22,18:09:41.888 - INFO - threading running +2023-08-22,18:09:41.899 - INFO - threading running +2023-08-22,18:09:41.910 - INFO - threading running +2023-08-22,18:09:41.920 - INFO - threading running +2023-08-22,18:09:41.930 - INFO - threading running +2023-08-22,18:09:41.940 - INFO - threading running +2023-08-22,18:09:41.951 - INFO - threading running +2023-08-22,18:09:41.961 - INFO - threading running +2023-08-22,18:09:41.972 - INFO - threading running +2023-08-22,18:09:41.982 - INFO - threading running +2023-08-22,18:09:41.991 - INFO - threading running +2023-08-22,18:09:42.001 - INFO - threading running +2023-08-22,18:09:42.011 - INFO - threading running +2023-08-22,18:09:42.021 - INFO - threading running +2023-08-22,18:09:42.031 - INFO - threading running +2023-08-22,18:09:42.041 - INFO - threading running +2023-08-22,18:09:42.052 - INFO - threading running +2023-08-22,18:09:42.061 - INFO - threading running +2023-08-22,18:09:42.071 - INFO - threading running +2023-08-22,18:09:42.081 - INFO - threading running +2023-08-22,18:09:42.091 - INFO - threading running +2023-08-22,18:09:42.101 - INFO - threading running +2023-08-22,18:09:42.112 - INFO - threading running +2023-08-22,18:09:42.114 - INFO - ---------------------------------------------------- +2023-08-22,18:09:42.114 - INFO - 82th iteration +2023-08-22,18:09:42.114 - INFO - average ll reward: 0.1220297540 +2023-08-22,18:09:42.114 - INFO - ---------------------------------------------------- + +2023-08-22,18:09:42.121 - INFO - updating finished +2023-08-22,18:09:46.264 - INFO - threading running +2023-08-22,18:09:46.272 - INFO - threading running +2023-08-22,18:09:46.282 - INFO - threading running +2023-08-22,18:09:46.292 - INFO - threading running +2023-08-22,18:09:46.302 - INFO - threading running +2023-08-22,18:09:46.312 - INFO - threading running +2023-08-22,18:09:46.322 - INFO - threading running +2023-08-22,18:09:46.332 - INFO - threading running +2023-08-22,18:09:46.342 - INFO - threading running +2023-08-22,18:09:46.352 - INFO - threading running +2023-08-22,18:09:46.362 - INFO - threading running +2023-08-22,18:09:46.372 - INFO - threading running +2023-08-22,18:09:46.382 - INFO - threading running +2023-08-22,18:09:46.392 - INFO - threading running +2023-08-22,18:09:46.402 - INFO - threading running +2023-08-22,18:09:46.413 - INFO - threading running +2023-08-22,18:09:46.423 - INFO - threading running +2023-08-22,18:09:46.434 - INFO - threading running +2023-08-22,18:09:46.445 - INFO - threading running +2023-08-22,18:09:46.455 - INFO - threading running +2023-08-22,18:09:46.465 - INFO - threading running +2023-08-22,18:09:46.475 - INFO - threading running +2023-08-22,18:09:46.486 - INFO - threading running +2023-08-22,18:09:46.495 - INFO - threading running +2023-08-22,18:09:46.505 - INFO - threading running +2023-08-22,18:09:46.515 - INFO - threading running +2023-08-22,18:09:46.526 - INFO - threading running +2023-08-22,18:09:46.536 - INFO - threading running +2023-08-22,18:09:46.546 - INFO - threading running +2023-08-22,18:09:46.557 - INFO - threading running +2023-08-22,18:09:46.566 - INFO - threading running +2023-08-22,18:09:46.576 - INFO - threading running +2023-08-22,18:09:46.586 - INFO - threading running +2023-08-22,18:09:46.596 - INFO - threading running +2023-08-22,18:09:46.606 - INFO - threading running +2023-08-22,18:09:46.617 - INFO - threading running +2023-08-22,18:09:46.628 - INFO - threading running +2023-08-22,18:09:46.638 - INFO - threading running +2023-08-22,18:09:46.648 - INFO - threading running +2023-08-22,18:09:46.658 - INFO - threading running +2023-08-22,18:09:46.668 - INFO - threading running +2023-08-22,18:09:46.678 - INFO - threading running +2023-08-22,18:09:46.688 - INFO - threading running +2023-08-22,18:09:46.698 - INFO - threading running +2023-08-22,18:09:46.708 - INFO - threading running +2023-08-22,18:09:46.718 - INFO - threading running +2023-08-22,18:09:46.728 - INFO - threading running +2023-08-22,18:09:46.738 - INFO - threading running +2023-08-22,18:09:46.748 - INFO - threading running +2023-08-22,18:09:46.758 - INFO - threading running +2023-08-22,18:09:46.769 - INFO - threading running +2023-08-22,18:09:46.779 - INFO - threading running +2023-08-22,18:09:46.789 - INFO - threading running +2023-08-22,18:09:46.799 - INFO - threading running +2023-08-22,18:09:46.809 - INFO - threading running +2023-08-22,18:09:46.819 - INFO - threading running +2023-08-22,18:09:46.824 - INFO - ---------------------------------------------------- +2023-08-22,18:09:46.824 - INFO - 83th iteration +2023-08-22,18:09:46.824 - INFO - average ll reward: 0.1046206729 +2023-08-22,18:09:46.824 - INFO - ---------------------------------------------------- + +2023-08-22,18:09:46.830 - INFO - updating finished +2023-08-22,18:09:50.929 - INFO - threading running +2023-08-22,18:09:50.941 - INFO - threading running +2023-08-22,18:09:50.951 - INFO - threading running +2023-08-22,18:09:50.962 - INFO - threading running +2023-08-22,18:09:50.972 - INFO - threading running +2023-08-22,18:09:50.982 - INFO - threading running +2023-08-22,18:09:50.992 - INFO - threading running +2023-08-22,18:09:51.002 - INFO - threading running +2023-08-22,18:09:51.013 - INFO - threading running +2023-08-22,18:09:51.022 - INFO - threading running +2023-08-22,18:09:51.032 - INFO - threading running +2023-08-22,18:09:51.042 - INFO - threading running +2023-08-22,18:09:51.052 - INFO - threading running +2023-08-22,18:09:51.062 - INFO - threading running +2023-08-22,18:09:51.072 - INFO - threading running +2023-08-22,18:09:51.083 - INFO - threading running +2023-08-22,18:09:51.092 - INFO - threading running +2023-08-22,18:09:51.103 - INFO - threading running +2023-08-22,18:09:51.113 - INFO - threading running +2023-08-22,18:09:51.122 - INFO - threading running +2023-08-22,18:09:51.132 - INFO - threading running +2023-08-22,18:09:51.142 - INFO - threading running +2023-08-22,18:09:51.153 - INFO - threading running +2023-08-22,18:09:51.163 - INFO - threading running +2023-08-22,18:09:51.173 - INFO - threading running +2023-08-22,18:09:51.183 - INFO - threading running +2023-08-22,18:09:51.193 - INFO - threading running +2023-08-22,18:09:51.203 - INFO - threading running +2023-08-22,18:09:51.213 - INFO - threading running +2023-08-22,18:09:51.224 - INFO - threading running +2023-08-22,18:09:51.235 - INFO - threading running +2023-08-22,18:09:51.246 - INFO - threading running +2023-08-22,18:09:51.256 - INFO - threading running +2023-08-22,18:09:51.266 - INFO - threading running +2023-08-22,18:09:51.276 - INFO - threading running +2023-08-22,18:09:51.286 - INFO - threading running +2023-08-22,18:09:51.296 - INFO - threading running +2023-08-22,18:09:51.307 - INFO - threading running +2023-08-22,18:09:51.317 - INFO - threading running +2023-08-22,18:09:51.326 - INFO - threading running +2023-08-22,18:09:51.336 - INFO - threading running +2023-08-22,18:09:51.347 - INFO - threading running +2023-08-22,18:09:51.356 - INFO - threading running +2023-08-22,18:09:51.366 - INFO - threading running +2023-08-22,18:09:51.376 - INFO - threading running +2023-08-22,18:09:51.386 - INFO - threading running +2023-08-22,18:09:51.397 - INFO - threading running +2023-08-22,18:09:51.406 - INFO - threading running +2023-08-22,18:09:51.416 - INFO - threading running +2023-08-22,18:09:51.426 - INFO - threading running +2023-08-22,18:09:51.437 - INFO - threading running +2023-08-22,18:09:51.447 - INFO - threading running +2023-08-22,18:09:51.456 - INFO - threading running +2023-08-22,18:09:51.466 - INFO - threading running +2023-08-22,18:09:51.477 - INFO - threading running +2023-08-22,18:09:51.481 - INFO - ---------------------------------------------------- +2023-08-22,18:09:51.481 - INFO - 84th iteration +2023-08-22,18:09:51.481 - INFO - average ll reward: 0.0859891971 +2023-08-22,18:09:51.481 - INFO - ---------------------------------------------------- + +2023-08-22,18:09:51.488 - INFO - updating finished +2023-08-22,18:09:55.563 - INFO - threading running +2023-08-22,18:09:55.576 - INFO - threading running +2023-08-22,18:09:55.587 - INFO - threading running +2023-08-22,18:09:55.596 - INFO - threading running +2023-08-22,18:09:55.606 - INFO - threading running +2023-08-22,18:09:55.617 - INFO - threading running +2023-08-22,18:09:55.626 - INFO - threading running +2023-08-22,18:09:55.636 - INFO - threading running +2023-08-22,18:09:55.646 - INFO - threading running +2023-08-22,18:09:55.657 - INFO - threading running +2023-08-22,18:09:55.667 - INFO - threading running +2023-08-22,18:09:55.676 - INFO - threading running +2023-08-22,18:09:55.687 - INFO - threading running +2023-08-22,18:09:55.697 - INFO - threading running +2023-08-22,18:09:55.707 - INFO - threading running +2023-08-22,18:09:55.718 - INFO - threading running +2023-08-22,18:09:55.727 - INFO - threading running +2023-08-22,18:09:55.737 - INFO - threading running +2023-08-22,18:09:55.747 - INFO - threading running +2023-08-22,18:09:55.757 - INFO - threading running +2023-08-22,18:09:55.767 - INFO - threading running +2023-08-22,18:09:55.777 - INFO - threading running +2023-08-22,18:09:55.787 - INFO - threading running +2023-08-22,18:09:55.797 - INFO - threading running +2023-08-22,18:09:55.807 - INFO - threading running +2023-08-22,18:09:55.818 - INFO - threading running +2023-08-22,18:09:55.828 - INFO - threading running +2023-08-22,18:09:55.837 - INFO - threading running +2023-08-22,18:09:55.847 - INFO - threading running +2023-08-22,18:09:55.858 - INFO - threading running +2023-08-22,18:09:55.869 - INFO - threading running +2023-08-22,18:09:55.879 - INFO - threading running +2023-08-22,18:09:55.889 - INFO - threading running +2023-08-22,18:09:55.899 - INFO - threading running +2023-08-22,18:09:55.910 - INFO - threading running +2023-08-22,18:09:55.920 - INFO - threading running +2023-08-22,18:09:55.929 - INFO - threading running +2023-08-22,18:09:55.940 - INFO - threading running +2023-08-22,18:09:55.951 - INFO - threading running +2023-08-22,18:09:55.962 - INFO - threading running +2023-08-22,18:09:55.972 - INFO - threading running +2023-08-22,18:09:55.982 - INFO - threading running +2023-08-22,18:09:55.992 - INFO - threading running +2023-08-22,18:09:56.002 - INFO - threading running +2023-08-22,18:09:56.012 - INFO - threading running +2023-08-22,18:09:56.023 - INFO - threading running +2023-08-22,18:09:56.032 - INFO - threading running +2023-08-22,18:09:56.042 - INFO - threading running +2023-08-22,18:09:56.052 - INFO - threading running +2023-08-22,18:09:56.062 - INFO - threading running +2023-08-22,18:09:56.072 - INFO - threading running +2023-08-22,18:09:56.082 - INFO - threading running +2023-08-22,18:09:56.092 - INFO - threading running +2023-08-22,18:09:56.103 - INFO - threading running +2023-08-22,18:09:56.113 - INFO - threading running +2023-08-22,18:09:56.123 - INFO - threading running +2023-08-22,18:09:56.133 - INFO - threading running +2023-08-22,18:09:56.144 - INFO - threading running +2023-08-22,18:09:56.155 - INFO - threading running +2023-08-22,18:09:56.166 - INFO - threading running +2023-08-22,18:09:56.176 - INFO - threading running +2023-08-22,18:09:56.179 - INFO - ---------------------------------------------------- +2023-08-22,18:09:56.179 - INFO - 85th iteration +2023-08-22,18:09:56.179 - INFO - average ll reward: 0.0922742588 +2023-08-22,18:09:56.179 - INFO - ---------------------------------------------------- + +2023-08-22,18:09:56.185 - INFO - updating finished +2023-08-22,18:10:00.269 - INFO - threading running +2023-08-22,18:10:00.279 - INFO - threading running +2023-08-22,18:10:00.289 - INFO - threading running +2023-08-22,18:10:00.299 - INFO - threading running +2023-08-22,18:10:00.310 - INFO - threading running +2023-08-22,18:10:00.321 - INFO - threading running +2023-08-22,18:10:00.331 - INFO - threading running +2023-08-22,18:10:00.340 - INFO - threading running +2023-08-22,18:10:00.350 - INFO - threading running +2023-08-22,18:10:00.360 - INFO - threading running +2023-08-22,18:10:00.370 - INFO - threading running +2023-08-22,18:10:00.380 - INFO - threading running +2023-08-22,18:10:00.390 - INFO - threading running +2023-08-22,18:10:00.400 - INFO - threading running +2023-08-22,18:10:00.410 - INFO - threading running +2023-08-22,18:10:00.421 - INFO - threading running +2023-08-22,18:10:00.430 - INFO - threading running +2023-08-22,18:10:00.440 - INFO - threading running +2023-08-22,18:10:00.451 - INFO - threading running +2023-08-22,18:10:00.462 - INFO - threading running +2023-08-22,18:10:00.472 - INFO - threading running +2023-08-22,18:10:00.482 - INFO - threading running +2023-08-22,18:10:00.491 - INFO - threading running +2023-08-22,18:10:00.502 - INFO - threading running +2023-08-22,18:10:00.512 - INFO - threading running +2023-08-22,18:10:00.522 - INFO - threading running +2023-08-22,18:10:00.532 - INFO - threading running +2023-08-22,18:10:00.542 - INFO - threading running +2023-08-22,18:10:00.553 - INFO - threading running +2023-08-22,18:10:00.562 - INFO - threading running +2023-08-22,18:10:00.572 - INFO - threading running +2023-08-22,18:10:00.582 - INFO - threading running +2023-08-22,18:10:00.593 - INFO - threading running +2023-08-22,18:10:00.603 - INFO - threading running +2023-08-22,18:10:00.613 - INFO - threading running +2023-08-22,18:10:00.623 - INFO - threading running +2023-08-22,18:10:00.634 - INFO - threading running +2023-08-22,18:10:00.643 - INFO - threading running +2023-08-22,18:10:00.653 - INFO - threading running +2023-08-22,18:10:00.664 - INFO - threading running +2023-08-22,18:10:00.674 - INFO - threading running +2023-08-22,18:10:00.684 - INFO - threading running +2023-08-22,18:10:00.694 - INFO - threading running +2023-08-22,18:10:00.705 - INFO - threading running +2023-08-22,18:10:00.714 - INFO - threading running +2023-08-22,18:10:00.724 - INFO - threading running +2023-08-22,18:10:00.734 - INFO - threading running +2023-08-22,18:10:00.744 - INFO - threading running +2023-08-22,18:10:00.754 - INFO - threading running +2023-08-22,18:10:00.764 - INFO - threading running +2023-08-22,18:10:00.775 - INFO - threading running +2023-08-22,18:10:00.785 - INFO - threading running +2023-08-22,18:10:00.795 - INFO - threading running +2023-08-22,18:10:00.806 - INFO - threading running +2023-08-22,18:10:00.816 - INFO - threading running +2023-08-22,18:10:00.826 - INFO - threading running +2023-08-22,18:10:00.834 - INFO - ---------------------------------------------------- +2023-08-22,18:10:00.834 - INFO - 86th iteration +2023-08-22,18:10:00.834 - INFO - average ll reward: 0.0836429530 +2023-08-22,18:10:00.834 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:00.837 - INFO - updating finished +2023-08-22,18:10:04.921 - INFO - threading running +2023-08-22,18:10:04.933 - INFO - threading running +2023-08-22,18:10:04.944 - INFO - threading running +2023-08-22,18:10:04.953 - INFO - threading running +2023-08-22,18:10:04.963 - INFO - threading running +2023-08-22,18:10:04.973 - INFO - threading running +2023-08-22,18:10:04.983 - INFO - threading running +2023-08-22,18:10:04.993 - INFO - threading running +2023-08-22,18:10:05.003 - INFO - threading running +2023-08-22,18:10:05.013 - INFO - threading running +2023-08-22,18:10:05.023 - INFO - threading running +2023-08-22,18:10:05.033 - INFO - threading running +2023-08-22,18:10:05.044 - INFO - threading running +2023-08-22,18:10:05.054 - INFO - threading running +2023-08-22,18:10:05.063 - INFO - threading running +2023-08-22,18:10:05.073 - INFO - threading running +2023-08-22,18:10:05.083 - INFO - threading running +2023-08-22,18:10:05.093 - INFO - threading running +2023-08-22,18:10:05.103 - INFO - threading running +2023-08-22,18:10:05.113 - INFO - threading running +2023-08-22,18:10:05.123 - INFO - threading running +2023-08-22,18:10:05.134 - INFO - threading running +2023-08-22,18:10:05.144 - INFO - threading running +2023-08-22,18:10:05.155 - INFO - threading running +2023-08-22,18:10:05.166 - INFO - threading running +2023-08-22,18:10:05.176 - INFO - threading running +2023-08-22,18:10:05.186 - INFO - threading running +2023-08-22,18:10:05.196 - INFO - threading running +2023-08-22,18:10:05.206 - INFO - threading running +2023-08-22,18:10:05.216 - INFO - threading running +2023-08-22,18:10:05.227 - INFO - threading running +2023-08-22,18:10:05.237 - INFO - threading running +2023-08-22,18:10:05.248 - INFO - threading running +2023-08-22,18:10:05.257 - INFO - threading running +2023-08-22,18:10:05.267 - INFO - threading running +2023-08-22,18:10:05.277 - INFO - threading running +2023-08-22,18:10:05.287 - INFO - threading running +2023-08-22,18:10:05.297 - INFO - threading running +2023-08-22,18:10:05.308 - INFO - threading running +2023-08-22,18:10:05.318 - INFO - threading running +2023-08-22,18:10:05.328 - INFO - threading running +2023-08-22,18:10:05.339 - INFO - threading running +2023-08-22,18:10:05.349 - INFO - threading running +2023-08-22,18:10:05.360 - INFO - threading running +2023-08-22,18:10:05.369 - INFO - threading running +2023-08-22,18:10:05.379 - INFO - threading running +2023-08-22,18:10:05.389 - INFO - threading running +2023-08-22,18:10:05.399 - INFO - threading running +2023-08-22,18:10:05.409 - INFO - threading running +2023-08-22,18:10:05.419 - INFO - threading running +2023-08-22,18:10:05.430 - INFO - threading running +2023-08-22,18:10:05.440 - INFO - threading running +2023-08-22,18:10:05.450 - INFO - threading running +2023-08-22,18:10:05.460 - INFO - threading running +2023-08-22,18:10:05.470 - INFO - threading running +2023-08-22,18:10:05.480 - INFO - threading running +2023-08-22,18:10:05.490 - INFO - threading running +2023-08-22,18:10:05.500 - INFO - threading running +2023-08-22,18:10:05.510 - INFO - threading running +2023-08-22,18:10:05.518 - INFO - ---------------------------------------------------- +2023-08-22,18:10:05.518 - INFO - 87th iteration +2023-08-22,18:10:05.518 - INFO - average ll reward: 0.0938242186 +2023-08-22,18:10:05.518 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:05.520 - INFO - updating finished +2023-08-22,18:10:09.568 - INFO - threading running +2023-08-22,18:10:09.579 - INFO - threading running +2023-08-22,18:10:09.589 - INFO - threading running +2023-08-22,18:10:09.599 - INFO - threading running +2023-08-22,18:10:09.609 - INFO - threading running +2023-08-22,18:10:09.619 - INFO - threading running +2023-08-22,18:10:09.630 - INFO - threading running +2023-08-22,18:10:09.640 - INFO - threading running +2023-08-22,18:10:09.650 - INFO - threading running +2023-08-22,18:10:09.661 - INFO - threading running +2023-08-22,18:10:09.671 - INFO - threading running +2023-08-22,18:10:09.681 - INFO - threading running +2023-08-22,18:10:09.692 - INFO - threading running +2023-08-22,18:10:09.702 - INFO - threading running +2023-08-22,18:10:09.712 - INFO - threading running +2023-08-22,18:10:09.722 - INFO - threading running +2023-08-22,18:10:09.733 - INFO - threading running +2023-08-22,18:10:09.742 - INFO - threading running +2023-08-22,18:10:09.752 - INFO - threading running +2023-08-22,18:10:09.762 - INFO - threading running +2023-08-22,18:10:09.772 - INFO - threading running +2023-08-22,18:10:09.782 - INFO - threading running +2023-08-22,18:10:09.792 - INFO - threading running +2023-08-22,18:10:09.802 - INFO - threading running +2023-08-22,18:10:09.812 - INFO - threading running +2023-08-22,18:10:09.822 - INFO - threading running +2023-08-22,18:10:09.832 - INFO - threading running +2023-08-22,18:10:09.842 - INFO - threading running +2023-08-22,18:10:09.852 - INFO - threading running +2023-08-22,18:10:09.862 - INFO - threading running +2023-08-22,18:10:09.872 - INFO - threading running +2023-08-22,18:10:09.882 - INFO - threading running +2023-08-22,18:10:09.892 - INFO - threading running +2023-08-22,18:10:09.902 - INFO - threading running +2023-08-22,18:10:09.912 - INFO - threading running +2023-08-22,18:10:09.923 - INFO - threading running +2023-08-22,18:10:09.933 - INFO - threading running +2023-08-22,18:10:09.943 - INFO - threading running +2023-08-22,18:10:09.953 - INFO - threading running +2023-08-22,18:10:09.964 - INFO - threading running +2023-08-22,18:10:09.975 - INFO - threading running +2023-08-22,18:10:09.985 - INFO - threading running +2023-08-22,18:10:09.995 - INFO - threading running +2023-08-22,18:10:10.006 - INFO - threading running +2023-08-22,18:10:10.015 - INFO - threading running +2023-08-22,18:10:10.026 - INFO - threading running +2023-08-22,18:10:10.035 - INFO - threading running +2023-08-22,18:10:10.045 - INFO - threading running +2023-08-22,18:10:10.055 - INFO - threading running +2023-08-22,18:10:10.065 - INFO - threading running +2023-08-22,18:10:10.076 - INFO - threading running +2023-08-22,18:10:10.085 - INFO - threading running +2023-08-22,18:10:10.095 - INFO - threading running +2023-08-22,18:10:10.105 - INFO - threading running +2023-08-22,18:10:10.110 - INFO - ---------------------------------------------------- +2023-08-22,18:10:10.110 - INFO - 88th iteration +2023-08-22,18:10:10.110 - INFO - average ll reward: 0.0945299567 +2023-08-22,18:10:10.110 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:10.115 - INFO - updating finished +2023-08-22,18:10:14.172 - INFO - threading running +2023-08-22,18:10:14.180 - INFO - threading running +2023-08-22,18:10:14.190 - INFO - threading running +2023-08-22,18:10:14.199 - INFO - threading running +2023-08-22,18:10:14.209 - INFO - threading running +2023-08-22,18:10:14.219 - INFO - threading running +2023-08-22,18:10:14.229 - INFO - threading running +2023-08-22,18:10:14.239 - INFO - threading running +2023-08-22,18:10:14.249 - INFO - threading running +2023-08-22,18:10:14.259 - INFO - threading running +2023-08-22,18:10:14.270 - INFO - threading running +2023-08-22,18:10:14.279 - INFO - threading running +2023-08-22,18:10:14.289 - INFO - threading running +2023-08-22,18:10:14.299 - INFO - threading running +2023-08-22,18:10:14.309 - INFO - threading running +2023-08-22,18:10:14.319 - INFO - threading running +2023-08-22,18:10:14.329 - INFO - threading running +2023-08-22,18:10:14.340 - INFO - threading running +2023-08-22,18:10:14.350 - INFO - threading running +2023-08-22,18:10:14.361 - INFO - threading running +2023-08-22,18:10:14.371 - INFO - threading running +2023-08-22,18:10:14.382 - INFO - threading running +2023-08-22,18:10:14.393 - INFO - threading running +2023-08-22,18:10:14.402 - INFO - threading running +2023-08-22,18:10:14.412 - INFO - threading running +2023-08-22,18:10:14.422 - INFO - threading running +2023-08-22,18:10:14.433 - INFO - threading running +2023-08-22,18:10:14.443 - INFO - threading running +2023-08-22,18:10:14.453 - INFO - threading running +2023-08-22,18:10:14.463 - INFO - threading running +2023-08-22,18:10:14.473 - INFO - threading running +2023-08-22,18:10:14.483 - INFO - threading running +2023-08-22,18:10:14.494 - INFO - threading running +2023-08-22,18:10:14.503 - INFO - threading running +2023-08-22,18:10:14.513 - INFO - threading running +2023-08-22,18:10:14.523 - INFO - threading running +2023-08-22,18:10:14.533 - INFO - threading running +2023-08-22,18:10:14.543 - INFO - threading running +2023-08-22,18:10:14.554 - INFO - threading running +2023-08-22,18:10:14.564 - INFO - threading running +2023-08-22,18:10:14.575 - INFO - threading running +2023-08-22,18:10:14.586 - INFO - threading running +2023-08-22,18:10:14.596 - INFO - threading running +2023-08-22,18:10:14.607 - INFO - threading running +2023-08-22,18:10:14.617 - INFO - threading running +2023-08-22,18:10:14.628 - INFO - threading running +2023-08-22,18:10:14.637 - INFO - threading running +2023-08-22,18:10:14.647 - INFO - threading running +2023-08-22,18:10:14.657 - INFO - threading running +2023-08-22,18:10:14.667 - INFO - threading running +2023-08-22,18:10:14.677 - INFO - threading running +2023-08-22,18:10:14.687 - INFO - threading running +2023-08-22,18:10:14.697 - INFO - threading running +2023-08-22,18:10:14.708 - INFO - threading running +2023-08-22,18:10:14.717 - INFO - threading running +2023-08-22,18:10:14.727 - INFO - threading running +2023-08-22,18:10:14.737 - INFO - threading running +2023-08-22,18:10:14.747 - INFO - threading running +2023-08-22,18:10:14.758 - INFO - threading running +2023-08-22,18:10:14.768 - INFO - threading running +2023-08-22,18:10:14.778 - INFO - threading running +2023-08-22,18:10:14.785 - INFO - ---------------------------------------------------- +2023-08-22,18:10:14.785 - INFO - 89th iteration +2023-08-22,18:10:14.785 - INFO - average ll reward: 0.0764683972 +2023-08-22,18:10:14.785 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:14.788 - INFO - updating finished +2023-08-22,18:10:18.931 - INFO - threading running +2023-08-22,18:10:18.945 - INFO - threading running +2023-08-22,18:10:18.955 - INFO - threading running +2023-08-22,18:10:18.966 - INFO - threading running +2023-08-22,18:10:18.977 - INFO - threading running +2023-08-22,18:10:18.986 - INFO - threading running +2023-08-22,18:10:18.997 - INFO - threading running +2023-08-22,18:10:19.007 - INFO - threading running +2023-08-22,18:10:19.017 - INFO - threading running +2023-08-22,18:10:19.027 - INFO - threading running +2023-08-22,18:10:19.037 - INFO - threading running +2023-08-22,18:10:19.047 - INFO - threading running +2023-08-22,18:10:19.057 - INFO - threading running +2023-08-22,18:10:19.067 - INFO - threading running +2023-08-22,18:10:19.078 - INFO - threading running +2023-08-22,18:10:19.089 - INFO - threading running +2023-08-22,18:10:19.098 - INFO - threading running +2023-08-22,18:10:19.108 - INFO - threading running +2023-08-22,18:10:19.118 - INFO - threading running +2023-08-22,18:10:19.128 - INFO - threading running +2023-08-22,18:10:19.138 - INFO - threading running +2023-08-22,18:10:19.148 - INFO - threading running +2023-08-22,18:10:19.158 - INFO - threading running +2023-08-22,18:10:19.168 - INFO - threading running +2023-08-22,18:10:19.178 - INFO - threading running +2023-08-22,18:10:19.188 - INFO - threading running +2023-08-22,18:10:19.199 - INFO - threading running +2023-08-22,18:10:19.209 - INFO - threading running +2023-08-22,18:10:19.219 - INFO - threading running +2023-08-22,18:10:19.229 - INFO - threading running +2023-08-22,18:10:19.239 - INFO - threading running +2023-08-22,18:10:19.249 - INFO - threading running +2023-08-22,18:10:19.259 - INFO - threading running +2023-08-22,18:10:19.269 - INFO - threading running +2023-08-22,18:10:19.280 - INFO - threading running +2023-08-22,18:10:19.290 - INFO - threading running +2023-08-22,18:10:19.301 - INFO - threading running +2023-08-22,18:10:19.311 - INFO - threading running +2023-08-22,18:10:19.322 - INFO - threading running +2023-08-22,18:10:19.333 - INFO - threading running +2023-08-22,18:10:19.343 - INFO - threading running +2023-08-22,18:10:19.353 - INFO - threading running +2023-08-22,18:10:19.363 - INFO - threading running +2023-08-22,18:10:19.373 - INFO - threading running +2023-08-22,18:10:19.383 - INFO - threading running +2023-08-22,18:10:19.394 - INFO - threading running +2023-08-22,18:10:19.403 - INFO - threading running +2023-08-22,18:10:19.413 - INFO - threading running +2023-08-22,18:10:19.423 - INFO - threading running +2023-08-22,18:10:19.433 - INFO - threading running +2023-08-22,18:10:19.443 - INFO - threading running +2023-08-22,18:10:19.453 - INFO - threading running +2023-08-22,18:10:19.463 - INFO - threading running +2023-08-22,18:10:19.473 - INFO - threading running +2023-08-22,18:10:19.483 - INFO - threading running +2023-08-22,18:10:19.493 - INFO - threading running +2023-08-22,18:10:19.504 - INFO - threading running +2023-08-22,18:10:19.514 - INFO - threading running +2023-08-22,18:10:19.525 - INFO - threading running +2023-08-22,18:10:19.534 - INFO - threading running +2023-08-22,18:10:19.545 - INFO - threading running +2023-08-22,18:10:19.554 - INFO - threading running +2023-08-22,18:10:19.565 - INFO - threading running +2023-08-22,18:10:19.575 - INFO - threading running +2023-08-22,18:10:19.582 - INFO - ---------------------------------------------------- +2023-08-22,18:10:19.582 - INFO - 90th iteration +2023-08-22,18:10:19.582 - INFO - average ll reward: 0.0881277178 +2023-08-22,18:10:19.582 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:19.585 - INFO - updating finished +2023-08-22,18:10:23.693 - INFO - threading running +2023-08-22,18:10:23.709 - INFO - threading running +2023-08-22,18:10:23.719 - INFO - threading running +2023-08-22,18:10:23.729 - INFO - threading running +2023-08-22,18:10:23.739 - INFO - threading running +2023-08-22,18:10:23.749 - INFO - threading running +2023-08-22,18:10:23.759 - INFO - threading running +2023-08-22,18:10:23.770 - INFO - threading running +2023-08-22,18:10:23.780 - INFO - threading running +2023-08-22,18:10:23.791 - INFO - threading running +2023-08-22,18:10:23.801 - INFO - threading running +2023-08-22,18:10:23.811 - INFO - threading running +2023-08-22,18:10:23.821 - INFO - threading running +2023-08-22,18:10:23.831 - INFO - threading running +2023-08-22,18:10:23.841 - INFO - threading running +2023-08-22,18:10:23.851 - INFO - threading running +2023-08-22,18:10:23.862 - INFO - threading running +2023-08-22,18:10:23.873 - INFO - threading running +2023-08-22,18:10:23.884 - INFO - threading running +2023-08-22,18:10:23.893 - INFO - threading running +2023-08-22,18:10:23.903 - INFO - threading running +2023-08-22,18:10:23.914 - INFO - threading running +2023-08-22,18:10:23.923 - INFO - threading running +2023-08-22,18:10:23.933 - INFO - threading running +2023-08-22,18:10:23.943 - INFO - threading running +2023-08-22,18:10:23.953 - INFO - threading running +2023-08-22,18:10:23.963 - INFO - threading running +2023-08-22,18:10:23.973 - INFO - threading running +2023-08-22,18:10:23.983 - INFO - threading running +2023-08-22,18:10:23.993 - INFO - threading running +2023-08-22,18:10:24.003 - INFO - threading running +2023-08-22,18:10:24.013 - INFO - threading running +2023-08-22,18:10:24.024 - INFO - threading running +2023-08-22,18:10:24.034 - INFO - threading running +2023-08-22,18:10:24.045 - INFO - threading running +2023-08-22,18:10:24.055 - INFO - threading running +2023-08-22,18:10:24.064 - INFO - threading running +2023-08-22,18:10:24.074 - INFO - threading running +2023-08-22,18:10:24.084 - INFO - threading running +2023-08-22,18:10:24.094 - INFO - threading running +2023-08-22,18:10:24.104 - INFO - threading running +2023-08-22,18:10:24.114 - INFO - threading running +2023-08-22,18:10:24.124 - INFO - threading running +2023-08-22,18:10:24.135 - INFO - threading running +2023-08-22,18:10:24.144 - INFO - threading running +2023-08-22,18:10:24.154 - INFO - threading running +2023-08-22,18:10:24.164 - INFO - threading running +2023-08-22,18:10:24.174 - INFO - threading running +2023-08-22,18:10:24.185 - INFO - threading running +2023-08-22,18:10:24.195 - INFO - threading running +2023-08-22,18:10:24.205 - INFO - threading running +2023-08-22,18:10:24.215 - INFO - threading running +2023-08-22,18:10:24.226 - INFO - threading running +2023-08-22,18:10:24.236 - INFO - threading running +2023-08-22,18:10:24.246 - INFO - threading running +2023-08-22,18:10:24.256 - INFO - threading running +2023-08-22,18:10:24.261 - INFO - ---------------------------------------------------- +2023-08-22,18:10:24.261 - INFO - 91th iteration +2023-08-22,18:10:24.261 - INFO - average ll reward: 0.0761568075 +2023-08-22,18:10:24.261 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:24.266 - INFO - updating finished +2023-08-22,18:10:28.332 - INFO - threading running +2023-08-22,18:10:28.343 - INFO - threading running +2023-08-22,18:10:28.354 - INFO - threading running +2023-08-22,18:10:28.363 - INFO - threading running +2023-08-22,18:10:28.373 - INFO - threading running +2023-08-22,18:10:28.383 - INFO - threading running +2023-08-22,18:10:28.393 - INFO - threading running +2023-08-22,18:10:28.403 - INFO - threading running +2023-08-22,18:10:28.413 - INFO - threading running +2023-08-22,18:10:28.423 - INFO - threading running +2023-08-22,18:10:28.433 - INFO - threading running +2023-08-22,18:10:28.443 - INFO - threading running +2023-08-22,18:10:28.453 - INFO - threading running +2023-08-22,18:10:28.463 - INFO - threading running +2023-08-22,18:10:28.474 - INFO - threading running +2023-08-22,18:10:28.484 - INFO - threading running +2023-08-22,18:10:28.494 - INFO - threading running +2023-08-22,18:10:28.504 - INFO - threading running +2023-08-22,18:10:28.515 - INFO - threading running +2023-08-22,18:10:28.525 - INFO - threading running +2023-08-22,18:10:28.535 - INFO - threading running +2023-08-22,18:10:28.546 - INFO - threading running +2023-08-22,18:10:28.555 - INFO - threading running +2023-08-22,18:10:28.565 - INFO - threading running +2023-08-22,18:10:28.575 - INFO - threading running +2023-08-22,18:10:28.585 - INFO - threading running +2023-08-22,18:10:28.595 - INFO - threading running +2023-08-22,18:10:28.606 - INFO - threading running +2023-08-22,18:10:28.616 - INFO - threading running +2023-08-22,18:10:28.627 - INFO - threading running +2023-08-22,18:10:28.637 - INFO - threading running +2023-08-22,18:10:28.648 - INFO - threading running +2023-08-22,18:10:28.658 - INFO - threading running +2023-08-22,18:10:28.667 - INFO - threading running +2023-08-22,18:10:28.678 - INFO - threading running +2023-08-22,18:10:28.687 - INFO - threading running +2023-08-22,18:10:28.697 - INFO - threading running +2023-08-22,18:10:28.708 - INFO - threading running +2023-08-22,18:10:28.717 - INFO - threading running +2023-08-22,18:10:28.727 - INFO - threading running +2023-08-22,18:10:28.737 - INFO - threading running +2023-08-22,18:10:28.747 - INFO - threading running +2023-08-22,18:10:28.757 - INFO - threading running +2023-08-22,18:10:28.767 - INFO - threading running +2023-08-22,18:10:28.777 - INFO - threading running +2023-08-22,18:10:28.787 - INFO - threading running +2023-08-22,18:10:28.798 - INFO - threading running +2023-08-22,18:10:28.809 - INFO - threading running +2023-08-22,18:10:28.818 - INFO - threading running +2023-08-22,18:10:28.828 - INFO - threading running +2023-08-22,18:10:28.839 - INFO - threading running +2023-08-22,18:10:28.848 - INFO - threading running +2023-08-22,18:10:28.858 - INFO - threading running +2023-08-22,18:10:28.868 - INFO - threading running +2023-08-22,18:10:28.878 - INFO - threading running +2023-08-22,18:10:28.888 - INFO - threading running +2023-08-22,18:10:28.896 - INFO - ---------------------------------------------------- +2023-08-22,18:10:28.896 - INFO - 92th iteration +2023-08-22,18:10:28.896 - INFO - average ll reward: 0.0727958989 +2023-08-22,18:10:28.896 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:28.898 - INFO - updating finished +2023-08-22,18:10:32.958 - INFO - threading running +2023-08-22,18:10:32.972 - INFO - threading running +2023-08-22,18:10:32.982 - INFO - threading running +2023-08-22,18:10:32.992 - INFO - threading running +2023-08-22,18:10:33.002 - INFO - threading running +2023-08-22,18:10:33.012 - INFO - threading running +2023-08-22,18:10:33.022 - INFO - threading running +2023-08-22,18:10:33.032 - INFO - threading running +2023-08-22,18:10:33.043 - INFO - threading running +2023-08-22,18:10:33.052 - INFO - threading running +2023-08-22,18:10:33.063 - INFO - threading running +2023-08-22,18:10:33.073 - INFO - threading running +2023-08-22,18:10:33.082 - INFO - threading running +2023-08-22,18:10:33.092 - INFO - threading running +2023-08-22,18:10:33.102 - INFO - threading running +2023-08-22,18:10:33.112 - INFO - threading running +2023-08-22,18:10:33.122 - INFO - threading running +2023-08-22,18:10:33.132 - INFO - threading running +2023-08-22,18:10:33.142 - INFO - threading running +2023-08-22,18:10:33.152 - INFO - threading running +2023-08-22,18:10:33.162 - INFO - threading running +2023-08-22,18:10:33.173 - INFO - threading running +2023-08-22,18:10:33.182 - INFO - threading running +2023-08-22,18:10:33.193 - INFO - threading running +2023-08-22,18:10:33.203 - INFO - threading running +2023-08-22,18:10:33.212 - INFO - threading running +2023-08-22,18:10:33.222 - INFO - threading running +2023-08-22,18:10:33.232 - INFO - threading running +2023-08-22,18:10:33.242 - INFO - threading running +2023-08-22,18:10:33.252 - INFO - threading running +2023-08-22,18:10:33.262 - INFO - threading running +2023-08-22,18:10:33.272 - INFO - threading running +2023-08-22,18:10:33.283 - INFO - threading running +2023-08-22,18:10:33.293 - INFO - threading running +2023-08-22,18:10:33.303 - INFO - threading running +2023-08-22,18:10:33.313 - INFO - threading running +2023-08-22,18:10:33.323 - INFO - threading running +2023-08-22,18:10:33.333 - INFO - threading running +2023-08-22,18:10:33.343 - INFO - threading running +2023-08-22,18:10:33.354 - INFO - threading running +2023-08-22,18:10:33.363 - INFO - threading running +2023-08-22,18:10:33.373 - INFO - threading running +2023-08-22,18:10:33.383 - INFO - threading running +2023-08-22,18:10:33.393 - INFO - threading running +2023-08-22,18:10:33.404 - INFO - threading running +2023-08-22,18:10:33.414 - INFO - threading running +2023-08-22,18:10:33.424 - INFO - threading running +2023-08-22,18:10:33.434 - INFO - threading running +2023-08-22,18:10:33.444 - INFO - threading running +2023-08-22,18:10:33.454 - INFO - threading running +2023-08-22,18:10:33.465 - INFO - threading running +2023-08-22,18:10:33.475 - INFO - threading running +2023-08-22,18:10:33.485 - INFO - threading running +2023-08-22,18:10:33.495 - INFO - threading running +2023-08-22,18:10:33.505 - INFO - threading running +2023-08-22,18:10:33.516 - INFO - threading running +2023-08-22,18:10:33.525 - INFO - threading running +2023-08-22,18:10:33.535 - INFO - threading running +2023-08-22,18:10:33.541 - INFO - ---------------------------------------------------- +2023-08-22,18:10:33.541 - INFO - 93th iteration +2023-08-22,18:10:33.541 - INFO - average ll reward: 0.0693098211 +2023-08-22,18:10:33.541 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:33.546 - INFO - updating finished +2023-08-22,18:10:37.612 - INFO - threading running +2023-08-22,18:10:37.625 - INFO - threading running +2023-08-22,18:10:37.636 - INFO - threading running +2023-08-22,18:10:37.646 - INFO - threading running +2023-08-22,18:10:37.655 - INFO - threading running +2023-08-22,18:10:37.665 - INFO - threading running +2023-08-22,18:10:37.676 - INFO - threading running +2023-08-22,18:10:37.687 - INFO - threading running +2023-08-22,18:10:37.696 - INFO - threading running +2023-08-22,18:10:37.706 - INFO - threading running +2023-08-22,18:10:37.716 - INFO - threading running +2023-08-22,18:10:37.726 - INFO - threading running +2023-08-22,18:10:37.736 - INFO - threading running +2023-08-22,18:10:37.747 - INFO - threading running +2023-08-22,18:10:37.757 - INFO - threading running +2023-08-22,18:10:37.767 - INFO - threading running +2023-08-22,18:10:37.777 - INFO - threading running +2023-08-22,18:10:37.787 - INFO - threading running +2023-08-22,18:10:37.797 - INFO - threading running +2023-08-22,18:10:37.807 - INFO - threading running +2023-08-22,18:10:37.817 - INFO - threading running +2023-08-22,18:10:37.828 - INFO - threading running +2023-08-22,18:10:37.839 - INFO - threading running +2023-08-22,18:10:37.848 - INFO - threading running +2023-08-22,18:10:37.858 - INFO - threading running +2023-08-22,18:10:37.868 - INFO - threading running +2023-08-22,18:10:37.878 - INFO - threading running +2023-08-22,18:10:37.889 - INFO - threading running +2023-08-22,18:10:37.900 - INFO - threading running +2023-08-22,18:10:37.910 - INFO - threading running +2023-08-22,18:10:37.920 - INFO - threading running +2023-08-22,18:10:37.930 - INFO - threading running +2023-08-22,18:10:37.940 - INFO - threading running +2023-08-22,18:10:37.950 - INFO - threading running +2023-08-22,18:10:37.960 - INFO - threading running +2023-08-22,18:10:37.970 - INFO - threading running +2023-08-22,18:10:37.980 - INFO - threading running +2023-08-22,18:10:37.990 - INFO - threading running +2023-08-22,18:10:38.000 - INFO - threading running +2023-08-22,18:10:38.010 - INFO - threading running +2023-08-22,18:10:38.020 - INFO - threading running +2023-08-22,18:10:38.030 - INFO - threading running +2023-08-22,18:10:38.040 - INFO - threading running +2023-08-22,18:10:38.050 - INFO - threading running +2023-08-22,18:10:38.060 - INFO - threading running +2023-08-22,18:10:38.070 - INFO - threading running +2023-08-22,18:10:38.080 - INFO - threading running +2023-08-22,18:10:38.090 - INFO - threading running +2023-08-22,18:10:38.100 - INFO - threading running +2023-08-22,18:10:38.110 - INFO - threading running +2023-08-22,18:10:38.120 - INFO - threading running +2023-08-22,18:10:38.130 - INFO - threading running +2023-08-22,18:10:38.140 - INFO - threading running +2023-08-22,18:10:38.150 - INFO - ---------------------------------------------------- +2023-08-22,18:10:38.150 - INFO - 94th iteration +2023-08-22,18:10:38.150 - INFO - average ll reward: 0.0682924935 +2023-08-22,18:10:38.150 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:38.151 - INFO - updating finished +2023-08-22,18:10:42.282 - INFO - threading running +2023-08-22,18:10:42.293 - INFO - threading running +2023-08-22,18:10:42.303 - INFO - threading running +2023-08-22,18:10:42.313 - INFO - threading running +2023-08-22,18:10:42.323 - INFO - threading running +2023-08-22,18:10:42.333 - INFO - threading running +2023-08-22,18:10:42.344 - INFO - threading running +2023-08-22,18:10:42.354 - INFO - threading running +2023-08-22,18:10:42.364 - INFO - threading running +2023-08-22,18:10:42.374 - INFO - threading running +2023-08-22,18:10:42.384 - INFO - threading running +2023-08-22,18:10:42.394 - INFO - threading running +2023-08-22,18:10:42.404 - INFO - threading running +2023-08-22,18:10:42.414 - INFO - threading running +2023-08-22,18:10:42.425 - INFO - threading running +2023-08-22,18:10:42.435 - INFO - threading running +2023-08-22,18:10:42.446 - INFO - threading running +2023-08-22,18:10:42.455 - INFO - threading running +2023-08-22,18:10:42.465 - INFO - threading running +2023-08-22,18:10:42.475 - INFO - threading running +2023-08-22,18:10:42.486 - INFO - threading running +2023-08-22,18:10:42.497 - INFO - threading running +2023-08-22,18:10:42.507 - INFO - threading running +2023-08-22,18:10:42.517 - INFO - threading running +2023-08-22,18:10:42.527 - INFO - threading running +2023-08-22,18:10:42.537 - INFO - threading running +2023-08-22,18:10:42.547 - INFO - threading running +2023-08-22,18:10:42.557 - INFO - threading running +2023-08-22,18:10:42.567 - INFO - threading running +2023-08-22,18:10:42.578 - INFO - threading running +2023-08-22,18:10:42.588 - INFO - threading running +2023-08-22,18:10:42.598 - INFO - threading running +2023-08-22,18:10:42.609 - INFO - threading running +2023-08-22,18:10:42.620 - INFO - threading running +2023-08-22,18:10:42.631 - INFO - threading running +2023-08-22,18:10:42.641 - INFO - threading running +2023-08-22,18:10:42.652 - INFO - threading running +2023-08-22,18:10:42.663 - INFO - threading running +2023-08-22,18:10:42.673 - INFO - threading running +2023-08-22,18:10:42.683 - INFO - threading running +2023-08-22,18:10:42.694 - INFO - threading running +2023-08-22,18:10:42.704 - INFO - threading running +2023-08-22,18:10:42.714 - INFO - threading running +2023-08-22,18:10:42.724 - INFO - threading running +2023-08-22,18:10:42.734 - INFO - threading running +2023-08-22,18:10:42.744 - INFO - threading running +2023-08-22,18:10:42.754 - INFO - threading running +2023-08-22,18:10:42.764 - INFO - threading running +2023-08-22,18:10:42.774 - INFO - threading running +2023-08-22,18:10:42.784 - INFO - threading running +2023-08-22,18:10:42.794 - INFO - threading running +2023-08-22,18:10:42.805 - INFO - threading running +2023-08-22,18:10:42.815 - INFO - threading running +2023-08-22,18:10:42.825 - INFO - threading running +2023-08-22,18:10:42.835 - INFO - threading running +2023-08-22,18:10:42.837 - INFO - ---------------------------------------------------- +2023-08-22,18:10:42.837 - INFO - 95th iteration +2023-08-22,18:10:42.837 - INFO - average ll reward: 0.0802527498 +2023-08-22,18:10:42.837 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:42.845 - INFO - updating finished +2023-08-22,18:10:46.937 - INFO - threading running +2023-08-22,18:10:46.944 - INFO - threading running +2023-08-22,18:10:46.954 - INFO - threading running +2023-08-22,18:10:46.965 - INFO - threading running +2023-08-22,18:10:46.974 - INFO - threading running +2023-08-22,18:10:46.984 - INFO - threading running +2023-08-22,18:10:46.994 - INFO - threading running +2023-08-22,18:10:47.004 - INFO - threading running +2023-08-22,18:10:47.014 - INFO - threading running +2023-08-22,18:10:47.024 - INFO - threading running +2023-08-22,18:10:47.034 - INFO - threading running +2023-08-22,18:10:47.045 - INFO - threading running +2023-08-22,18:10:47.054 - INFO - threading running +2023-08-22,18:10:47.065 - INFO - threading running +2023-08-22,18:10:47.076 - INFO - threading running +2023-08-22,18:10:47.086 - INFO - threading running +2023-08-22,18:10:47.096 - INFO - threading running +2023-08-22,18:10:47.105 - INFO - threading running +2023-08-22,18:10:47.115 - INFO - threading running +2023-08-22,18:10:47.125 - INFO - threading running +2023-08-22,18:10:47.135 - INFO - threading running +2023-08-22,18:10:47.146 - INFO - threading running +2023-08-22,18:10:47.156 - INFO - threading running +2023-08-22,18:10:47.166 - INFO - threading running +2023-08-22,18:10:47.176 - INFO - threading running +2023-08-22,18:10:47.186 - INFO - threading running +2023-08-22,18:10:47.196 - INFO - threading running +2023-08-22,18:10:47.206 - INFO - threading running +2023-08-22,18:10:47.216 - INFO - threading running +2023-08-22,18:10:47.226 - INFO - threading running +2023-08-22,18:10:47.236 - INFO - threading running +2023-08-22,18:10:47.247 - INFO - threading running +2023-08-22,18:10:47.257 - INFO - threading running +2023-08-22,18:10:47.267 - INFO - threading running +2023-08-22,18:10:47.277 - INFO - threading running +2023-08-22,18:10:47.287 - INFO - threading running +2023-08-22,18:10:47.298 - INFO - threading running +2023-08-22,18:10:47.308 - INFO - threading running +2023-08-22,18:10:47.317 - INFO - threading running +2023-08-22,18:10:47.327 - INFO - threading running +2023-08-22,18:10:47.337 - INFO - threading running +2023-08-22,18:10:47.347 - INFO - threading running +2023-08-22,18:10:47.358 - INFO - threading running +2023-08-22,18:10:47.367 - INFO - threading running +2023-08-22,18:10:47.378 - INFO - threading running +2023-08-22,18:10:47.388 - INFO - threading running +2023-08-22,18:10:47.398 - INFO - threading running +2023-08-22,18:10:47.408 - INFO - threading running +2023-08-22,18:10:47.419 - INFO - threading running +2023-08-22,18:10:47.429 - INFO - threading running +2023-08-22,18:10:47.439 - INFO - threading running +2023-08-22,18:10:47.449 - INFO - threading running +2023-08-22,18:10:47.459 - INFO - threading running +2023-08-22,18:10:47.469 - INFO - threading running +2023-08-22,18:10:47.479 - INFO - threading running +2023-08-22,18:10:47.489 - INFO - threading running +2023-08-22,18:10:47.500 - INFO - threading running +2023-08-22,18:10:47.509 - INFO - threading running +2023-08-22,18:10:47.519 - INFO - threading running +2023-08-22,18:10:47.529 - INFO - threading running +2023-08-22,18:10:47.540 - INFO - threading running +2023-08-22,18:10:47.549 - INFO - ---------------------------------------------------- +2023-08-22,18:10:47.549 - INFO - 96th iteration +2023-08-22,18:10:47.549 - INFO - average ll reward: 0.0782047798 +2023-08-22,18:10:47.549 - INFO - threading running +2023-08-22,18:10:47.550 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:47.559 - INFO - updating finished +2023-08-22,18:10:51.638 - INFO - threading running +2023-08-22,18:10:51.645 - INFO - threading running +2023-08-22,18:10:51.655 - INFO - threading running +2023-08-22,18:10:51.665 - INFO - threading running +2023-08-22,18:10:51.676 - INFO - threading running +2023-08-22,18:10:51.686 - INFO - threading running +2023-08-22,18:10:51.696 - INFO - threading running +2023-08-22,18:10:51.706 - INFO - threading running +2023-08-22,18:10:51.716 - INFO - threading running +2023-08-22,18:10:51.726 - INFO - threading running +2023-08-22,18:10:51.736 - INFO - threading running +2023-08-22,18:10:51.746 - INFO - threading running +2023-08-22,18:10:51.757 - INFO - threading running +2023-08-22,18:10:51.767 - INFO - threading running +2023-08-22,18:10:51.777 - INFO - threading running +2023-08-22,18:10:51.788 - INFO - threading running +2023-08-22,18:10:51.797 - INFO - threading running +2023-08-22,18:10:51.807 - INFO - threading running +2023-08-22,18:10:51.817 - INFO - threading running +2023-08-22,18:10:51.827 - INFO - threading running +2023-08-22,18:10:51.837 - INFO - threading running +2023-08-22,18:10:51.847 - INFO - threading running +2023-08-22,18:10:51.857 - INFO - threading running +2023-08-22,18:10:51.867 - INFO - threading running +2023-08-22,18:10:51.877 - INFO - threading running +2023-08-22,18:10:51.887 - INFO - threading running +2023-08-22,18:10:51.897 - INFO - threading running +2023-08-22,18:10:51.907 - INFO - threading running +2023-08-22,18:10:51.918 - INFO - threading running +2023-08-22,18:10:51.927 - INFO - threading running +2023-08-22,18:10:51.937 - INFO - threading running +2023-08-22,18:10:51.948 - INFO - threading running +2023-08-22,18:10:51.957 - INFO - threading running +2023-08-22,18:10:51.967 - INFO - threading running +2023-08-22,18:10:51.977 - INFO - threading running +2023-08-22,18:10:51.987 - INFO - threading running +2023-08-22,18:10:51.997 - INFO - threading running +2023-08-22,18:10:52.007 - INFO - threading running +2023-08-22,18:10:52.018 - INFO - threading running +2023-08-22,18:10:52.029 - INFO - threading running +2023-08-22,18:10:52.039 - INFO - threading running +2023-08-22,18:10:52.049 - INFO - threading running +2023-08-22,18:10:52.059 - INFO - threading running +2023-08-22,18:10:52.069 - INFO - threading running +2023-08-22,18:10:52.080 - INFO - threading running +2023-08-22,18:10:52.091 - INFO - threading running +2023-08-22,18:10:52.100 - INFO - threading running +2023-08-22,18:10:52.110 - INFO - threading running +2023-08-22,18:10:52.120 - INFO - threading running +2023-08-22,18:10:52.130 - INFO - threading running +2023-08-22,18:10:52.140 - INFO - threading running +2023-08-22,18:10:52.150 - INFO - threading running +2023-08-22,18:10:52.160 - INFO - threading running +2023-08-22,18:10:52.170 - INFO - threading running +2023-08-22,18:10:52.180 - INFO - threading running +2023-08-22,18:10:52.191 - INFO - threading running +2023-08-22,18:10:52.202 - INFO - threading running +2023-08-22,18:10:52.211 - INFO - threading running +2023-08-22,18:10:52.214 - INFO - ---------------------------------------------------- +2023-08-22,18:10:52.214 - INFO - 97th iteration +2023-08-22,18:10:52.215 - INFO - average ll reward: 0.0834538686 +2023-08-22,18:10:52.215 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:52.221 - INFO - updating finished +2023-08-22,18:10:56.290 - INFO - threading running +2023-08-22,18:10:56.302 - INFO - threading running +2023-08-22,18:10:56.312 - INFO - threading running +2023-08-22,18:10:56.322 - INFO - threading running +2023-08-22,18:10:56.332 - INFO - threading running +2023-08-22,18:10:56.343 - INFO - threading running +2023-08-22,18:10:56.353 - INFO - threading running +2023-08-22,18:10:56.363 - INFO - threading running +2023-08-22,18:10:56.374 - INFO - threading running +2023-08-22,18:10:56.384 - INFO - threading running +2023-08-22,18:10:56.394 - INFO - threading running +2023-08-22,18:10:56.404 - INFO - threading running +2023-08-22,18:10:56.414 - INFO - threading running +2023-08-22,18:10:56.424 - INFO - threading running +2023-08-22,18:10:56.434 - INFO - threading running +2023-08-22,18:10:56.445 - INFO - threading running +2023-08-22,18:10:56.455 - INFO - threading running +2023-08-22,18:10:56.466 - INFO - threading running +2023-08-22,18:10:56.476 - INFO - threading running +2023-08-22,18:10:56.486 - INFO - threading running +2023-08-22,18:10:56.496 - INFO - threading running +2023-08-22,18:10:56.506 - INFO - threading running +2023-08-22,18:10:56.516 - INFO - threading running +2023-08-22,18:10:56.526 - INFO - threading running +2023-08-22,18:10:56.536 - INFO - threading running +2023-08-22,18:10:56.547 - INFO - threading running +2023-08-22,18:10:56.558 - INFO - threading running +2023-08-22,18:10:56.568 - INFO - threading running +2023-08-22,18:10:56.578 - INFO - threading running +2023-08-22,18:10:56.589 - INFO - threading running +2023-08-22,18:10:56.598 - INFO - threading running +2023-08-22,18:10:56.609 - INFO - threading running +2023-08-22,18:10:56.619 - INFO - threading running +2023-08-22,18:10:56.628 - INFO - threading running +2023-08-22,18:10:56.639 - INFO - threading running +2023-08-22,18:10:56.648 - INFO - threading running +2023-08-22,18:10:56.658 - INFO - threading running +2023-08-22,18:10:56.668 - INFO - threading running +2023-08-22,18:10:56.678 - INFO - threading running +2023-08-22,18:10:56.688 - INFO - threading running +2023-08-22,18:10:56.698 - INFO - threading running +2023-08-22,18:10:56.709 - INFO - threading running +2023-08-22,18:10:56.719 - INFO - threading running +2023-08-22,18:10:56.729 - INFO - threading running +2023-08-22,18:10:56.739 - INFO - threading running +2023-08-22,18:10:56.749 - INFO - threading running +2023-08-22,18:10:56.759 - INFO - threading running +2023-08-22,18:10:56.769 - INFO - threading running +2023-08-22,18:10:56.779 - INFO - threading running +2023-08-22,18:10:56.790 - INFO - threading running +2023-08-22,18:10:56.799 - INFO - threading running +2023-08-22,18:10:56.809 - INFO - threading running +2023-08-22,18:10:56.819 - INFO - threading running +2023-08-22,18:10:56.829 - INFO - threading running +2023-08-22,18:10:56.839 - INFO - threading running +2023-08-22,18:10:56.847 - INFO - ---------------------------------------------------- +2023-08-22,18:10:56.847 - INFO - 98th iteration +2023-08-22,18:10:56.847 - INFO - average ll reward: 0.0827081835 +2023-08-22,18:10:56.847 - INFO - ---------------------------------------------------- + +2023-08-22,18:10:56.850 - INFO - updating finished +2023-08-22,18:11:00.902 - INFO - threading running +2023-08-22,18:11:00.914 - INFO - threading running +2023-08-22,18:11:00.924 - INFO - threading running +2023-08-22,18:11:00.935 - INFO - threading running +2023-08-22,18:11:00.945 - INFO - threading running +2023-08-22,18:11:00.955 - INFO - threading running +2023-08-22,18:11:00.965 - INFO - threading running +2023-08-22,18:11:00.975 - INFO - threading running +2023-08-22,18:11:00.985 - INFO - threading running +2023-08-22,18:11:00.995 - INFO - threading running +2023-08-22,18:11:01.005 - INFO - threading running +2023-08-22,18:11:01.015 - INFO - threading running +2023-08-22,18:11:01.025 - INFO - threading running +2023-08-22,18:11:01.036 - INFO - threading running +2023-08-22,18:11:01.046 - INFO - threading running +2023-08-22,18:11:01.057 - INFO - threading running +2023-08-22,18:11:01.068 - INFO - threading running +2023-08-22,18:11:01.078 - INFO - threading running +2023-08-22,18:11:01.089 - INFO - threading running +2023-08-22,18:11:01.098 - INFO - threading running +2023-08-22,18:11:01.109 - INFO - threading running +2023-08-22,18:11:01.118 - INFO - threading running +2023-08-22,18:11:01.128 - INFO - threading running +2023-08-22,18:11:01.138 - INFO - threading running +2023-08-22,18:11:01.149 - INFO - threading running +2023-08-22,18:11:01.159 - INFO - threading running +2023-08-22,18:11:01.169 - INFO - threading running +2023-08-22,18:11:01.179 - INFO - threading running +2023-08-22,18:11:01.189 - INFO - threading running +2023-08-22,18:11:01.199 - INFO - threading running +2023-08-22,18:11:01.210 - INFO - threading running +2023-08-22,18:11:01.220 - INFO - threading running +2023-08-22,18:11:01.230 - INFO - threading running +2023-08-22,18:11:01.240 - INFO - threading running +2023-08-22,18:11:01.251 - INFO - threading running +2023-08-22,18:11:01.261 - INFO - threading running +2023-08-22,18:11:01.271 - INFO - threading running +2023-08-22,18:11:01.281 - INFO - threading running +2023-08-22,18:11:01.291 - INFO - threading running +2023-08-22,18:11:01.301 - INFO - threading running +2023-08-22,18:11:01.311 - INFO - threading running +2023-08-22,18:11:01.321 - INFO - threading running +2023-08-22,18:11:01.331 - INFO - threading running +2023-08-22,18:11:01.341 - INFO - threading running +2023-08-22,18:11:01.351 - INFO - threading running +2023-08-22,18:11:01.361 - INFO - threading running +2023-08-22,18:11:01.371 - INFO - threading running +2023-08-22,18:11:01.382 - INFO - threading running +2023-08-22,18:11:01.392 - INFO - threading running +2023-08-22,18:11:01.401 - INFO - threading running +2023-08-22,18:11:01.411 - INFO - threading running +2023-08-22,18:11:01.421 - INFO - threading running +2023-08-22,18:11:01.431 - INFO - threading running +2023-08-22,18:11:01.441 - INFO - threading running +2023-08-22,18:11:01.451 - INFO - threading running +2023-08-22,18:11:01.461 - INFO - threading running +2023-08-22,18:11:01.472 - INFO - threading running +2023-08-22,18:11:01.482 - INFO - threading running +2023-08-22,18:11:01.493 - INFO - threading running +2023-08-22,18:11:01.502 - INFO - threading running +2023-08-22,18:11:01.513 - INFO - threading running +2023-08-22,18:11:01.517 - INFO - ---------------------------------------------------- +2023-08-22,18:11:01.517 - INFO - 99th iteration +2023-08-22,18:11:01.517 - INFO - average ll reward: 0.0788439365 +2023-08-22,18:11:01.518 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:01.522 - INFO - updating finished +2023-08-22,18:11:05.675 - INFO - threading running +2023-08-22,18:11:05.689 - INFO - threading running +2023-08-22,18:11:05.699 - INFO - threading running +2023-08-22,18:11:05.709 - INFO - threading running +2023-08-22,18:11:05.719 - INFO - threading running +2023-08-22,18:11:05.729 - INFO - threading running +2023-08-22,18:11:05.739 - INFO - threading running +2023-08-22,18:11:05.750 - INFO - threading running +2023-08-22,18:11:05.760 - INFO - threading running +2023-08-22,18:11:05.770 - INFO - threading running +2023-08-22,18:11:05.780 - INFO - threading running +2023-08-22,18:11:05.790 - INFO - threading running +2023-08-22,18:11:05.800 - INFO - threading running +2023-08-22,18:11:05.811 - INFO - threading running +2023-08-22,18:11:05.821 - INFO - threading running +2023-08-22,18:11:05.831 - INFO - threading running +2023-08-22,18:11:05.841 - INFO - threading running +2023-08-22,18:11:05.852 - INFO - threading running +2023-08-22,18:11:05.861 - INFO - threading running +2023-08-22,18:11:05.871 - INFO - threading running +2023-08-22,18:11:05.881 - INFO - threading running +2023-08-22,18:11:05.892 - INFO - threading running +2023-08-22,18:11:05.901 - INFO - threading running +2023-08-22,18:11:05.912 - INFO - threading running +2023-08-22,18:11:05.921 - INFO - threading running +2023-08-22,18:11:05.931 - INFO - threading running +2023-08-22,18:11:05.942 - INFO - threading running +2023-08-22,18:11:05.951 - INFO - threading running +2023-08-22,18:11:05.962 - INFO - threading running +2023-08-22,18:11:05.971 - INFO - threading running +2023-08-22,18:11:05.981 - INFO - threading running +2023-08-22,18:11:05.991 - INFO - threading running +2023-08-22,18:11:06.001 - INFO - threading running +2023-08-22,18:11:06.011 - INFO - threading running +2023-08-22,18:11:06.022 - INFO - threading running +2023-08-22,18:11:06.032 - INFO - threading running +2023-08-22,18:11:06.042 - INFO - threading running +2023-08-22,18:11:06.053 - INFO - threading running +2023-08-22,18:11:06.063 - INFO - threading running +2023-08-22,18:11:06.074 - INFO - threading running +2023-08-22,18:11:06.084 - INFO - threading running +2023-08-22,18:11:06.095 - INFO - threading running +2023-08-22,18:11:06.104 - INFO - threading running +2023-08-22,18:11:06.114 - INFO - threading running +2023-08-22,18:11:06.124 - INFO - threading running +2023-08-22,18:11:06.135 - INFO - threading running +2023-08-22,18:11:06.146 - INFO - threading running +2023-08-22,18:11:06.156 - INFO - threading running +2023-08-22,18:11:06.166 - INFO - threading running +2023-08-22,18:11:06.176 - INFO - threading running +2023-08-22,18:11:06.186 - INFO - threading running +2023-08-22,18:11:06.196 - INFO - threading running +2023-08-22,18:11:06.207 - INFO - threading running +2023-08-22,18:11:06.217 - INFO - threading running +2023-08-22,18:11:06.227 - INFO - threading running +2023-08-22,18:11:06.237 - INFO - threading running +2023-08-22,18:11:06.247 - INFO - threading running +2023-08-22,18:11:06.257 - INFO - threading running +2023-08-22,18:11:06.268 - INFO - threading running +2023-08-22,18:11:06.278 - INFO - threading running +2023-08-22,18:11:06.281 - INFO - ---------------------------------------------------- +2023-08-22,18:11:06.281 - INFO - 100th iteration +2023-08-22,18:11:06.281 - INFO - average ll reward: 0.0964767258 +2023-08-22,18:11:06.281 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:06.289 - INFO - updating finished +2023-08-22,18:11:10.407 - INFO - threading running +2023-08-22,18:11:10.418 - INFO - threading running +2023-08-22,18:11:10.428 - INFO - threading running +2023-08-22,18:11:10.438 - INFO - threading running +2023-08-22,18:11:10.448 - INFO - threading running +2023-08-22,18:11:10.458 - INFO - threading running +2023-08-22,18:11:10.468 - INFO - threading running +2023-08-22,18:11:10.478 - INFO - threading running +2023-08-22,18:11:10.489 - INFO - threading running +2023-08-22,18:11:10.498 - INFO - threading running +2023-08-22,18:11:10.508 - INFO - threading running +2023-08-22,18:11:10.518 - INFO - threading running +2023-08-22,18:11:10.529 - INFO - threading running +2023-08-22,18:11:10.539 - INFO - threading running +2023-08-22,18:11:10.548 - INFO - threading running +2023-08-22,18:11:10.558 - INFO - threading running +2023-08-22,18:11:10.568 - INFO - threading running +2023-08-22,18:11:10.578 - INFO - threading running +2023-08-22,18:11:10.588 - INFO - threading running +2023-08-22,18:11:10.598 - INFO - threading running +2023-08-22,18:11:10.608 - INFO - threading running +2023-08-22,18:11:10.618 - INFO - threading running +2023-08-22,18:11:10.628 - INFO - threading running +2023-08-22,18:11:10.638 - INFO - threading running +2023-08-22,18:11:10.648 - INFO - threading running +2023-08-22,18:11:10.659 - INFO - threading running +2023-08-22,18:11:10.669 - INFO - threading running +2023-08-22,18:11:10.680 - INFO - threading running +2023-08-22,18:11:10.690 - INFO - threading running +2023-08-22,18:11:10.700 - INFO - threading running +2023-08-22,18:11:10.711 - INFO - threading running +2023-08-22,18:11:10.721 - INFO - threading running +2023-08-22,18:11:10.731 - INFO - threading running +2023-08-22,18:11:10.741 - INFO - threading running +2023-08-22,18:11:10.751 - INFO - threading running +2023-08-22,18:11:10.761 - INFO - threading running +2023-08-22,18:11:10.771 - INFO - threading running +2023-08-22,18:11:10.782 - INFO - threading running +2023-08-22,18:11:10.792 - INFO - threading running +2023-08-22,18:11:10.801 - INFO - threading running +2023-08-22,18:11:10.811 - INFO - threading running +2023-08-22,18:11:10.821 - INFO - threading running +2023-08-22,18:11:10.831 - INFO - threading running +2023-08-22,18:11:10.841 - INFO - threading running +2023-08-22,18:11:10.851 - INFO - threading running +2023-08-22,18:11:10.861 - INFO - threading running +2023-08-22,18:11:10.871 - INFO - threading running +2023-08-22,18:11:10.882 - INFO - threading running +2023-08-22,18:11:10.891 - INFO - threading running +2023-08-22,18:11:10.901 - INFO - threading running +2023-08-22,18:11:10.912 - INFO - threading running +2023-08-22,18:11:10.923 - INFO - threading running +2023-08-22,18:11:10.933 - INFO - threading running +2023-08-22,18:11:10.943 - INFO - threading running +2023-08-22,18:11:10.953 - INFO - threading running +2023-08-22,18:11:10.964 - INFO - threading running +2023-08-22,18:11:10.974 - INFO - threading running +2023-08-22,18:11:10.979 - INFO - ---------------------------------------------------- +2023-08-22,18:11:10.979 - INFO - 101th iteration +2023-08-22,18:11:10.979 - INFO - average ll reward: 0.1005593526 +2023-08-22,18:11:10.979 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:10.983 - INFO - updating finished +2023-08-22,18:11:15.085 - INFO - threading running +2023-08-22,18:11:15.097 - INFO - threading running +2023-08-22,18:11:15.108 - INFO - threading running +2023-08-22,18:11:15.118 - INFO - threading running +2023-08-22,18:11:15.128 - INFO - threading running +2023-08-22,18:11:15.138 - INFO - threading running +2023-08-22,18:11:15.148 - INFO - threading running +2023-08-22,18:11:15.159 - INFO - threading running +2023-08-22,18:11:15.168 - INFO - threading running +2023-08-22,18:11:15.178 - INFO - threading running +2023-08-22,18:11:15.188 - INFO - threading running +2023-08-22,18:11:15.199 - INFO - threading running +2023-08-22,18:11:15.209 - INFO - threading running +2023-08-22,18:11:15.218 - INFO - threading running +2023-08-22,18:11:15.228 - INFO - threading running +2023-08-22,18:11:15.239 - INFO - threading running +2023-08-22,18:11:15.249 - INFO - threading running +2023-08-22,18:11:15.259 - INFO - threading running +2023-08-22,18:11:15.269 - INFO - threading running +2023-08-22,18:11:15.279 - INFO - threading running +2023-08-22,18:11:15.289 - INFO - threading running +2023-08-22,18:11:15.299 - INFO - threading running +2023-08-22,18:11:15.310 - INFO - threading running +2023-08-22,18:11:15.319 - INFO - threading running +2023-08-22,18:11:15.329 - INFO - threading running +2023-08-22,18:11:15.339 - INFO - threading running +2023-08-22,18:11:15.350 - INFO - threading running +2023-08-22,18:11:15.361 - INFO - threading running +2023-08-22,18:11:15.371 - INFO - threading running +2023-08-22,18:11:15.381 - INFO - threading running +2023-08-22,18:11:15.391 - INFO - threading running +2023-08-22,18:11:15.401 - INFO - threading running +2023-08-22,18:11:15.412 - INFO - threading running +2023-08-22,18:11:15.423 - INFO - threading running +2023-08-22,18:11:15.432 - INFO - threading running +2023-08-22,18:11:15.442 - INFO - threading running +2023-08-22,18:11:15.452 - INFO - threading running +2023-08-22,18:11:15.462 - INFO - threading running +2023-08-22,18:11:15.472 - INFO - threading running +2023-08-22,18:11:15.483 - INFO - threading running +2023-08-22,18:11:15.493 - INFO - threading running +2023-08-22,18:11:15.503 - INFO - threading running +2023-08-22,18:11:15.513 - INFO - threading running +2023-08-22,18:11:15.524 - INFO - threading running +2023-08-22,18:11:15.533 - INFO - threading running +2023-08-22,18:11:15.543 - INFO - threading running +2023-08-22,18:11:15.554 - INFO - threading running +2023-08-22,18:11:15.564 - INFO - threading running +2023-08-22,18:11:15.574 - INFO - threading running +2023-08-22,18:11:15.585 - INFO - threading running +2023-08-22,18:11:15.595 - INFO - threading running +2023-08-22,18:11:15.605 - INFO - threading running +2023-08-22,18:11:15.615 - INFO - threading running +2023-08-22,18:11:15.625 - INFO - threading running +2023-08-22,18:11:15.635 - INFO - threading running +2023-08-22,18:11:15.645 - INFO - threading running +2023-08-22,18:11:15.655 - INFO - threading running +2023-08-22,18:11:15.666 - INFO - threading running +2023-08-22,18:11:15.677 - INFO - threading running +2023-08-22,18:11:15.683 - INFO - ---------------------------------------------------- +2023-08-22,18:11:15.683 - INFO - 102th iteration +2023-08-22,18:11:15.683 - INFO - average ll reward: 0.0863593770 +2023-08-22,18:11:15.683 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:15.687 - INFO - updating finished +2023-08-22,18:11:19.770 - INFO - threading running +2023-08-22,18:11:19.777 - INFO - threading running +2023-08-22,18:11:19.787 - INFO - threading running +2023-08-22,18:11:19.797 - INFO - threading running +2023-08-22,18:11:19.808 - INFO - threading running +2023-08-22,18:11:19.818 - INFO - threading running +2023-08-22,18:11:19.828 - INFO - threading running +2023-08-22,18:11:19.839 - INFO - threading running +2023-08-22,18:11:19.850 - INFO - threading running +2023-08-22,18:11:19.859 - INFO - threading running +2023-08-22,18:11:19.869 - INFO - threading running +2023-08-22,18:11:19.879 - INFO - threading running +2023-08-22,18:11:19.890 - INFO - threading running +2023-08-22,18:11:19.899 - INFO - threading running +2023-08-22,18:11:19.909 - INFO - threading running +2023-08-22,18:11:19.920 - INFO - threading running +2023-08-22,18:11:19.930 - INFO - threading running +2023-08-22,18:11:19.940 - INFO - threading running +2023-08-22,18:11:19.950 - INFO - threading running +2023-08-22,18:11:19.960 - INFO - threading running +2023-08-22,18:11:19.970 - INFO - threading running +2023-08-22,18:11:19.980 - INFO - threading running +2023-08-22,18:11:19.990 - INFO - threading running +2023-08-22,18:11:20.000 - INFO - threading running +2023-08-22,18:11:20.010 - INFO - threading running +2023-08-22,18:11:20.020 - INFO - threading running +2023-08-22,18:11:20.031 - INFO - threading running +2023-08-22,18:11:20.041 - INFO - threading running +2023-08-22,18:11:20.051 - INFO - threading running +2023-08-22,18:11:20.062 - INFO - threading running +2023-08-22,18:11:20.071 - INFO - threading running +2023-08-22,18:11:20.082 - INFO - threading running +2023-08-22,18:11:20.091 - INFO - threading running +2023-08-22,18:11:20.101 - INFO - threading running +2023-08-22,18:11:20.111 - INFO - threading running +2023-08-22,18:11:20.121 - INFO - threading running +2023-08-22,18:11:20.131 - INFO - threading running +2023-08-22,18:11:20.142 - INFO - threading running +2023-08-22,18:11:20.152 - INFO - threading running +2023-08-22,18:11:20.162 - INFO - threading running +2023-08-22,18:11:20.172 - INFO - threading running +2023-08-22,18:11:20.182 - INFO - threading running +2023-08-22,18:11:20.192 - INFO - threading running +2023-08-22,18:11:20.202 - INFO - threading running +2023-08-22,18:11:20.212 - INFO - threading running +2023-08-22,18:11:20.222 - INFO - threading running +2023-08-22,18:11:20.232 - INFO - threading running +2023-08-22,18:11:20.242 - INFO - threading running +2023-08-22,18:11:20.252 - INFO - threading running +2023-08-22,18:11:20.262 - INFO - threading running +2023-08-22,18:11:20.272 - INFO - threading running +2023-08-22,18:11:20.282 - INFO - threading running +2023-08-22,18:11:20.292 - INFO - threading running +2023-08-22,18:11:20.303 - INFO - threading running +2023-08-22,18:11:20.310 - INFO - ---------------------------------------------------- +2023-08-22,18:11:20.310 - INFO - 103th iteration +2023-08-22,18:11:20.310 - INFO - average ll reward: 0.0928361842 +2023-08-22,18:11:20.310 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:20.313 - INFO - updating finished +2023-08-22,18:11:24.352 - INFO - threading running +2023-08-22,18:11:24.365 - INFO - threading running +2023-08-22,18:11:24.376 - INFO - threading running +2023-08-22,18:11:24.385 - INFO - threading running +2023-08-22,18:11:24.395 - INFO - threading running +2023-08-22,18:11:24.406 - INFO - threading running +2023-08-22,18:11:24.416 - INFO - threading running +2023-08-22,18:11:24.427 - INFO - threading running +2023-08-22,18:11:24.437 - INFO - threading running +2023-08-22,18:11:24.446 - INFO - threading running +2023-08-22,18:11:24.456 - INFO - threading running +2023-08-22,18:11:24.466 - INFO - threading running +2023-08-22,18:11:24.477 - INFO - threading running +2023-08-22,18:11:24.487 - INFO - threading running +2023-08-22,18:11:24.497 - INFO - threading running +2023-08-22,18:11:24.507 - INFO - threading running +2023-08-22,18:11:24.517 - INFO - threading running +2023-08-22,18:11:24.527 - INFO - threading running +2023-08-22,18:11:24.537 - INFO - threading running +2023-08-22,18:11:24.547 - INFO - threading running +2023-08-22,18:11:24.558 - INFO - threading running +2023-08-22,18:11:24.568 - INFO - threading running +2023-08-22,18:11:24.578 - INFO - threading running +2023-08-22,18:11:24.588 - INFO - threading running +2023-08-22,18:11:24.598 - INFO - threading running +2023-08-22,18:11:24.609 - INFO - threading running +2023-08-22,18:11:24.618 - INFO - threading running +2023-08-22,18:11:24.628 - INFO - threading running +2023-08-22,18:11:24.638 - INFO - threading running +2023-08-22,18:11:24.648 - INFO - threading running +2023-08-22,18:11:24.658 - INFO - threading running +2023-08-22,18:11:24.669 - INFO - threading running +2023-08-22,18:11:24.678 - INFO - threading running +2023-08-22,18:11:24.688 - INFO - threading running +2023-08-22,18:11:24.698 - INFO - threading running +2023-08-22,18:11:24.708 - INFO - threading running +2023-08-22,18:11:24.718 - INFO - threading running +2023-08-22,18:11:24.729 - INFO - threading running +2023-08-22,18:11:24.739 - INFO - threading running +2023-08-22,18:11:24.749 - INFO - threading running +2023-08-22,18:11:24.759 - INFO - threading running +2023-08-22,18:11:24.770 - INFO - threading running +2023-08-22,18:11:24.781 - INFO - threading running +2023-08-22,18:11:24.790 - INFO - threading running +2023-08-22,18:11:24.800 - INFO - threading running +2023-08-22,18:11:24.811 - INFO - threading running +2023-08-22,18:11:24.822 - INFO - threading running +2023-08-22,18:11:24.833 - INFO - threading running +2023-08-22,18:11:24.843 - INFO - threading running +2023-08-22,18:11:24.852 - INFO - threading running +2023-08-22,18:11:24.862 - INFO - threading running +2023-08-22,18:11:24.872 - INFO - threading running +2023-08-22,18:11:24.882 - INFO - threading running +2023-08-22,18:11:24.892 - INFO - threading running +2023-08-22,18:11:24.902 - INFO - threading running +2023-08-22,18:11:24.912 - INFO - threading running +2023-08-22,18:11:24.923 - INFO - threading running +2023-08-22,18:11:24.929 - INFO - ---------------------------------------------------- +2023-08-22,18:11:24.929 - INFO - 104th iteration +2023-08-22,18:11:24.929 - INFO - average ll reward: 0.0962024206 +2023-08-22,18:11:24.929 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:24.932 - INFO - updating finished +2023-08-22,18:11:29.018 - INFO - threading running +2023-08-22,18:11:29.030 - INFO - threading running +2023-08-22,18:11:29.040 - INFO - threading running +2023-08-22,18:11:29.051 - INFO - threading running +2023-08-22,18:11:29.060 - INFO - threading running +2023-08-22,18:11:29.071 - INFO - threading running +2023-08-22,18:11:29.080 - INFO - threading running +2023-08-22,18:11:29.090 - INFO - threading running +2023-08-22,18:11:29.100 - INFO - threading running +2023-08-22,18:11:29.110 - INFO - threading running +2023-08-22,18:11:29.120 - INFO - threading running +2023-08-22,18:11:29.130 - INFO - threading running +2023-08-22,18:11:29.141 - INFO - threading running +2023-08-22,18:11:29.150 - INFO - threading running +2023-08-22,18:11:29.161 - INFO - threading running +2023-08-22,18:11:29.171 - INFO - threading running +2023-08-22,18:11:29.181 - INFO - threading running +2023-08-22,18:11:29.191 - INFO - threading running +2023-08-22,18:11:29.202 - INFO - threading running +2023-08-22,18:11:29.213 - INFO - threading running +2023-08-22,18:11:29.222 - INFO - threading running +2023-08-22,18:11:29.233 - INFO - threading running +2023-08-22,18:11:29.242 - INFO - threading running +2023-08-22,18:11:29.252 - INFO - threading running +2023-08-22,18:11:29.262 - INFO - threading running +2023-08-22,18:11:29.273 - INFO - threading running +2023-08-22,18:11:29.282 - INFO - threading running +2023-08-22,18:11:29.293 - INFO - threading running +2023-08-22,18:11:29.302 - INFO - threading running +2023-08-22,18:11:29.312 - INFO - threading running +2023-08-22,18:11:29.322 - INFO - threading running +2023-08-22,18:11:29.332 - INFO - threading running +2023-08-22,18:11:29.342 - INFO - threading running +2023-08-22,18:11:29.352 - INFO - threading running +2023-08-22,18:11:29.362 - INFO - threading running +2023-08-22,18:11:29.373 - INFO - threading running +2023-08-22,18:11:29.383 - INFO - threading running +2023-08-22,18:11:29.393 - INFO - threading running +2023-08-22,18:11:29.403 - INFO - threading running +2023-08-22,18:11:29.414 - INFO - threading running +2023-08-22,18:11:29.424 - INFO - threading running +2023-08-22,18:11:29.434 - INFO - threading running +2023-08-22,18:11:29.444 - INFO - threading running +2023-08-22,18:11:29.454 - INFO - threading running +2023-08-22,18:11:29.464 - INFO - threading running +2023-08-22,18:11:29.474 - INFO - threading running +2023-08-22,18:11:29.485 - INFO - threading running +2023-08-22,18:11:29.496 - INFO - threading running +2023-08-22,18:11:29.505 - INFO - threading running +2023-08-22,18:11:29.515 - INFO - threading running +2023-08-22,18:11:29.525 - INFO - threading running +2023-08-22,18:11:29.535 - INFO - threading running +2023-08-22,18:11:29.545 - INFO - threading running +2023-08-22,18:11:29.556 - INFO - threading running +2023-08-22,18:11:29.565 - INFO - threading running +2023-08-22,18:11:29.575 - INFO - threading running +2023-08-22,18:11:29.585 - INFO - threading running +2023-08-22,18:11:29.595 - INFO - threading running +2023-08-22,18:11:29.602 - INFO - ---------------------------------------------------- +2023-08-22,18:11:29.602 - INFO - 105th iteration +2023-08-22,18:11:29.603 - INFO - average ll reward: 0.1080108761 +2023-08-22,18:11:29.603 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:29.605 - INFO - updating finished +2023-08-22,18:11:33.737 - INFO - threading running +2023-08-22,18:11:33.744 - INFO - threading running +2023-08-22,18:11:33.754 - INFO - threading running +2023-08-22,18:11:33.764 - INFO - threading running +2023-08-22,18:11:33.774 - INFO - threading running +2023-08-22,18:11:33.784 - INFO - threading running +2023-08-22,18:11:33.794 - INFO - threading running +2023-08-22,18:11:33.804 - INFO - threading running +2023-08-22,18:11:33.814 - INFO - threading running +2023-08-22,18:11:33.825 - INFO - threading running +2023-08-22,18:11:33.836 - INFO - threading running +2023-08-22,18:11:33.845 - INFO - threading running +2023-08-22,18:11:33.856 - INFO - threading running +2023-08-22,18:11:33.866 - INFO - threading running +2023-08-22,18:11:33.875 - INFO - threading running +2023-08-22,18:11:33.885 - INFO - threading running +2023-08-22,18:11:33.895 - INFO - threading running +2023-08-22,18:11:33.905 - INFO - threading running +2023-08-22,18:11:33.915 - INFO - threading running +2023-08-22,18:11:33.925 - INFO - threading running +2023-08-22,18:11:33.935 - INFO - threading running +2023-08-22,18:11:33.946 - INFO - threading running +2023-08-22,18:11:33.956 - INFO - threading running +2023-08-22,18:11:33.966 - INFO - threading running +2023-08-22,18:11:33.976 - INFO - threading running +2023-08-22,18:11:33.986 - INFO - threading running +2023-08-22,18:11:33.997 - INFO - threading running +2023-08-22,18:11:34.006 - INFO - threading running +2023-08-22,18:11:34.017 - INFO - threading running +2023-08-22,18:11:34.027 - INFO - threading running +2023-08-22,18:11:34.037 - INFO - threading running +2023-08-22,18:11:34.047 - INFO - threading running +2023-08-22,18:11:34.058 - INFO - threading running +2023-08-22,18:11:34.069 - INFO - threading running +2023-08-22,18:11:34.080 - INFO - threading running +2023-08-22,18:11:34.091 - INFO - threading running +2023-08-22,18:11:34.101 - INFO - threading running +2023-08-22,18:11:34.111 - INFO - threading running +2023-08-22,18:11:34.121 - INFO - threading running +2023-08-22,18:11:34.131 - INFO - threading running +2023-08-22,18:11:34.141 - INFO - threading running +2023-08-22,18:11:34.151 - INFO - threading running +2023-08-22,18:11:34.161 - INFO - threading running +2023-08-22,18:11:34.171 - INFO - threading running +2023-08-22,18:11:34.181 - INFO - threading running +2023-08-22,18:11:34.191 - INFO - threading running +2023-08-22,18:11:34.202 - INFO - threading running +2023-08-22,18:11:34.213 - INFO - threading running +2023-08-22,18:11:34.223 - INFO - threading running +2023-08-22,18:11:34.233 - INFO - threading running +2023-08-22,18:11:34.243 - INFO - threading running +2023-08-22,18:11:34.253 - INFO - threading running +2023-08-22,18:11:34.263 - INFO - threading running +2023-08-22,18:11:34.273 - INFO - threading running +2023-08-22,18:11:34.283 - INFO - threading running +2023-08-22,18:11:34.293 - INFO - threading running +2023-08-22,18:11:34.303 - INFO - threading running +2023-08-22,18:11:34.314 - INFO - threading running +2023-08-22,18:11:34.323 - INFO - threading running +2023-08-22,18:11:34.329 - INFO - ---------------------------------------------------- +2023-08-22,18:11:34.329 - INFO - 106th iteration +2023-08-22,18:11:34.329 - INFO - average ll reward: 0.0945512624 +2023-08-22,18:11:34.329 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:34.334 - INFO - updating finished +2023-08-22,18:11:38.420 - INFO - threading running +2023-08-22,18:11:38.428 - INFO - threading running +2023-08-22,18:11:38.438 - INFO - threading running +2023-08-22,18:11:38.448 - INFO - threading running +2023-08-22,18:11:38.458 - INFO - threading running +2023-08-22,18:11:38.468 - INFO - threading running +2023-08-22,18:11:38.479 - INFO - threading running +2023-08-22,18:11:38.489 - INFO - threading running +2023-08-22,18:11:38.499 - INFO - threading running +2023-08-22,18:11:38.508 - INFO - threading running +2023-08-22,18:11:38.519 - INFO - threading running +2023-08-22,18:11:38.529 - INFO - threading running +2023-08-22,18:11:38.539 - INFO - threading running +2023-08-22,18:11:38.549 - INFO - threading running +2023-08-22,18:11:38.559 - INFO - threading running +2023-08-22,18:11:38.569 - INFO - threading running +2023-08-22,18:11:38.579 - INFO - threading running +2023-08-22,18:11:38.589 - INFO - threading running +2023-08-22,18:11:38.599 - INFO - threading running +2023-08-22,18:11:38.609 - INFO - threading running +2023-08-22,18:11:38.619 - INFO - threading running +2023-08-22,18:11:38.630 - INFO - threading running +2023-08-22,18:11:38.640 - INFO - threading running +2023-08-22,18:11:38.651 - INFO - threading running +2023-08-22,18:11:38.661 - INFO - threading running +2023-08-22,18:11:38.671 - INFO - threading running +2023-08-22,18:11:38.681 - INFO - threading running +2023-08-22,18:11:38.691 - INFO - threading running +2023-08-22,18:11:38.701 - INFO - threading running +2023-08-22,18:11:38.711 - INFO - threading running +2023-08-22,18:11:38.721 - INFO - threading running +2023-08-22,18:11:38.731 - INFO - threading running +2023-08-22,18:11:38.742 - INFO - threading running +2023-08-22,18:11:38.752 - INFO - threading running +2023-08-22,18:11:38.763 - INFO - threading running +2023-08-22,18:11:38.772 - INFO - threading running +2023-08-22,18:11:38.782 - INFO - threading running +2023-08-22,18:11:38.793 - INFO - threading running +2023-08-22,18:11:38.804 - INFO - threading running +2023-08-22,18:11:38.814 - INFO - threading running +2023-08-22,18:11:38.823 - INFO - threading running +2023-08-22,18:11:38.833 - INFO - threading running +2023-08-22,18:11:38.843 - INFO - threading running +2023-08-22,18:11:38.854 - INFO - threading running +2023-08-22,18:11:38.863 - INFO - threading running +2023-08-22,18:11:38.873 - INFO - threading running +2023-08-22,18:11:38.883 - INFO - threading running +2023-08-22,18:11:38.894 - INFO - threading running +2023-08-22,18:11:38.904 - INFO - threading running +2023-08-22,18:11:38.914 - INFO - threading running +2023-08-22,18:11:38.924 - INFO - threading running +2023-08-22,18:11:38.934 - INFO - threading running +2023-08-22,18:11:38.944 - INFO - threading running +2023-08-22,18:11:38.954 - INFO - threading running +2023-08-22,18:11:38.965 - INFO - threading running +2023-08-22,18:11:38.975 - INFO - threading running +2023-08-22,18:11:38.985 - INFO - threading running +2023-08-22,18:11:38.993 - INFO - ---------------------------------------------------- +2023-08-22,18:11:38.993 - INFO - 107th iteration +2023-08-22,18:11:38.993 - INFO - average ll reward: 0.1288367951 +2023-08-22,18:11:38.993 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:38.995 - INFO - updating finished +2023-08-22,18:11:43.060 - INFO - threading running +2023-08-22,18:11:43.073 - INFO - threading running +2023-08-22,18:11:43.084 - INFO - threading running +2023-08-22,18:11:43.093 - INFO - threading running +2023-08-22,18:11:43.103 - INFO - threading running +2023-08-22,18:11:43.113 - INFO - threading running +2023-08-22,18:11:43.123 - INFO - threading running +2023-08-22,18:11:43.133 - INFO - threading running +2023-08-22,18:11:43.144 - INFO - threading running +2023-08-22,18:11:43.154 - INFO - threading running +2023-08-22,18:11:43.164 - INFO - threading running +2023-08-22,18:11:43.174 - INFO - threading running +2023-08-22,18:11:43.184 - INFO - threading running +2023-08-22,18:11:43.194 - INFO - threading running +2023-08-22,18:11:43.205 - INFO - threading running +2023-08-22,18:11:43.214 - INFO - threading running +2023-08-22,18:11:43.224 - INFO - threading running +2023-08-22,18:11:43.235 - INFO - threading running +2023-08-22,18:11:43.245 - INFO - threading running +2023-08-22,18:11:43.255 - INFO - threading running +2023-08-22,18:11:43.265 - INFO - threading running +2023-08-22,18:11:43.275 - INFO - threading running +2023-08-22,18:11:43.286 - INFO - threading running +2023-08-22,18:11:43.296 - INFO - threading running +2023-08-22,18:11:43.305 - INFO - threading running +2023-08-22,18:11:43.315 - INFO - threading running +2023-08-22,18:11:43.325 - INFO - threading running +2023-08-22,18:11:43.335 - INFO - threading running +2023-08-22,18:11:43.345 - INFO - threading running +2023-08-22,18:11:43.356 - INFO - threading running +2023-08-22,18:11:43.366 - INFO - threading running +2023-08-22,18:11:43.376 - INFO - threading running +2023-08-22,18:11:43.387 - INFO - threading running +2023-08-22,18:11:43.396 - INFO - threading running +2023-08-22,18:11:43.406 - INFO - threading running +2023-08-22,18:11:43.416 - INFO - threading running +2023-08-22,18:11:43.427 - INFO - threading running +2023-08-22,18:11:43.437 - INFO - threading running +2023-08-22,18:11:43.446 - INFO - threading running +2023-08-22,18:11:43.456 - INFO - threading running +2023-08-22,18:11:43.466 - INFO - threading running +2023-08-22,18:11:43.476 - INFO - threading running +2023-08-22,18:11:43.486 - INFO - threading running +2023-08-22,18:11:43.496 - INFO - threading running +2023-08-22,18:11:43.506 - INFO - threading running +2023-08-22,18:11:43.517 - INFO - threading running +2023-08-22,18:11:43.526 - INFO - threading running +2023-08-22,18:11:43.536 - INFO - threading running +2023-08-22,18:11:43.547 - INFO - threading running +2023-08-22,18:11:43.557 - INFO - threading running +2023-08-22,18:11:43.567 - INFO - threading running +2023-08-22,18:11:43.577 - INFO - threading running +2023-08-22,18:11:43.588 - INFO - threading running +2023-08-22,18:11:43.598 - INFO - threading running +2023-08-22,18:11:43.605 - INFO - ---------------------------------------------------- +2023-08-22,18:11:43.605 - INFO - 108th iteration +2023-08-22,18:11:43.605 - INFO - average ll reward: 0.0786761581 +2023-08-22,18:11:43.605 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:43.607 - INFO - updating finished +2023-08-22,18:11:47.654 - INFO - threading running +2023-08-22,18:11:47.669 - INFO - threading running +2023-08-22,18:11:47.680 - INFO - threading running +2023-08-22,18:11:47.689 - INFO - threading running +2023-08-22,18:11:47.699 - INFO - threading running +2023-08-22,18:11:47.709 - INFO - threading running +2023-08-22,18:11:47.719 - INFO - threading running +2023-08-22,18:11:47.729 - INFO - threading running +2023-08-22,18:11:47.739 - INFO - threading running +2023-08-22,18:11:47.749 - INFO - threading running +2023-08-22,18:11:47.760 - INFO - threading running +2023-08-22,18:11:47.770 - INFO - threading running +2023-08-22,18:11:47.780 - INFO - threading running +2023-08-22,18:11:47.790 - INFO - threading running +2023-08-22,18:11:47.801 - INFO - threading running +2023-08-22,18:11:47.811 - INFO - threading running +2023-08-22,18:11:47.820 - INFO - threading running +2023-08-22,18:11:47.830 - INFO - threading running +2023-08-22,18:11:47.840 - INFO - threading running +2023-08-22,18:11:47.851 - INFO - threading running +2023-08-22,18:11:47.861 - INFO - threading running +2023-08-22,18:11:47.872 - INFO - threading running +2023-08-22,18:11:47.882 - INFO - threading running +2023-08-22,18:11:47.892 - INFO - threading running +2023-08-22,18:11:47.902 - INFO - threading running +2023-08-22,18:11:47.913 - INFO - threading running +2023-08-22,18:11:47.922 - INFO - threading running +2023-08-22,18:11:47.933 - INFO - threading running +2023-08-22,18:11:47.944 - INFO - threading running +2023-08-22,18:11:47.953 - INFO - threading running +2023-08-22,18:11:47.963 - INFO - threading running +2023-08-22,18:11:47.973 - INFO - threading running +2023-08-22,18:11:47.983 - INFO - threading running +2023-08-22,18:11:47.993 - INFO - threading running +2023-08-22,18:11:48.003 - INFO - threading running +2023-08-22,18:11:48.013 - INFO - threading running +2023-08-22,18:11:48.023 - INFO - threading running +2023-08-22,18:11:48.033 - INFO - threading running +2023-08-22,18:11:48.044 - INFO - threading running +2023-08-22,18:11:48.055 - INFO - threading running +2023-08-22,18:11:48.065 - INFO - threading running +2023-08-22,18:11:48.075 - INFO - threading running +2023-08-22,18:11:48.085 - INFO - threading running +2023-08-22,18:11:48.095 - INFO - threading running +2023-08-22,18:11:48.106 - INFO - threading running +2023-08-22,18:11:48.115 - INFO - threading running +2023-08-22,18:11:48.125 - INFO - threading running +2023-08-22,18:11:48.135 - INFO - threading running +2023-08-22,18:11:48.145 - INFO - threading running +2023-08-22,18:11:48.155 - INFO - threading running +2023-08-22,18:11:48.166 - INFO - threading running +2023-08-22,18:11:48.175 - INFO - threading running +2023-08-22,18:11:48.186 - INFO - threading running +2023-08-22,18:11:48.193 - INFO - ---------------------------------------------------- +2023-08-22,18:11:48.193 - INFO - 109th iteration +2023-08-22,18:11:48.193 - INFO - average ll reward: 0.1057605067 +2023-08-22,18:11:48.193 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:48.196 - INFO - updating finished +2023-08-22,18:11:52.266 - INFO - threading running +2023-08-22,18:11:52.282 - INFO - threading running +2023-08-22,18:11:52.292 - INFO - threading running +2023-08-22,18:11:52.302 - INFO - threading running +2023-08-22,18:11:52.312 - INFO - threading running +2023-08-22,18:11:52.323 - INFO - threading running +2023-08-22,18:11:52.333 - INFO - threading running +2023-08-22,18:11:52.343 - INFO - threading running +2023-08-22,18:11:52.354 - INFO - threading running +2023-08-22,18:11:52.364 - INFO - threading running +2023-08-22,18:11:52.374 - INFO - threading running +2023-08-22,18:11:52.384 - INFO - threading running +2023-08-22,18:11:52.394 - INFO - threading running +2023-08-22,18:11:52.404 - INFO - threading running +2023-08-22,18:11:52.414 - INFO - threading running +2023-08-22,18:11:52.424 - INFO - threading running +2023-08-22,18:11:52.434 - INFO - threading running +2023-08-22,18:11:52.444 - INFO - threading running +2023-08-22,18:11:52.455 - INFO - threading running +2023-08-22,18:11:52.464 - INFO - threading running +2023-08-22,18:11:52.474 - INFO - threading running +2023-08-22,18:11:52.484 - INFO - threading running +2023-08-22,18:11:52.494 - INFO - threading running +2023-08-22,18:11:52.504 - INFO - threading running +2023-08-22,18:11:52.514 - INFO - threading running +2023-08-22,18:11:52.524 - INFO - threading running +2023-08-22,18:11:52.535 - INFO - threading running +2023-08-22,18:11:52.545 - INFO - threading running +2023-08-22,18:11:52.555 - INFO - threading running +2023-08-22,18:11:52.564 - INFO - threading running +2023-08-22,18:11:52.574 - INFO - threading running +2023-08-22,18:11:52.584 - INFO - threading running +2023-08-22,18:11:52.595 - INFO - threading running +2023-08-22,18:11:52.605 - INFO - threading running +2023-08-22,18:11:52.615 - INFO - threading running +2023-08-22,18:11:52.626 - INFO - threading running +2023-08-22,18:11:52.635 - INFO - threading running +2023-08-22,18:11:52.645 - INFO - threading running +2023-08-22,18:11:52.655 - INFO - threading running +2023-08-22,18:11:52.665 - INFO - threading running +2023-08-22,18:11:52.675 - INFO - threading running +2023-08-22,18:11:52.685 - INFO - threading running +2023-08-22,18:11:52.695 - INFO - threading running +2023-08-22,18:11:52.706 - INFO - threading running +2023-08-22,18:11:52.716 - INFO - threading running +2023-08-22,18:11:52.726 - INFO - threading running +2023-08-22,18:11:52.737 - INFO - threading running +2023-08-22,18:11:52.746 - INFO - threading running +2023-08-22,18:11:52.756 - INFO - threading running +2023-08-22,18:11:52.766 - INFO - threading running +2023-08-22,18:11:52.776 - INFO - threading running +2023-08-22,18:11:52.786 - INFO - threading running +2023-08-22,18:11:52.796 - INFO - threading running +2023-08-22,18:11:52.806 - INFO - threading running +2023-08-22,18:11:52.816 - INFO - threading running +2023-08-22,18:11:52.826 - INFO - threading running +2023-08-22,18:11:52.837 - INFO - threading running +2023-08-22,18:11:52.846 - INFO - threading running +2023-08-22,18:11:52.855 - INFO - ---------------------------------------------------- +2023-08-22,18:11:52.855 - INFO - 110th iteration +2023-08-22,18:11:52.856 - INFO - average ll reward: 0.1102505942 +2023-08-22,18:11:52.856 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:52.856 - INFO - updating finished +2023-08-22,18:11:56.997 - INFO - threading running +2023-08-22,18:11:57.012 - INFO - threading running +2023-08-22,18:11:57.022 - INFO - threading running +2023-08-22,18:11:57.032 - INFO - threading running +2023-08-22,18:11:57.042 - INFO - threading running +2023-08-22,18:11:57.052 - INFO - threading running +2023-08-22,18:11:57.062 - INFO - threading running +2023-08-22,18:11:57.073 - INFO - threading running +2023-08-22,18:11:57.084 - INFO - threading running +2023-08-22,18:11:57.093 - INFO - threading running +2023-08-22,18:11:57.103 - INFO - threading running +2023-08-22,18:11:57.113 - INFO - threading running +2023-08-22,18:11:57.123 - INFO - threading running +2023-08-22,18:11:57.133 - INFO - threading running +2023-08-22,18:11:57.143 - INFO - threading running +2023-08-22,18:11:57.153 - INFO - threading running +2023-08-22,18:11:57.163 - INFO - threading running +2023-08-22,18:11:57.174 - INFO - threading running +2023-08-22,18:11:57.184 - INFO - threading running +2023-08-22,18:11:57.195 - INFO - threading running +2023-08-22,18:11:57.205 - INFO - threading running +2023-08-22,18:11:57.216 - INFO - threading running +2023-08-22,18:11:57.225 - INFO - threading running +2023-08-22,18:11:57.235 - INFO - threading running +2023-08-22,18:11:57.246 - INFO - threading running +2023-08-22,18:11:57.256 - INFO - threading running +2023-08-22,18:11:57.266 - INFO - threading running +2023-08-22,18:11:57.276 - INFO - threading running +2023-08-22,18:11:57.287 - INFO - threading running +2023-08-22,18:11:57.298 - INFO - threading running +2023-08-22,18:11:57.307 - INFO - threading running +2023-08-22,18:11:57.317 - INFO - threading running +2023-08-22,18:11:57.328 - INFO - threading running +2023-08-22,18:11:57.337 - INFO - threading running +2023-08-22,18:11:57.347 - INFO - threading running +2023-08-22,18:11:57.357 - INFO - threading running +2023-08-22,18:11:57.367 - INFO - threading running +2023-08-22,18:11:57.377 - INFO - threading running +2023-08-22,18:11:57.387 - INFO - threading running +2023-08-22,18:11:57.398 - INFO - threading running +2023-08-22,18:11:57.408 - INFO - threading running +2023-08-22,18:11:57.418 - INFO - threading running +2023-08-22,18:11:57.428 - INFO - threading running +2023-08-22,18:11:57.438 - INFO - threading running +2023-08-22,18:11:57.448 - INFO - threading running +2023-08-22,18:11:57.458 - INFO - threading running +2023-08-22,18:11:57.468 - INFO - threading running +2023-08-22,18:11:57.478 - INFO - threading running +2023-08-22,18:11:57.488 - INFO - threading running +2023-08-22,18:11:57.498 - INFO - threading running +2023-08-22,18:11:57.509 - INFO - threading running +2023-08-22,18:11:57.519 - INFO - threading running +2023-08-22,18:11:57.529 - INFO - threading running +2023-08-22,18:11:57.539 - INFO - threading running +2023-08-22,18:11:57.549 - INFO - threading running +2023-08-22,18:11:57.559 - INFO - threading running +2023-08-22,18:11:57.569 - INFO - threading running +2023-08-22,18:11:57.580 - INFO - threading running +2023-08-22,18:11:57.589 - INFO - ---------------------------------------------------- +2023-08-22,18:11:57.589 - INFO - 111th iteration +2023-08-22,18:11:57.589 - INFO - average ll reward: 0.0891956440 +2023-08-22,18:11:57.589 - INFO - ---------------------------------------------------- + +2023-08-22,18:11:57.590 - INFO - updating finished +2023-08-22,18:12:01.710 - INFO - threading running +2023-08-22,18:12:01.725 - INFO - threading running +2023-08-22,18:12:01.735 - INFO - threading running +2023-08-22,18:12:01.745 - INFO - threading running +2023-08-22,18:12:01.755 - INFO - threading running +2023-08-22,18:12:01.765 - INFO - threading running +2023-08-22,18:12:01.775 - INFO - threading running +2023-08-22,18:12:01.786 - INFO - threading running +2023-08-22,18:12:01.797 - INFO - threading running +2023-08-22,18:12:01.807 - INFO - threading running +2023-08-22,18:12:01.817 - INFO - threading running +2023-08-22,18:12:01.827 - INFO - threading running +2023-08-22,18:12:01.838 - INFO - threading running +2023-08-22,18:12:01.848 - INFO - threading running +2023-08-22,18:12:01.858 - INFO - threading running +2023-08-22,18:12:01.868 - INFO - threading running +2023-08-22,18:12:01.879 - INFO - threading running +2023-08-22,18:12:01.888 - INFO - threading running +2023-08-22,18:12:01.898 - INFO - threading running +2023-08-22,18:12:01.908 - INFO - threading running +2023-08-22,18:12:01.918 - INFO - threading running +2023-08-22,18:12:01.928 - INFO - threading running +2023-08-22,18:12:01.939 - INFO - threading running +2023-08-22,18:12:01.948 - INFO - threading running +2023-08-22,18:12:01.958 - INFO - threading running +2023-08-22,18:12:01.969 - INFO - threading running +2023-08-22,18:12:01.979 - INFO - threading running +2023-08-22,18:12:01.988 - INFO - threading running +2023-08-22,18:12:01.998 - INFO - threading running +2023-08-22,18:12:02.008 - INFO - threading running +2023-08-22,18:12:02.018 - INFO - threading running +2023-08-22,18:12:02.028 - INFO - threading running +2023-08-22,18:12:02.038 - INFO - threading running +2023-08-22,18:12:02.048 - INFO - threading running +2023-08-22,18:12:02.058 - INFO - threading running +2023-08-22,18:12:02.069 - INFO - threading running +2023-08-22,18:12:02.079 - INFO - threading running +2023-08-22,18:12:02.089 - INFO - threading running +2023-08-22,18:12:02.099 - INFO - threading running +2023-08-22,18:12:02.109 - INFO - threading running +2023-08-22,18:12:02.119 - INFO - threading running +2023-08-22,18:12:02.129 - INFO - threading running +2023-08-22,18:12:02.139 - INFO - threading running +2023-08-22,18:12:02.150 - INFO - threading running +2023-08-22,18:12:02.160 - INFO - threading running +2023-08-22,18:12:02.170 - INFO - threading running +2023-08-22,18:12:02.180 - INFO - threading running +2023-08-22,18:12:02.190 - INFO - threading running +2023-08-22,18:12:02.201 - INFO - threading running +2023-08-22,18:12:02.211 - INFO - threading running +2023-08-22,18:12:02.221 - INFO - threading running +2023-08-22,18:12:02.231 - INFO - threading running +2023-08-22,18:12:02.241 - INFO - threading running +2023-08-22,18:12:02.251 - INFO - threading running +2023-08-22,18:12:02.261 - INFO - threading running +2023-08-22,18:12:02.271 - INFO - threading running +2023-08-22,18:12:02.281 - INFO - threading running +2023-08-22,18:12:02.291 - INFO - threading running +2023-08-22,18:12:02.301 - INFO - threading running +2023-08-22,18:12:02.311 - INFO - threading running +2023-08-22,18:12:02.321 - INFO - threading running +2023-08-22,18:12:02.331 - INFO - threading running +2023-08-22,18:12:02.337 - INFO - ---------------------------------------------------- +2023-08-22,18:12:02.337 - INFO - 112th iteration +2023-08-22,18:12:02.337 - INFO - average ll reward: 0.0851023651 +2023-08-22,18:12:02.337 - INFO - ---------------------------------------------------- + +2023-08-22,18:12:02.341 - INFO - updating finished +2023-08-22,18:12:06.444 - INFO - threading running +2023-08-22,18:12:06.456 - INFO - threading running +2023-08-22,18:12:06.467 - INFO - threading running +2023-08-22,18:12:06.477 - INFO - threading running +2023-08-22,18:12:06.487 - INFO - threading running +2023-08-22,18:12:06.497 - INFO - threading running +2023-08-22,18:12:06.507 - INFO - threading running +2023-08-22,18:12:06.518 - INFO - threading running +2023-08-22,18:12:06.527 - INFO - threading running +2023-08-22,18:12:06.537 - INFO - threading running +2023-08-22,18:12:06.547 - INFO - threading running +2023-08-22,18:12:06.557 - INFO - threading running +2023-08-22,18:12:06.567 - INFO - threading running +2023-08-22,18:12:06.578 - INFO - threading running +2023-08-22,18:12:06.587 - INFO - threading running +2023-08-22,18:12:06.598 - INFO - threading running +2023-08-22,18:12:06.608 - INFO - threading running +2023-08-22,18:12:06.618 - INFO - threading running +2023-08-22,18:12:06.628 - INFO - threading running +2023-08-22,18:12:06.639 - INFO - threading running +2023-08-22,18:12:06.649 - INFO - threading running +2023-08-22,18:12:06.660 - INFO - threading running +2023-08-22,18:12:06.670 - INFO - threading running +2023-08-22,18:12:06.679 - INFO - threading running +2023-08-22,18:12:06.689 - INFO - threading running +2023-08-22,18:12:06.700 - INFO - threading running +2023-08-22,18:12:06.709 - INFO - threading running +2023-08-22,18:12:06.719 - INFO - threading running +2023-08-22,18:12:06.729 - INFO - threading running +2023-08-22,18:12:06.739 - INFO - threading running +2023-08-22,18:12:06.749 - INFO - threading running +2023-08-22,18:12:06.759 - INFO - threading running +2023-08-22,18:12:06.769 - INFO - threading running +2023-08-22,18:12:06.780 - INFO - threading running +2023-08-22,18:12:06.789 - INFO - threading running +2023-08-22,18:12:06.799 - INFO - threading running +2023-08-22,18:12:06.809 - INFO - threading running +2023-08-22,18:12:06.820 - INFO - threading running +2023-08-22,18:12:06.831 - INFO - threading running +2023-08-22,18:12:06.841 - INFO - threading running +2023-08-22,18:12:06.851 - INFO - threading running +2023-08-22,18:12:06.861 - INFO - threading running +2023-08-22,18:12:06.871 - INFO - threading running +2023-08-22,18:12:06.881 - INFO - threading running +2023-08-22,18:12:06.891 - INFO - threading running +2023-08-22,18:12:06.901 - INFO - threading running +2023-08-22,18:12:06.911 - INFO - threading running +2023-08-22,18:12:06.922 - INFO - threading running +2023-08-22,18:12:06.932 - INFO - threading running +2023-08-22,18:12:06.942 - INFO - threading running +2023-08-22,18:12:06.953 - INFO - threading running +2023-08-22,18:12:06.962 - INFO - threading running +2023-08-22,18:12:06.973 - INFO - threading running +2023-08-22,18:12:06.982 - INFO - threading running +2023-08-22,18:12:06.992 - INFO - threading running +2023-08-22,18:12:07.002 - INFO - threading running +2023-08-22,18:12:07.012 - INFO - threading running +2023-08-22,18:12:07.022 - INFO - threading running +2023-08-22,18:12:07.032 - INFO - threading running +2023-08-22,18:12:07.042 - INFO - threading running +2023-08-22,18:12:07.045 - INFO - ---------------------------------------------------- +2023-08-22,18:12:07.045 - INFO - 113th iteration +2023-08-22,18:12:07.045 - INFO - average ll reward: 0.0905751605 +2023-08-22,18:12:07.045 - INFO - ---------------------------------------------------- + +2023-08-22,18:12:07.052 - INFO - updating finished +2023-08-22,18:12:11.121 - INFO - threading running +2023-08-22,18:12:11.128 - INFO - threading running +2023-08-22,18:12:11.138 - INFO - threading running +2023-08-22,18:12:11.149 - INFO - threading running +2023-08-22,18:12:11.158 - INFO - threading running +2023-08-22,18:12:11.168 - INFO - threading running +2023-08-22,18:12:11.178 - INFO - threading running +2023-08-22,18:12:11.188 - INFO - threading running +2023-08-22,18:12:11.198 - INFO - threading running +2023-08-22,18:12:11.208 - INFO - threading running +2023-08-22,18:12:11.218 - INFO - threading running +2023-08-22,18:12:11.229 - INFO - threading running +2023-08-22,18:12:11.238 - INFO - threading running +2023-08-22,18:12:11.248 - INFO - threading running +2023-08-22,18:12:11.258 - INFO - threading running +2023-08-22,18:12:11.269 - INFO - threading running +2023-08-22,18:12:11.278 - INFO - threading running +2023-08-22,18:12:11.288 - INFO - threading running +2023-08-22,18:12:11.298 - INFO - threading running +2023-08-22,18:12:11.308 - INFO - threading running +2023-08-22,18:12:11.318 - INFO - threading running +2023-08-22,18:12:11.329 - INFO - threading running +2023-08-22,18:12:11.339 - INFO - threading running +2023-08-22,18:12:11.350 - INFO - threading running +2023-08-22,18:12:11.361 - INFO - threading running +2023-08-22,18:12:11.371 - INFO - threading running +2023-08-22,18:12:11.381 - INFO - threading running +2023-08-22,18:12:11.390 - INFO - threading running +2023-08-22,18:12:11.401 - INFO - threading running +2023-08-22,18:12:11.411 - INFO - threading running +2023-08-22,18:12:11.422 - INFO - threading running +2023-08-22,18:12:11.432 - INFO - threading running +2023-08-22,18:12:11.442 - INFO - threading running +2023-08-22,18:12:11.451 - INFO - threading running +2023-08-22,18:12:11.462 - INFO - threading running +2023-08-22,18:12:11.471 - INFO - threading running +2023-08-22,18:12:11.482 - INFO - threading running +2023-08-22,18:12:11.493 - INFO - threading running +2023-08-22,18:12:11.503 - INFO - threading running +2023-08-22,18:12:11.513 - INFO - threading running +2023-08-22,18:12:11.523 - INFO - threading running +2023-08-22,18:12:11.534 - INFO - threading running +2023-08-22,18:12:11.544 - INFO - threading running +2023-08-22,18:12:11.555 - INFO - threading running +2023-08-22,18:12:11.564 - INFO - threading running +2023-08-22,18:12:11.574 - INFO - threading running +2023-08-22,18:12:11.585 - INFO - threading running +2023-08-22,18:12:11.595 - INFO - threading running +2023-08-22,18:12:11.605 - INFO - threading running +2023-08-22,18:12:11.615 - INFO - threading running +2023-08-22,18:12:11.625 - INFO - threading running +2023-08-22,18:12:11.635 - INFO - threading running +2023-08-22,18:12:11.645 - INFO - threading running +2023-08-22,18:12:11.655 - INFO - threading running +2023-08-22,18:12:11.665 - INFO - threading running +2023-08-22,18:12:11.675 - INFO - threading running +2023-08-22,18:12:11.686 - INFO - threading running +2023-08-22,18:12:11.695 - INFO - threading running +2023-08-22,18:12:11.705 - INFO - threading running +2023-08-22,18:12:11.715 - INFO - threading running +2023-08-22,18:12:11.725 - INFO - threading running +2023-08-22,18:12:11.735 - INFO - threading running +2023-08-22,18:12:11.745 - INFO - threading running +2023-08-22,18:12:11.753 - INFO - ---------------------------------------------------- +2023-08-22,18:12:11.754 - INFO - 114th iteration +2023-08-22,18:12:11.754 - INFO - average ll reward: 0.0805989603 +2023-08-22,18:12:11.754 - INFO - ---------------------------------------------------- + +2023-08-22,18:12:11.755 - INFO - updating finished +2023-08-22,18:12:15.818 - INFO - threading running +2023-08-22,18:12:15.832 - INFO - threading running +2023-08-22,18:12:15.843 - INFO - threading running +2023-08-22,18:12:15.853 - INFO - threading running +2023-08-22,18:12:15.864 - INFO - threading running +2023-08-22,18:12:15.875 - INFO - threading running +2023-08-22,18:12:15.885 - INFO - threading running +2023-08-22,18:12:15.895 - INFO - threading running +2023-08-22,18:12:15.905 - INFO - threading running +2023-08-22,18:12:15.915 - INFO - threading running +2023-08-22,18:12:15.925 - INFO - threading running +2023-08-22,18:12:15.936 - INFO - threading running +2023-08-22,18:12:15.945 - INFO - threading running +2023-08-22,18:12:15.955 - INFO - threading running +2023-08-22,18:12:15.966 - INFO - threading running +2023-08-22,18:12:15.976 - INFO - threading running +2023-08-22,18:12:15.987 - INFO - threading running +2023-08-22,18:12:15.997 - INFO - threading running +2023-08-22,18:12:16.007 - INFO - threading running +2023-08-22,18:12:16.017 - INFO - threading running +2023-08-22,18:12:16.027 - INFO - threading running +2023-08-22,18:12:16.037 - INFO - threading running +2023-08-22,18:12:16.047 - INFO - threading running +2023-08-22,18:12:16.057 - INFO - threading running +2023-08-22,18:12:16.068 - INFO - threading running +2023-08-22,18:12:16.077 - INFO - threading running +2023-08-22,18:12:16.087 - INFO - threading running +2023-08-22,18:12:16.097 - INFO - threading running +2023-08-22,18:12:16.107 - INFO - threading running +2023-08-22,18:12:16.117 - INFO - threading running +2023-08-22,18:12:16.127 - INFO - threading running +2023-08-22,18:12:16.137 - INFO - threading running +2023-08-22,18:12:16.147 - INFO - threading running +2023-08-22,18:12:16.158 - INFO - threading running +2023-08-22,18:12:16.168 - INFO - threading running +2023-08-22,18:12:16.178 - INFO - threading running +2023-08-22,18:12:16.188 - INFO - threading running +2023-08-22,18:12:16.198 - INFO - threading running +2023-08-22,18:12:16.209 - INFO - threading running +2023-08-22,18:12:16.218 - INFO - threading running +2023-08-22,18:12:16.228 - INFO - threading running +2023-08-22,18:12:16.238 - INFO - threading running +2023-08-22,18:12:16.248 - INFO - threading running +2023-08-22,18:12:16.258 - INFO - threading running +2023-08-22,18:12:16.269 - INFO - threading running +2023-08-22,18:12:16.278 - INFO - threading running +2023-08-22,18:12:16.288 - INFO - threading running +2023-08-22,18:12:16.298 - INFO - threading running +2023-08-22,18:12:16.308 - INFO - threading running +2023-08-22,18:12:16.318 - INFO - threading running +2023-08-22,18:12:16.328 - INFO - threading running +2023-08-22,18:12:16.339 - INFO - threading running +2023-08-22,18:12:16.348 - INFO - threading running +2023-08-22,18:12:16.359 - INFO - threading running +2023-08-22,18:12:16.370 - INFO - threading running +2023-08-22,18:12:16.381 - INFO - threading running +2023-08-22,18:12:16.392 - INFO - threading running +2023-08-22,18:12:16.401 - INFO - ---------------------------------------------------- +2023-08-22,18:12:16.402 - INFO - threading running +2023-08-22,18:12:16.402 - INFO - 115th iteration +2023-08-22,18:12:16.403 - INFO - average ll reward: 0.0750169766 +2023-08-22,18:12:16.403 - INFO - ---------------------------------------------------- + +2023-08-22,18:12:16.412 - INFO - updating finished +2023-08-22,18:12:20.469 - INFO - threading running +2023-08-22,18:12:20.477 - INFO - threading running +2023-08-22,18:12:20.488 - INFO - threading running +2023-08-22,18:12:20.497 - INFO - threading running +2023-08-22,18:12:20.507 - INFO - threading running +2023-08-22,18:12:20.517 - INFO - threading running +2023-08-22,18:12:20.527 - INFO - threading running +2023-08-22,18:12:20.537 - INFO - threading running +2023-08-22,18:12:20.547 - INFO - threading running +2023-08-22,18:12:20.557 - INFO - threading running +2023-08-22,18:12:20.567 - INFO - threading running +2023-08-22,18:12:20.577 - INFO - threading running +2023-08-22,18:12:20.587 - INFO - threading running +2023-08-22,18:12:20.598 - INFO - threading running +2023-08-22,18:12:20.608 - INFO - threading running +2023-08-22,18:12:20.617 - INFO - threading running +2023-08-22,18:12:20.627 - INFO - threading running +2023-08-22,18:12:20.637 - INFO - threading running +2023-08-22,18:12:20.647 - INFO - threading running +2023-08-22,18:12:20.658 - INFO - threading running +2023-08-22,18:12:20.667 - INFO - threading running +2023-08-22,18:12:20.677 - INFO - threading running +2023-08-22,18:12:20.688 - INFO - threading running +2023-08-22,18:12:20.699 - INFO - threading running +2023-08-22,18:12:20.710 - INFO - threading running +2023-08-22,18:12:20.720 - INFO - threading running +2023-08-22,18:12:20.730 - INFO - threading running +2023-08-22,18:12:20.740 - INFO - threading running +2023-08-22,18:12:20.751 - INFO - threading running +2023-08-22,18:12:20.761 - INFO - threading running +2023-08-22,18:12:20.772 - INFO - threading running +2023-08-22,18:12:20.783 - INFO - threading running +2023-08-22,18:12:20.792 - INFO - threading running +2023-08-22,18:12:20.802 - INFO - threading running +2023-08-22,18:12:20.812 - INFO - threading running +2023-08-22,18:12:20.823 - INFO - threading running +2023-08-22,18:12:20.834 - INFO - threading running +2023-08-22,18:12:20.843 - INFO - threading running +2023-08-22,18:12:20.853 - INFO - threading running +2023-08-22,18:12:20.863 - INFO - threading running +2023-08-22,18:12:20.873 - INFO - threading running +2023-08-22,18:12:20.883 - INFO - threading running +2023-08-22,18:12:20.893 - INFO - threading running +2023-08-22,18:12:20.903 - INFO - threading running +2023-08-22,18:12:20.913 - INFO - threading running +2023-08-22,18:12:20.923 - INFO - threading running +2023-08-22,18:12:20.933 - INFO - threading running +2023-08-22,18:12:20.943 - INFO - threading running +2023-08-22,18:12:20.953 - INFO - threading running +2023-08-22,18:12:20.963 - INFO - threading running +2023-08-22,18:12:20.973 - INFO - threading running +2023-08-22,18:12:20.983 - INFO - threading running +2023-08-22,18:12:20.994 - INFO - threading running +2023-08-22,18:12:21.003 - INFO - threading running +2023-08-22,18:12:21.013 - INFO - threading running +2023-08-22,18:12:21.023 - INFO - threading running +2023-08-22,18:12:21.033 - INFO - threading running +2023-08-22,18:12:21.043 - INFO - threading running +2023-08-22,18:12:21.054 - INFO - threading running +2023-08-22,18:12:21.064 - INFO - threading running +2023-08-22,18:12:21.068 - INFO - ---------------------------------------------------- +2023-08-22,18:12:21.068 - INFO - 116th iteration +2023-08-22,18:12:21.068 - INFO - average ll reward: 0.0974541077 +2023-08-22,18:12:21.068 - INFO - ---------------------------------------------------- + +2023-08-22,18:12:21.074 - INFO - updating finished +2023-08-22,18:12:25.221 - INFO - threading running +2023-08-22,18:12:25.237 - INFO - threading running +2023-08-22,18:12:25.247 - INFO - threading running +2023-08-22,18:12:25.257 - INFO - threading running +2023-08-22,18:12:25.267 - INFO - threading running +2023-08-22,18:12:25.278 - INFO - threading running +2023-08-22,18:12:25.287 - INFO - threading running +2023-08-22,18:12:25.297 - INFO - threading running +2023-08-22,18:12:25.307 - INFO - threading running +2023-08-22,18:12:25.317 - INFO - threading running +2023-08-22,18:12:25.327 - INFO - threading running +2023-08-22,18:12:25.337 - INFO - threading running +2023-08-22,18:12:25.347 - INFO - threading running +2023-08-22,18:12:25.357 - INFO - threading running +2023-08-22,18:12:25.368 - INFO - threading running +2023-08-22,18:12:25.378 - INFO - threading running +2023-08-22,18:12:25.388 - INFO - threading running +2023-08-22,18:12:25.397 - INFO - threading running +2023-08-22,18:12:25.407 - INFO - threading running +2023-08-22,18:12:25.418 - INFO - threading running +2023-08-22,18:12:25.427 - INFO - threading running +2023-08-22,18:12:25.437 - INFO - threading running +2023-08-22,18:12:25.447 - INFO - threading running +2023-08-22,18:12:25.457 - INFO - threading running +2023-08-22,18:12:25.467 - INFO - threading running +2023-08-22,18:12:25.478 - INFO - threading running +2023-08-22,18:12:25.489 - INFO - threading running +2023-08-22,18:12:25.499 - INFO - threading running +2023-08-22,18:12:25.509 - INFO - threading running +2023-08-22,18:12:25.520 - INFO - threading running +2023-08-22,18:12:25.530 - INFO - threading running +2023-08-22,18:12:25.540 - INFO - threading running +2023-08-22,18:12:25.550 - INFO - threading running +2023-08-22,18:12:25.560 - INFO - threading running +2023-08-22,18:12:25.570 - INFO - threading running +2023-08-22,18:12:25.581 - INFO - threading running +2023-08-22,18:12:25.590 - INFO - threading running +2023-08-22,18:12:25.600 - INFO - threading running +2023-08-22,18:12:25.610 - INFO - threading running +2023-08-22,18:12:25.620 - INFO - threading running +2023-08-22,18:12:25.630 - INFO - threading running +2023-08-22,18:12:25.640 - INFO - threading running +2023-08-22,18:12:25.651 - INFO - threading running +2023-08-22,18:12:25.660 - INFO - threading running +2023-08-22,18:12:25.670 - INFO - threading running +2023-08-22,18:12:25.680 - INFO - threading running +2023-08-22,18:12:25.690 - INFO - threading running +2023-08-22,18:12:25.701 - INFO - threading running +2023-08-22,18:12:25.712 - INFO - threading running +2023-08-22,18:12:25.721 - INFO - threading running +2023-08-22,18:12:25.731 - INFO - threading running +2023-08-22,18:12:25.741 - INFO - threading running +2023-08-22,18:12:25.751 - INFO - threading running +2023-08-22,18:12:25.762 - INFO - threading running +2023-08-22,18:12:25.771 - INFO - threading running +2023-08-22,18:12:25.781 - INFO - threading running +2023-08-22,18:12:25.791 - INFO - threading running +2023-08-22,18:12:25.801 - INFO - threading running +2023-08-22,18:12:25.808 - INFO - ---------------------------------------------------- +2023-08-22,18:12:25.808 - INFO - 117th iteration +2023-08-22,18:12:25.808 - INFO - average ll reward: 0.0871609890 +2023-08-22,18:12:25.808 - INFO - ---------------------------------------------------- + +2023-08-22,18:12:25.812 - INFO - updating finished +2023-08-22,18:12:29.932 - INFO - threading running +2023-08-22,18:12:29.939 - INFO - threading running +2023-08-22,18:12:29.949 - INFO - threading running +2023-08-22,18:12:29.959 - INFO - threading running +2023-08-22,18:12:29.969 - INFO - threading running +2023-08-22,18:12:29.979 - INFO - threading running +2023-08-22,18:12:29.989 - INFO - threading running +2023-08-22,18:12:30.000 - INFO - threading running +2023-08-22,18:12:30.010 - INFO - threading running +2023-08-22,18:12:30.021 - INFO - threading running +2023-08-22,18:12:30.032 - INFO - threading running +2023-08-22,18:12:30.042 - INFO - threading running +2023-08-22,18:12:30.052 - INFO - threading running +2023-08-22,18:12:30.062 - INFO - threading running +2023-08-22,18:12:30.072 - INFO - threading running +2023-08-22,18:12:30.082 - INFO - threading running +2023-08-22,18:12:30.092 - INFO - threading running +2023-08-22,18:12:30.102 - INFO - threading running +2023-08-22,18:12:30.112 - INFO - threading running +2023-08-22,18:12:30.122 - INFO - threading running +2023-08-22,18:12:30.132 - INFO - threading running +2023-08-22,18:12:30.143 - INFO - threading running +2023-08-22,18:12:30.152 - INFO - threading running +2023-08-22,18:12:30.162 - INFO - threading running +2023-08-22,18:12:30.172 - INFO - threading running +2023-08-22,18:12:30.182 - INFO - threading running +2023-08-22,18:12:30.193 - INFO - threading running +2023-08-22,18:12:30.204 - INFO - threading running +2023-08-22,18:12:30.214 - INFO - threading running +2023-08-22,18:12:30.224 - INFO - threading running +2023-08-22,18:12:30.234 - INFO - threading running +2023-08-22,18:12:30.244 - INFO - threading running +2023-08-22,18:12:30.254 - INFO - threading running +2023-08-22,18:12:30.264 - INFO - threading running +2023-08-22,18:12:30.274 - INFO - threading running +2023-08-22,18:12:30.284 - INFO - threading running +2023-08-22,18:12:30.294 - INFO - threading running +2023-08-22,18:12:30.304 - INFO - threading running +2023-08-22,18:12:30.314 - INFO - threading running +2023-08-22,18:12:30.324 - INFO - threading running +2023-08-22,18:12:30.334 - INFO - threading running +2023-08-22,18:12:30.344 - INFO - threading running +2023-08-22,18:12:30.354 - INFO - threading running +2023-08-22,18:12:30.364 - INFO - threading running +2023-08-22,18:12:30.374 - INFO - threading running +2023-08-22,18:12:30.385 - INFO - threading running +2023-08-22,18:12:30.396 - INFO - threading running +2023-08-22,18:12:30.406 - INFO - threading running +2023-08-22,18:12:30.415 - INFO - threading running +2023-08-22,18:12:30.425 - INFO - threading running +2023-08-22,18:12:30.436 - INFO - threading running +2023-08-22,18:12:30.446 - INFO - threading running +2023-08-22,18:12:30.456 - INFO - threading running +2023-08-22,18:12:30.467 - INFO - threading running +2023-08-22,18:12:30.478 - INFO - threading running +2023-08-22,18:12:30.487 - INFO - threading running +2023-08-22,18:12:30.497 - INFO - threading running +2023-08-22,18:12:30.507 - INFO - threading running +2023-08-22,18:12:30.518 - INFO - threading running +2023-08-22,18:12:30.522 - INFO - ---------------------------------------------------- +2023-08-22,18:12:30.522 - INFO - 118th iteration +2023-08-22,18:12:30.522 - INFO - average ll reward: 0.0889053590 +2023-08-22,18:12:30.522 - INFO - ---------------------------------------------------- + +2023-08-22,18:12:30.528 - INFO - updating finished +2023-08-22,18:12:34.604 - INFO - threading running +2023-08-22,18:12:34.619 - INFO - threading running +2023-08-22,18:12:34.629 - INFO - threading running +2023-08-22,18:12:34.639 - INFO - threading running +2023-08-22,18:12:34.650 - INFO - threading running +2023-08-22,18:12:34.659 - INFO - threading running +2023-08-22,18:12:34.669 - INFO - threading running +2023-08-22,18:12:34.679 - INFO - threading running +2023-08-22,18:12:34.690 - INFO - threading running +2023-08-22,18:12:34.701 - INFO - threading running +2023-08-22,18:12:34.712 - INFO - threading running +2023-08-22,18:12:34.721 - INFO - threading running +2023-08-22,18:12:34.731 - INFO - threading running +2023-08-22,18:12:34.741 - INFO - threading running +2023-08-22,18:12:34.751 - INFO - threading running +2023-08-22,18:12:34.761 - INFO - threading running +2023-08-22,18:12:34.771 - INFO - threading running +2023-08-22,18:12:34.782 - INFO - threading running +2023-08-22,18:12:34.791 - INFO - threading running +2023-08-22,18:12:34.801 - INFO - threading running +2023-08-22,18:12:34.811 - INFO - threading running +2023-08-22,18:12:34.821 - INFO - threading running +2023-08-22,18:12:34.832 - INFO - threading running +2023-08-22,18:12:34.841 - INFO - threading running +2023-08-22,18:12:34.851 - INFO - threading running +2023-08-22,18:12:34.861 - INFO - threading running +2023-08-22,18:12:34.871 - INFO - threading running +2023-08-22,18:12:34.882 - INFO - threading running +2023-08-22,18:12:34.891 - INFO - threading running +2023-08-22,18:12:34.901 - INFO - threading running +2023-08-22,18:12:34.911 - INFO - threading running +2023-08-22,18:12:34.921 - INFO - threading running +2023-08-22,18:12:34.931 - INFO - threading running +2023-08-22,18:12:34.941 - INFO - threading running +2023-08-22,18:12:34.952 - INFO - threading running +2023-08-22,18:12:34.961 - INFO - threading running +2023-08-22,18:12:34.971 - INFO - threading running +2023-08-22,18:12:34.981 - INFO - threading running +2023-08-22,18:12:34.991 - INFO - threading running +2023-08-22,18:12:35.001 - INFO - threading running +2023-08-22,18:12:35.012 - INFO - threading running +2023-08-22,18:12:35.022 - INFO - threading running +2023-08-22,18:12:35.033 - INFO - threading running +2023-08-22,18:12:35.043 - INFO - threading running +2023-08-22,18:12:35.054 - INFO - threading running +2023-08-22,18:12:35.064 - INFO - threading running +2023-08-22,18:12:35.074 - INFO - threading running +2023-08-22,18:12:35.084 - INFO - threading running +2023-08-22,18:12:35.094 - INFO - threading running +2023-08-22,18:12:35.104 - INFO - threading running +2023-08-22,18:12:35.114 - INFO - threading running +2023-08-22,18:12:35.125 - INFO - threading running +2023-08-22,18:12:35.135 - INFO - threading running +2023-08-22,18:12:35.145 - INFO - threading running +2023-08-22,18:12:35.155 - INFO - threading running +2023-08-22,18:12:35.165 - INFO - threading running +2023-08-22,18:12:35.175 - INFO - threading running +2023-08-22,18:12:35.177 - INFO - ---------------------------------------------------- +2023-08-22,18:12:35.177 - INFO - 119th iteration +2023-08-22,18:12:35.177 - INFO - average ll reward: 0.0859838732 +2023-08-22,18:12:35.177 - INFO - ---------------------------------------------------- + +2023-08-22,18:12:35.185 - INFO - updating finished +2023-08-22,18:12:39.255 - INFO - threading running +2023-08-22,18:12:39.266 - INFO - threading running +2023-08-22,18:12:39.277 - INFO - threading running +2023-08-22,18:12:39.286 - INFO - threading running +2023-08-22,18:12:39.296 - INFO - threading running +2023-08-22,18:12:39.307 - INFO - threading running +2023-08-22,18:12:39.316 - INFO - threading running +2023-08-22,18:12:39.327 - INFO - threading running +2023-08-22,18:12:39.336 - INFO - threading running +2023-08-22,18:12:39.346 - INFO - threading running +2023-08-22,18:12:39.356 - INFO - threading running +2023-08-22,18:12:39.367 - INFO - threading running +2023-08-22,18:12:39.378 - INFO - threading running +2023-08-22,18:12:39.387 - INFO - threading running +2023-08-22,18:12:39.397 - INFO - threading running +2023-08-22,18:12:39.408 - INFO - threading running +2023-08-22,18:12:39.418 - INFO - threading running +2023-08-22,18:12:39.428 - INFO - threading running +2023-08-22,18:12:39.438 - INFO - threading running +2023-08-22,18:12:39.448 - INFO - threading running +2023-08-22,18:12:39.458 - INFO - threading running +2023-08-22,18:12:39.468 - INFO - threading running +2023-08-22,18:12:39.479 - INFO - threading running +2023-08-22,18:12:39.489 - INFO - threading running +2023-08-22,18:12:39.499 - INFO - threading running +2023-08-22,18:12:39.509 - INFO - threading running +2023-08-22,18:12:39.519 - INFO - threading running +2023-08-22,18:12:39.529 - INFO - threading running +2023-08-22,18:12:39.539 - INFO - threading running +2023-08-22,18:12:39.549 - INFO - threading running +2023-08-22,18:12:39.559 - INFO - threading running +2023-08-22,18:12:39.569 - INFO - threading running +2023-08-22,18:12:39.580 - INFO - threading running +2023-08-22,18:12:39.590 - INFO - threading running +2023-08-22,18:12:39.600 - INFO - threading running +2023-08-22,18:12:39.611 - INFO - threading running +2023-08-22,18:12:39.620 - INFO - threading running +2023-08-22,18:12:39.630 - INFO - threading running +2023-08-22,18:12:39.640 - INFO - threading running +2023-08-22,18:12:39.650 - INFO - threading running +2023-08-22,18:12:39.661 - INFO - threading running +2023-08-22,18:12:39.672 - INFO - threading running +2023-08-22,18:12:39.682 - INFO - threading running +2023-08-22,18:12:39.693 - INFO - threading running +2023-08-22,18:12:39.702 - INFO - threading running +2023-08-22,18:12:39.712 - INFO - threading running +2023-08-22,18:12:39.722 - INFO - threading running +2023-08-22,18:12:39.733 - INFO - threading running +2023-08-22,18:12:39.742 - INFO - threading running +2023-08-22,18:12:39.752 - INFO - threading running +2023-08-22,18:12:39.763 - INFO - threading running +2023-08-22,18:12:39.773 - INFO - threading running +2023-08-22,18:12:39.783 - INFO - threading running +2023-08-22,18:12:39.793 - INFO - threading running +2023-08-22,18:12:39.803 - INFO - threading running +2023-08-22,18:12:39.814 - INFO - threading running +2023-08-22,18:12:39.823 - INFO - threading running +2023-08-22,18:12:39.833 - INFO - threading running +2023-08-22,18:12:39.854 - INFO - threading running +2023-08-22,18:12:39.867 - INFO - threading running +2023-08-22,18:12:39.880 - INFO - threading running +2023-08-22,18:12:39.894 - INFO - threading running +2023-08-22,18:12:39.922 - INFO - threading running +2023-08-22,18:12:39.944 - INFO - threading running +2023-08-22,18:12:39.958 - INFO - threading running +2023-08-22,18:12:39.971 - INFO - threading running +2023-08-22,18:12:39.982 - INFO - threading running +2023-08-22,18:12:39.998 - INFO - threading running +2023-08-22,18:12:40.010 - INFO - threading running +2023-08-22,18:12:40.020 - INFO - threading running +2023-08-22,18:12:40.034 - INFO - threading running +2023-08-22,18:12:40.056 - INFO - threading running +2023-08-22,18:12:40.072 - INFO - threading running +2023-08-22,18:12:40.119 - INFO - threading running +2023-08-22,18:12:40.170 - INFO - threading running +2023-08-22,18:12:40.191 - INFO - threading running +2023-08-22,18:12:40.228 - INFO - threading running +2023-08-22,18:12:40.278 - INFO - threading running +2023-08-22,18:12:40.297 - INFO - threading running +2023-08-22,18:12:40.335 - INFO - threading running +2023-08-22,18:12:40.381 - INFO - threading running +2023-08-22,18:12:40.401 - INFO - threading running +2023-08-22,18:12:40.438 - INFO - threading running +2023-08-22,18:12:40.489 - INFO - threading running +2023-08-22,18:12:40.509 - INFO - threading running +2023-08-22,18:12:40.546 - INFO - threading running +2023-08-22,18:12:40.595 - INFO - threading running +2023-08-22,18:12:40.614 - INFO - threading running +2023-08-22,18:12:40.651 - INFO - threading running +2023-08-22,18:12:40.665 - INFO - threading running +2023-08-22,18:12:40.707 - INFO - threading running +2023-08-22,18:12:40.727 - INFO - threading running +2023-08-22,18:12:40.762 - INFO - threading running +2023-08-22,18:12:40.808 - INFO - threading running +2023-08-22,18:12:40.828 - INFO - threading running +2023-08-22,18:12:40.865 - INFO - threading running +2023-08-22,18:12:40.914 - INFO - threading running +2023-08-22,18:12:40.934 - INFO - threading running +2023-08-22,18:12:40.969 - INFO - threading running +2023-08-22,18:12:40.984 - INFO - threading running +2023-08-22,18:12:41.024 - INFO - threading running +2023-08-22,18:12:41.034 - INFO - threading running +2023-08-22,18:12:41.047 - INFO - threading running +2023-08-22,18:12:41.082 - INFO - threading running +2023-08-22,18:12:41.129 - INFO - threading running +2023-08-22,18:12:41.148 - INFO - threading running +2023-08-22,18:12:41.187 - INFO - threading running +2023-08-22,18:12:41.235 - INFO - threading running +2023-08-22,18:12:41.254 - INFO - threading running +2023-08-22,18:12:41.294 - INFO - threading running +2023-08-22,18:12:41.349 - INFO - threading running +2023-08-22,18:12:41.369 - INFO - threading running +2023-08-22,18:12:41.405 - INFO - threading running +2023-08-22,18:12:41.455 - INFO - threading running +2023-08-22,18:12:41.475 - INFO - threading running +2023-08-22,18:12:41.520 - INFO - threading running +2023-08-22,18:12:41.567 - INFO - threading running +2023-08-22,18:12:41.580 - INFO - threading running +2023-08-22,18:12:41.595 - INFO - threading running +2023-08-22,18:12:41.631 - INFO - threading running +2023-08-22,18:12:41.677 - INFO - threading running +2023-08-22,18:12:41.697 - INFO - threading running +2023-08-22,18:12:41.742 - INFO - threading running +2023-08-22,18:12:41.787 - INFO - threading running +2023-08-22,18:12:41.806 - INFO - threading running +2023-08-22,18:12:41.816 - INFO - threading running +2023-08-22,18:12:41.826 - INFO - threading running +2023-08-22,18:12:41.836 - INFO - threading running +2023-08-22,18:12:41.839 - INFO - ---------------------------------------------------- +2023-08-22,18:12:41.839 - INFO - 120th iteration +2023-08-22,18:12:41.839 - INFO - average ll reward: 0.0809265303 +2023-08-22,18:12:41.839 - INFO - ---------------------------------------------------- + +2023-08-22,18:12:41.847 - INFO - updating finished +2023-08-22,18:12:45.910 - INFO - threading running +2023-08-22,18:12:45.925 - INFO - threading running +2023-08-22,18:12:45.936 - INFO - threading running +2023-08-22,18:12:45.945 - INFO - threading running +2023-08-22,18:12:45.955 - INFO - threading running +2023-08-22,18:12:45.965 - INFO - threading running +2023-08-22,18:12:45.975 - INFO - threading running +2023-08-22,18:12:45.986 - INFO - threading running +2023-08-22,18:12:45.996 - INFO - threading running +2023-08-22,18:12:46.005 - INFO - threading running +2023-08-22,18:12:46.016 - INFO - threading running +2023-08-22,18:12:46.026 - INFO - threading running +2023-08-22,18:12:46.035 - INFO - threading running +2023-08-22,18:12:46.046 - INFO - threading running +2023-08-22,18:12:46.056 - INFO - threading running +2023-08-22,18:12:46.066 - INFO - threading running +2023-08-22,18:12:46.076 - INFO - threading running +2023-08-22,18:12:46.086 - INFO - threading running +2023-08-22,18:12:46.096 - INFO - threading running +2023-08-22,18:12:46.106 - INFO - threading running +2023-08-22,18:12:46.116 - INFO - threading running +2023-08-22,18:12:46.127 - INFO - threading running +2023-08-22,18:12:46.137 - INFO - threading running +2023-08-22,18:12:46.148 - INFO - threading running +2023-08-22,18:12:46.159 - INFO - threading running +2023-08-22,18:12:46.168 - INFO - threading running +2023-08-22,18:12:46.178 - INFO - threading running +2023-08-22,18:12:46.188 - INFO - threading running +2023-08-22,18:12:46.198 - INFO - threading running +2023-08-22,18:12:46.208 - INFO - threading running +2023-08-22,18:12:46.218 - INFO - threading running +2023-08-22,18:12:46.228 - INFO - threading running +2023-08-22,18:12:46.239 - INFO - threading running +2023-08-22,18:12:46.248 - INFO - threading running +2023-08-22,18:12:46.259 - INFO - threading running +2023-08-22,18:12:46.268 - INFO - threading running +2023-08-22,18:12:46.278 - INFO - threading running +2023-08-22,18:12:46.288 - INFO - threading running +2023-08-22,18:12:46.298 - INFO - threading running +2023-08-22,18:12:46.308 - INFO - threading running +2023-08-22,18:12:46.319 - INFO - threading running +2023-08-22,18:12:46.328 - INFO - threading running +2023-08-22,18:12:46.338 - INFO - threading running +2023-08-22,18:12:46.349 - INFO - threading running +2023-08-22,18:12:46.359 - INFO - threading running +2023-08-22,18:12:46.368 - INFO - threading running +2023-08-22,18:12:46.379 - INFO - threading running +2023-08-22,18:12:46.389 - INFO - threading running +2023-08-22,18:12:46.399 - INFO - threading running +2023-08-22,18:12:46.409 - INFO - threading running +2023-08-22,18:12:46.420 - INFO - threading running +2023-08-22,18:12:46.429 - INFO - threading running +2023-08-22,18:12:46.439 - INFO - threading running +2023-08-22,18:12:46.449 - INFO - threading running +2023-08-22,18:12:46.460 - INFO - threading running +2023-08-22,18:12:46.469 - INFO - threading running +2023-08-22,18:12:46.479 - INFO - threading running +2023-08-22,18:12:46.482 - INFO - ---------------------------------------------------- +2023-08-22,18:12:46.483 - INFO - 121th iteration +2023-08-22,18:12:46.483 - INFO - average ll reward: 0.0871929481 +2023-08-22,18:12:46.483 - INFO - ---------------------------------------------------- + +2023-08-22,18:12:46.489 - INFO - updating finished +2023-08-22,18:12:50.617 - INFO - threading running +2023-08-22,18:12:50.631 - INFO - threading running +2023-08-22,18:12:50.641 - INFO - threading running +2023-08-22,18:12:50.652 - INFO - threading running +2023-08-22,18:12:50.663 - INFO - threading running +2023-08-22,18:12:50.672 - INFO - threading running +2023-08-22,18:12:50.682 - INFO - threading running +2023-08-22,18:12:50.692 - INFO - threading running +2023-08-22,18:12:50.702 - INFO - threading running +2023-08-22,18:12:50.712 - INFO - threading running +2023-08-22,18:12:50.722 - INFO - threading running +2023-08-22,18:12:50.732 - INFO - threading running +2023-08-22,18:12:50.743 - INFO - threading running +2023-08-22,18:12:50.752 - INFO - threading running +2023-08-22,18:12:50.762 - INFO - threading running +2023-08-22,18:12:50.772 - INFO - threading running +2023-08-22,18:12:50.782 - INFO - threading running +2023-08-22,18:12:50.793 - INFO - threading running +2023-08-22,18:12:50.803 - INFO - threading running +2023-08-22,18:12:50.813 - INFO - threading running +2023-08-22,18:12:50.823 - INFO - threading running +2023-08-22,18:12:50.833 - INFO - threading running +2023-08-22,18:12:50.843 - INFO - threading running +2023-08-22,18:12:50.853 - INFO - threading running +2023-08-22,18:12:50.863 - INFO - threading running +2023-08-22,18:12:50.874 - INFO - threading running +2023-08-22,18:12:50.884 - INFO - threading running +2023-08-22,18:12:50.895 - INFO - threading running +2023-08-22,18:12:50.906 - INFO - threading running +2023-08-22,18:12:50.915 - INFO - threading running +2023-08-22,18:12:50.925 - INFO - threading running +2023-08-22,18:12:50.935 - INFO - threading running +2023-08-22,18:12:50.946 - INFO - threading running +2023-08-22,18:12:50.955 - INFO - threading running +2023-08-22,18:12:50.965 - INFO - threading running +2023-08-22,18:12:50.975 - INFO - threading running +2023-08-22,18:12:50.985 - INFO - threading running +2023-08-22,18:12:50.995 - INFO - threading running +2023-08-22,18:12:51.005 - INFO - threading running +2023-08-22,18:12:51.015 - INFO - threading running +2023-08-22,18:12:51.026 - INFO - threading running +2023-08-22,18:12:51.035 - INFO - threading running +2023-08-22,18:12:51.045 - INFO - threading running +2023-08-22,18:12:51.055 - INFO - threading running +2023-08-22,18:12:51.065 - INFO - threading running +2023-08-22,18:12:51.075 - INFO - threading running +2023-08-22,18:12:51.085 - INFO - threading running +2023-08-22,18:12:51.096 - INFO - threading running +2023-08-22,18:12:51.106 - INFO - threading running +2023-08-22,18:12:51.116 - INFO - threading running +2023-08-22,18:12:51.126 - INFO - threading running +2023-08-22,18:12:51.136 - INFO - threading running +2023-08-22,18:12:51.146 - INFO - threading running +2023-08-22,18:12:51.156 - INFO - threading running +2023-08-22,18:12:51.166 - INFO - threading running +2023-08-22,18:12:51.176 - INFO - threading running +2023-08-22,18:12:51.186 - INFO - threading running +2023-08-22,18:12:51.190 - INFO - ---------------------------------------------------- +2023-08-22,18:12:51.190 - INFO - 122th iteration +2023-08-22,18:12:51.190 - INFO - average ll reward: 0.0872675161 +2023-08-22,18:12:51.190 - INFO - ---------------------------------------------------- + +2023-08-22,18:12:51.196 - INFO - updating finished +2023-08-22,18:12:55.311 - INFO - threading running +2023-08-22,18:12:55.326 - INFO - threading running +2023-08-22,18:12:55.337 - INFO - threading running +2023-08-22,18:12:55.346 - INFO - threading running +2023-08-22,18:12:55.356 - INFO - threading running +2023-08-22,18:12:55.366 - INFO - threading running +2023-08-22,18:12:55.376 - INFO - threading running +2023-08-22,18:12:55.386 - INFO - threading running +2023-08-22,18:12:55.396 - INFO - threading running +2023-08-22,18:12:55.406 - INFO - threading running +2023-08-22,18:12:55.416 - INFO - threading running +2023-08-22,18:12:55.426 - INFO - threading running +2023-08-22,18:12:55.436 - INFO - threading running +2023-08-22,18:12:55.446 - INFO - threading running +2023-08-22,18:12:55.456 - INFO - threading running +2023-08-22,18:12:55.466 - INFO - threading running +2023-08-22,18:12:55.476 - INFO - threading running +2023-08-22,18:12:55.486 - INFO - threading running +2023-08-22,18:12:55.496 - INFO - threading running +2023-08-22,18:12:55.507 - INFO - threading running +2023-08-22,18:12:55.517 - INFO - threading running +2023-08-22,18:12:55.527 - INFO - threading running +2023-08-22,18:12:55.537 - INFO - threading running +2023-08-22,18:12:55.547 - INFO - threading running +2023-08-22,18:12:55.557 - INFO - threading running +2023-08-22,18:12:55.568 - INFO - threading running +2023-08-22,18:12:55.578 - INFO - threading running +2023-08-22,18:12:55.589 - INFO - threading running +2023-08-22,18:12:55.599 - INFO - threading running +2023-08-22,18:12:55.609 - INFO - threading running +2023-08-22,18:12:55.619 - INFO - threading running +2023-08-22,18:12:55.629 - INFO - threading running +2023-08-22,18:12:55.639 - INFO - threading running +2023-08-22,18:12:55.650 - INFO - threading running +2023-08-22,18:12:55.660 - INFO - threading running +2023-08-22,18:12:55.670 - INFO - threading running +2023-08-22,18:12:55.681 - INFO - threading running +2023-08-22,18:12:55.690 - INFO - threading running +2023-08-22,18:12:55.700 - INFO - threading running +2023-08-22,18:12:55.710 - INFO - threading running +2023-08-22,18:12:55.720 - INFO - threading running +2023-08-22,18:12:55.730 - INFO - threading running +2023-08-22,18:12:55.740 - INFO - threading running +2023-08-22,18:12:55.750 - INFO - threading running +2023-08-22,18:12:55.761 - INFO - threading running +2023-08-22,18:12:55.771 - INFO - threading running +2023-08-22,18:12:55.782 - INFO - threading running +2023-08-22,18:12:55.792 - INFO - threading running +2023-08-22,18:12:55.802 - INFO - threading running +2023-08-22,18:12:55.812 - INFO - threading running +2023-08-22,18:12:55.822 - INFO - threading running +2023-08-22,18:12:55.832 - INFO - threading running +2023-08-22,18:12:55.843 - INFO - threading running +2023-08-22,18:12:55.852 - INFO - threading running +2023-08-22,18:12:55.863 - INFO - threading running +2023-08-22,18:12:55.872 - INFO - threading running +2023-08-22,18:12:55.882 - INFO - threading running +2023-08-22,18:12:55.892 - INFO - threading running +2023-08-22,18:12:55.899 - INFO - ---------------------------------------------------- +2023-08-22,18:12:55.900 - INFO - 123th iteration +2023-08-22,18:12:55.900 - INFO - average ll reward: 0.0806974981 +2023-08-22,18:12:55.900 - INFO - ---------------------------------------------------- + +2023-08-22,18:12:55.902 - INFO - updating finished +2023-08-22,18:12:59.983 - INFO - threading running +2023-08-22,18:12:59.997 - INFO - threading running +2023-08-22,18:13:00.007 - INFO - threading running +2023-08-22,18:13:00.017 - INFO - threading running +2023-08-22,18:13:00.027 - INFO - threading running +2023-08-22,18:13:00.037 - INFO - threading running +2023-08-22,18:13:00.047 - INFO - threading running +2023-08-22,18:13:00.058 - INFO - threading running +2023-08-22,18:13:00.068 - INFO - threading running +2023-08-22,18:13:00.078 - INFO - threading running +2023-08-22,18:13:00.088 - INFO - threading running +2023-08-22,18:13:00.099 - INFO - threading running +2023-08-22,18:13:00.108 - INFO - threading running +2023-08-22,18:13:00.119 - INFO - threading running +2023-08-22,18:13:00.129 - INFO - threading running +2023-08-22,18:13:00.139 - INFO - threading running +2023-08-22,18:13:00.150 - INFO - threading running +2023-08-22,18:13:00.161 - INFO - threading running +2023-08-22,18:13:00.171 - INFO - threading running +2023-08-22,18:13:00.181 - INFO - threading running +2023-08-22,18:13:00.191 - INFO - threading running +2023-08-22,18:13:00.202 - INFO - threading running +2023-08-22,18:13:00.212 - INFO - threading running +2023-08-22,18:13:00.223 - INFO - threading running +2023-08-22,18:13:00.233 - INFO - threading running +2023-08-22,18:13:00.242 - INFO - threading running +2023-08-22,18:13:00.252 - INFO - threading running +2023-08-22,18:13:00.262 - INFO - threading running +2023-08-22,18:13:00.272 - INFO - threading running +2023-08-22,18:13:00.282 - INFO - threading running +2023-08-22,18:13:00.293 - INFO - threading running +2023-08-22,18:13:00.304 - INFO - threading running +2023-08-22,18:13:00.314 - INFO - threading running +2023-08-22,18:13:00.323 - INFO - threading running +2023-08-22,18:13:00.333 - INFO - threading running +2023-08-22,18:13:00.343 - INFO - threading running +2023-08-22,18:13:00.353 - INFO - threading running +2023-08-22,18:13:00.363 - INFO - threading running +2023-08-22,18:13:00.374 - INFO - threading running +2023-08-22,18:13:00.384 - INFO - threading running +2023-08-22,18:13:00.394 - INFO - threading running +2023-08-22,18:13:00.404 - INFO - threading running +2023-08-22,18:13:00.414 - INFO - threading running +2023-08-22,18:13:00.425 - INFO - threading running +2023-08-22,18:13:00.434 - INFO - threading running +2023-08-22,18:13:00.444 - INFO - threading running +2023-08-22,18:13:00.454 - INFO - threading running +2023-08-22,18:13:00.465 - INFO - threading running +2023-08-22,18:13:00.474 - INFO - threading running +2023-08-22,18:13:00.484 - INFO - threading running +2023-08-22,18:13:00.495 - INFO - threading running +2023-08-22,18:13:00.506 - INFO - threading running +2023-08-22,18:13:00.516 - INFO - threading running +2023-08-22,18:13:00.526 - INFO - threading running +2023-08-22,18:13:00.535 - INFO - threading running +2023-08-22,18:13:00.545 - INFO - threading running +2023-08-22,18:13:00.555 - INFO - threading running +2023-08-22,18:13:00.556 - INFO - ---------------------------------------------------- +2023-08-22,18:13:00.557 - INFO - 124th iteration +2023-08-22,18:13:00.557 - INFO - average ll reward: 0.0884472965 +2023-08-22,18:13:00.557 - INFO - ---------------------------------------------------- + +2023-08-22,18:13:00.565 - INFO - updating finished +2023-08-22,18:13:04.630 - INFO - threading running +2023-08-22,18:13:04.642 - INFO - threading running +2023-08-22,18:13:04.652 - INFO - threading running +2023-08-22,18:13:04.662 - INFO - threading running +2023-08-22,18:13:04.672 - INFO - threading running +2023-08-22,18:13:04.683 - INFO - threading running +2023-08-22,18:13:04.692 - INFO - threading running +2023-08-22,18:13:04.702 - INFO - threading running +2023-08-22,18:13:04.712 - INFO - threading running +2023-08-22,18:13:04.722 - INFO - threading running +2023-08-22,18:13:04.732 - INFO - threading running +2023-08-22,18:13:04.742 - INFO - threading running +2023-08-22,18:13:04.752 - INFO - threading running +2023-08-22,18:13:04.763 - INFO - threading running +2023-08-22,18:13:04.774 - INFO - threading running +2023-08-22,18:13:04.783 - INFO - threading running +2023-08-22,18:13:04.793 - INFO - threading running +2023-08-22,18:13:04.803 - INFO - threading running +2023-08-22,18:13:04.814 - INFO - threading running +2023-08-22,18:13:04.824 - INFO - threading running +2023-08-22,18:13:04.834 - INFO - threading running +2023-08-22,18:13:04.844 - INFO - threading running +2023-08-22,18:13:04.855 - INFO - threading running +2023-08-22,18:13:04.865 - INFO - threading running +2023-08-22,18:13:04.875 - INFO - threading running +2023-08-22,18:13:04.885 - INFO - threading running +2023-08-22,18:13:04.895 - INFO - threading running +2023-08-22,18:13:04.905 - INFO - threading running +2023-08-22,18:13:04.915 - INFO - threading running +2023-08-22,18:13:04.926 - INFO - threading running +2023-08-22,18:13:04.935 - INFO - threading running +2023-08-22,18:13:04.945 - INFO - threading running +2023-08-22,18:13:04.956 - INFO - threading running +2023-08-22,18:13:04.966 - INFO - threading running +2023-08-22,18:13:04.977 - INFO - threading running +2023-08-22,18:13:04.987 - INFO - threading running +2023-08-22,18:13:04.997 - INFO - threading running +2023-08-22,18:13:05.007 - INFO - threading running +2023-08-22,18:13:05.017 - INFO - threading running +2023-08-22,18:13:05.028 - INFO - threading running +2023-08-22,18:13:05.037 - INFO - threading running +2023-08-22,18:13:05.047 - INFO - threading running +2023-08-22,18:13:05.057 - INFO - threading running +2023-08-22,18:13:05.068 - INFO - threading running +2023-08-22,18:13:05.078 - INFO - threading running +2023-08-22,18:13:05.088 - INFO - threading running +2023-08-22,18:13:05.099 - INFO - threading running +2023-08-22,18:13:05.109 - INFO - threading running +2023-08-22,18:13:05.119 - INFO - threading running +2023-08-22,18:13:05.130 - INFO - threading running +2023-08-22,18:13:05.136 - INFO - ---------------------------------------------------- +2023-08-22,18:13:05.136 - INFO - 125th iteration +2023-08-22,18:13:05.136 - INFO - average ll reward: 0.1181069184 +2023-08-22,18:13:05.136 - INFO - ---------------------------------------------------- + +2023-08-22,18:13:05.141 - INFO - updating finished +2023-08-22,18:13:09.198 - INFO - threading running +2023-08-22,18:13:09.209 - INFO - threading running +2023-08-22,18:13:09.219 - INFO - threading running +2023-08-22,18:13:09.229 - INFO - threading running +2023-08-22,18:13:09.239 - INFO - threading running +2023-08-22,18:13:09.250 - INFO - threading running +2023-08-22,18:13:09.259 - INFO - threading running +2023-08-22,18:13:09.269 - INFO - threading running +2023-08-22,18:13:09.279 - INFO - threading running +2023-08-22,18:13:09.289 - INFO - threading running +2023-08-22,18:13:09.300 - INFO - threading running +2023-08-22,18:13:09.310 - INFO - threading running +2023-08-22,18:13:09.319 - INFO - threading running +2023-08-22,18:13:09.329 - INFO - threading running +2023-08-22,18:13:09.339 - INFO - threading running +2023-08-22,18:13:09.349 - INFO - threading running +2023-08-22,18:13:09.359 - INFO - threading running +2023-08-22,18:13:09.370 - INFO - threading running +2023-08-22,18:13:09.380 - INFO - threading running +2023-08-22,18:13:09.390 - INFO - threading running +2023-08-22,18:13:09.400 - INFO - threading running +2023-08-22,18:13:09.411 - INFO - threading running +2023-08-22,18:13:09.421 - INFO - threading running +2023-08-22,18:13:09.431 - INFO - threading running +2023-08-22,18:13:09.442 - INFO - threading running +2023-08-22,18:13:09.453 - INFO - threading running +2023-08-22,18:13:09.462 - INFO - threading running +2023-08-22,18:13:09.472 - INFO - threading running +2023-08-22,18:13:09.482 - INFO - threading running +2023-08-22,18:13:09.492 - INFO - threading running +2023-08-22,18:13:09.502 - INFO - threading running +2023-08-22,18:13:09.512 - INFO - threading running +2023-08-22,18:13:09.522 - INFO - threading running +2023-08-22,18:13:09.532 - INFO - threading running +2023-08-22,18:13:09.543 - INFO - threading running +2023-08-22,18:13:09.553 - INFO - threading running +2023-08-22,18:13:09.563 - INFO - threading running +2023-08-22,18:13:09.572 - INFO - threading running +2023-08-22,18:13:09.582 - INFO - threading running +2023-08-22,18:13:09.592 - INFO - threading running +2023-08-22,18:13:09.603 - INFO - threading running +2023-08-22,18:13:09.612 - INFO - threading running +2023-08-22,18:13:09.622 - INFO - threading running +2023-08-22,18:13:09.633 - INFO - threading running +2023-08-22,18:13:09.642 - INFO - threading running +2023-08-22,18:13:09.652 - INFO - threading running +2023-08-22,18:13:09.662 - INFO - threading running +2023-08-22,18:13:09.672 - INFO - threading running +2023-08-22,18:13:09.683 - INFO - threading running +2023-08-22,18:13:09.693 - INFO - threading running +2023-08-22,18:13:09.704 - INFO - threading running +2023-08-22,18:13:09.713 - INFO - threading running +2023-08-22,18:13:09.723 - INFO - threading running +2023-08-22,18:13:09.733 - INFO - threading running +2023-08-22,18:13:09.743 - INFO - threading running +2023-08-22,18:13:09.754 - INFO - threading running +2023-08-22,18:13:09.756 - INFO - ---------------------------------------------------- +2023-08-22,18:13:09.757 - INFO - 126th iteration +2023-08-22,18:13:09.757 - INFO - average ll reward: 0.0850171438 +2023-08-22,18:13:09.757 - INFO - ---------------------------------------------------- + +2023-08-22,18:13:09.765 - INFO - updating finished +2023-08-22,18:13:13.795 - INFO - threading running +2023-08-22,18:13:13.808 - INFO - threading running +2023-08-22,18:13:13.818 - INFO - threading running +2023-08-22,18:13:13.828 - INFO - threading running +2023-08-22,18:13:13.838 - INFO - threading running +2023-08-22,18:13:13.848 - INFO - threading running +2023-08-22,18:13:13.858 - INFO - threading running +2023-08-22,18:13:13.868 - INFO - threading running +2023-08-22,18:13:13.878 - INFO - threading running +2023-08-22,18:13:13.889 - INFO - threading running +2023-08-22,18:13:13.898 - INFO - threading running +2023-08-22,18:13:13.909 - INFO - threading running +2023-08-22,18:13:13.918 - INFO - threading running +2023-08-22,18:13:13.928 - INFO - threading running +2023-08-22,18:13:13.939 - INFO - threading running +2023-08-22,18:13:13.950 - INFO - threading running +2023-08-22,18:13:13.960 - INFO - threading running +2023-08-22,18:13:13.970 - INFO - threading running +2023-08-22,18:13:13.980 - INFO - threading running +2023-08-22,18:13:13.991 - INFO - threading running +2023-08-22,18:13:14.000 - INFO - threading running +2023-08-22,18:13:14.011 - INFO - threading running +2023-08-22,18:13:14.021 - INFO - threading running +2023-08-22,18:13:14.030 - INFO - threading running +2023-08-22,18:13:14.040 - INFO - threading running +2023-08-22,18:13:14.050 - INFO - threading running +2023-08-22,18:13:14.060 - INFO - threading running +2023-08-22,18:13:14.070 - INFO - threading running +2023-08-22,18:13:14.081 - INFO - threading running +2023-08-22,18:13:14.092 - INFO - threading running +2023-08-22,18:13:14.102 - INFO - threading running +2023-08-22,18:13:14.111 - INFO - threading running +2023-08-22,18:13:14.121 - INFO - threading running +2023-08-22,18:13:14.131 - INFO - threading running +2023-08-22,18:13:14.141 - INFO - threading running +2023-08-22,18:13:14.151 - INFO - threading running +2023-08-22,18:13:14.161 - INFO - threading running +2023-08-22,18:13:14.171 - INFO - threading running +2023-08-22,18:13:14.181 - INFO - threading running +2023-08-22,18:13:14.191 - INFO - threading running +2023-08-22,18:13:14.202 - INFO - threading running +2023-08-22,18:13:14.211 - INFO - threading running +2023-08-22,18:13:14.221 - INFO - threading running +2023-08-22,18:13:14.231 - INFO - threading running +2023-08-22,18:13:14.241 - INFO - threading running +2023-08-22,18:13:14.252 - INFO - threading running +2023-08-22,18:13:14.262 - INFO - threading running +2023-08-22,18:13:14.272 - INFO - threading running +2023-08-22,18:13:14.282 - INFO - threading running +2023-08-22,18:13:14.292 - INFO - threading running +2023-08-22,18:13:14.303 - INFO - threading running +2023-08-22,18:13:14.313 - INFO - threading running +2023-08-22,18:13:14.323 - INFO - threading running +2023-08-22,18:13:14.333 - INFO - threading running +2023-08-22,18:13:14.343 - INFO - threading running +2023-08-22,18:13:14.353 - INFO - threading running +2023-08-22,18:13:14.361 - INFO - ---------------------------------------------------- +2023-08-22,18:13:14.361 - INFO - 127th iteration +2023-08-22,18:13:14.361 - INFO - average ll reward: 0.0859918628 +2023-08-22,18:13:14.361 - INFO - ---------------------------------------------------- + +2023-08-22,18:13:14.363 - INFO - updating finished +2023-08-22,18:13:18.459 - INFO - threading running +2023-08-22,18:13:18.470 - INFO - threading running +2023-08-22,18:13:18.480 - INFO - threading running +2023-08-22,18:13:18.490 - INFO - threading running +2023-08-22,18:13:18.501 - INFO - threading running +2023-08-22,18:13:18.511 - INFO - threading running +2023-08-22,18:13:18.522 - INFO - threading running +2023-08-22,18:13:18.531 - INFO - threading running +2023-08-22,18:13:18.541 - INFO - threading running +2023-08-22,18:13:18.551 - INFO - threading running +2023-08-22,18:13:18.561 - INFO - threading running +2023-08-22,18:13:18.572 - INFO - threading running +2023-08-22,18:13:18.583 - INFO - threading running +2023-08-22,18:13:18.593 - INFO - threading running +2023-08-22,18:13:18.602 - INFO - threading running +2023-08-22,18:13:18.612 - INFO - threading running +2023-08-22,18:13:18.623 - INFO - threading running +2023-08-22,18:13:18.633 - INFO - threading running +2023-08-22,18:13:18.643 - INFO - threading running +2023-08-22,18:13:18.653 - INFO - threading running +2023-08-22,18:13:18.663 - INFO - threading running +2023-08-22,18:13:18.674 - INFO - threading running +2023-08-22,18:13:18.683 - INFO - threading running +2023-08-22,18:13:18.694 - INFO - threading running +2023-08-22,18:13:18.705 - INFO - threading running +2023-08-22,18:13:18.715 - INFO - threading running +2023-08-22,18:13:18.724 - INFO - threading running +2023-08-22,18:13:18.734 - INFO - threading running +2023-08-22,18:13:18.744 - INFO - threading running +2023-08-22,18:13:18.755 - INFO - threading running +2023-08-22,18:13:18.764 - INFO - threading running +2023-08-22,18:13:18.774 - INFO - threading running +2023-08-22,18:13:18.784 - INFO - threading running +2023-08-22,18:13:18.795 - INFO - threading running +2023-08-22,18:13:18.805 - INFO - threading running +2023-08-22,18:13:18.815 - INFO - threading running +2023-08-22,18:13:18.826 - INFO - threading running +2023-08-22,18:13:18.836 - INFO - threading running +2023-08-22,18:13:18.846 - INFO - threading running +2023-08-22,18:13:18.856 - INFO - threading running +2023-08-22,18:13:18.867 - INFO - threading running +2023-08-22,18:13:18.877 - INFO - threading running +2023-08-22,18:13:18.888 - INFO - threading running +2023-08-22,18:13:18.898 - INFO - threading running +2023-08-22,18:13:18.907 - INFO - threading running +2023-08-22,18:13:18.917 - INFO - threading running +2023-08-22,18:13:18.927 - INFO - threading running +2023-08-22,18:13:18.938 - INFO - threading running +2023-08-22,18:13:18.947 - INFO - threading running +2023-08-22,18:13:18.957 - INFO - threading running +2023-08-22,18:13:18.967 - INFO - threading running +2023-08-22,18:13:18.977 - INFO - threading running +2023-08-22,18:13:18.988 - INFO - threading running +2023-08-22,18:13:18.998 - INFO - threading running +2023-08-22,18:13:19.008 - INFO - threading running +2023-08-22,18:13:19.017 - INFO - threading running +2023-08-22,18:13:19.027 - INFO - threading running +2023-08-22,18:13:19.037 - INFO - threading running +2023-08-22,18:13:19.046 - INFO - ---------------------------------------------------- +2023-08-22,18:13:19.047 - INFO - 128th iteration +2023-08-22,18:13:19.047 - INFO - average ll reward: 0.1005620147 +2023-08-22,18:13:19.047 - INFO - ---------------------------------------------------- + +2023-08-22,18:13:19.047 - INFO - updating finished +2023-08-22,18:13:23.121 - INFO - threading running +2023-08-22,18:13:23.136 - INFO - threading running +2023-08-22,18:13:23.146 - INFO - threading running +2023-08-22,18:13:23.156 - INFO - threading running +2023-08-22,18:13:23.167 - INFO - threading running +2023-08-22,18:13:23.177 - INFO - threading running +2023-08-22,18:13:23.187 - INFO - threading running +2023-08-22,18:13:23.197 - INFO - threading running +2023-08-22,18:13:23.207 - INFO - threading running +2023-08-22,18:13:23.218 - INFO - threading running +2023-08-22,18:13:23.228 - INFO - threading running +2023-08-22,18:13:23.239 - INFO - threading running +2023-08-22,18:13:23.250 - INFO - threading running +2023-08-22,18:13:23.259 - INFO - threading running +2023-08-22,18:13:23.269 - INFO - threading running +2023-08-22,18:13:23.279 - INFO - threading running +2023-08-22,18:13:23.289 - INFO - threading running +2023-08-22,18:13:23.299 - INFO - threading running +2023-08-22,18:13:23.310 - INFO - threading running +2023-08-22,18:13:23.319 - INFO - threading running +2023-08-22,18:13:23.329 - INFO - threading running +2023-08-22,18:13:23.339 - INFO - threading running +2023-08-22,18:13:23.349 - INFO - threading running +2023-08-22,18:13:23.359 - INFO - threading running +2023-08-22,18:13:23.369 - INFO - threading running +2023-08-22,18:13:23.379 - INFO - threading running +2023-08-22,18:13:23.389 - INFO - threading running +2023-08-22,18:13:23.400 - INFO - threading running +2023-08-22,18:13:23.409 - INFO - threading running +2023-08-22,18:13:23.419 - INFO - threading running +2023-08-22,18:13:23.429 - INFO - threading running +2023-08-22,18:13:23.439 - INFO - threading running +2023-08-22,18:13:23.449 - INFO - threading running +2023-08-22,18:13:23.459 - INFO - threading running +2023-08-22,18:13:23.469 - INFO - threading running +2023-08-22,18:13:23.480 - INFO - threading running +2023-08-22,18:13:23.489 - INFO - threading running +2023-08-22,18:13:23.499 - INFO - threading running +2023-08-22,18:13:23.509 - INFO - threading running +2023-08-22,18:13:23.520 - INFO - threading running +2023-08-22,18:13:23.531 - INFO - threading running +2023-08-22,18:13:23.542 - INFO - threading running +2023-08-22,18:13:23.552 - INFO - threading running +2023-08-22,18:13:23.563 - INFO - threading running +2023-08-22,18:13:23.574 - INFO - threading running +2023-08-22,18:13:23.584 - INFO - threading running +2023-08-22,18:13:23.595 - INFO - threading running +2023-08-22,18:13:23.605 - INFO - threading running +2023-08-22,18:13:23.615 - INFO - threading running +2023-08-22,18:13:23.625 - INFO - threading running +2023-08-22,18:13:23.635 - INFO - threading running +2023-08-22,18:13:23.646 - INFO - threading running +2023-08-22,18:13:23.656 - INFO - threading running +2023-08-22,18:13:23.665 - INFO - threading running +2023-08-22,18:13:23.675 - INFO - threading running +2023-08-22,18:13:23.686 - INFO - threading running +2023-08-22,18:13:23.696 - INFO - threading running +2023-08-22,18:13:23.706 - INFO - threading running +2023-08-22,18:13:23.709 - INFO - ---------------------------------------------------- +2023-08-22,18:13:23.709 - INFO - 129th iteration +2023-08-22,18:13:23.709 - INFO - average ll reward: 0.1043969659 +2023-08-22,18:13:23.710 - INFO - ---------------------------------------------------- + +2023-08-22,18:13:23.715 - INFO - updating finished +2023-08-22,18:13:27.782 - INFO - threading running +2023-08-22,18:13:27.794 - INFO - threading running +2023-08-22,18:13:27.805 - INFO - threading running +2023-08-22,18:13:27.815 - INFO - threading running +2023-08-22,18:13:27.825 - INFO - threading running +2023-08-22,18:13:27.835 - INFO - threading running +2023-08-22,18:13:27.845 - INFO - threading running +2023-08-22,18:13:27.855 - INFO - threading running +2023-08-22,18:13:27.865 - INFO - threading running +2023-08-22,18:13:27.875 - INFO - threading running +2023-08-22,18:13:27.886 - INFO - threading running +2023-08-22,18:13:27.896 - INFO - threading running +2023-08-22,18:13:27.905 - INFO - threading running +2023-08-22,18:13:27.915 - INFO - threading running +2023-08-22,18:13:27.926 - INFO - threading running +2023-08-22,18:13:27.936 - INFO - threading running +2023-08-22,18:13:27.946 - INFO - threading running +2023-08-22,18:13:27.956 - INFO - threading running +2023-08-22,18:13:27.966 - INFO - threading running +2023-08-22,18:13:27.977 - INFO - threading running +2023-08-22,18:13:27.986 - INFO - threading running +2023-08-22,18:13:27.996 - INFO - threading running +2023-08-22,18:13:28.006 - INFO - threading running +2023-08-22,18:13:28.016 - INFO - threading running +2023-08-22,18:13:28.026 - INFO - threading running +2023-08-22,18:13:28.036 - INFO - threading running +2023-08-22,18:13:28.046 - INFO - threading running +2023-08-22,18:13:28.056 - INFO - threading running +2023-08-22,18:13:28.066 - INFO - threading running +2023-08-22,18:13:28.076 - INFO - threading running +2023-08-22,18:13:28.087 - INFO - threading running +2023-08-22,18:13:28.097 - INFO - threading running +2023-08-22,18:13:28.107 - INFO - threading running +2023-08-22,18:13:28.117 - INFO - threading running +2023-08-22,18:13:28.127 - INFO - threading running +2023-08-22,18:13:28.138 - INFO - threading running +2023-08-22,18:13:28.147 - INFO - threading running +2023-08-22,18:13:28.157 - INFO - threading running +2023-08-22,18:13:28.167 - INFO - threading running +2023-08-22,18:13:28.178 - INFO - threading running +2023-08-22,18:13:28.189 - INFO - threading running +2023-08-22,18:13:28.199 - INFO - threading running +2023-08-22,18:13:28.209 - INFO - threading running +2023-08-22,18:13:28.219 - INFO - threading running +2023-08-22,18:13:28.230 - INFO - threading running +2023-08-22,18:13:28.239 - INFO - threading running +2023-08-22,18:13:28.249 - INFO - threading running +2023-08-22,18:13:28.259 - INFO - threading running +2023-08-22,18:13:28.270 - INFO - threading running +2023-08-22,18:13:28.280 - INFO - threading running +2023-08-22,18:13:28.290 - INFO - threading running +2023-08-22,18:13:28.300 - INFO - threading running +2023-08-22,18:13:28.310 - INFO - threading running +2023-08-22,18:13:28.320 - INFO - threading running +2023-08-22,18:13:28.331 - INFO - threading running +2023-08-22,18:13:28.341 - INFO - threading running +2023-08-22,18:13:28.351 - INFO - threading running +2023-08-22,18:13:28.357 - INFO - ---------------------------------------------------- +2023-08-22,18:13:28.357 - INFO - 130th iteration +2023-08-22,18:13:28.357 - INFO - average ll reward: 0.0949027992 +2023-08-22,18:13:28.357 - INFO - ---------------------------------------------------- + +2023-08-22,18:13:28.362 - INFO - updating finished +2023-08-22,18:13:32.431 - INFO - threading running +2023-08-22,18:13:32.446 - INFO - threading running +2023-08-22,18:13:32.456 - INFO - threading running +2023-08-22,18:13:32.466 - INFO - threading running +2023-08-22,18:13:32.476 - INFO - threading running +2023-08-22,18:13:32.486 - INFO - threading running +2023-08-22,18:13:32.496 - INFO - threading running +2023-08-22,18:13:32.506 - INFO - threading running +2023-08-22,18:13:32.516 - INFO - threading running +2023-08-22,18:13:32.527 - INFO - threading running +2023-08-22,18:13:32.537 - INFO - threading running +2023-08-22,18:13:32.548 - INFO - threading running +2023-08-22,18:13:32.559 - INFO - threading running +2023-08-22,18:13:32.569 - INFO - threading running +2023-08-22,18:13:32.578 - INFO - threading running +2023-08-22,18:13:32.588 - INFO - threading running +2023-08-22,18:13:32.598 - INFO - threading running +2023-08-22,18:13:32.608 - INFO - threading running +2023-08-22,18:13:32.618 - INFO - threading running +2023-08-22,18:13:32.628 - INFO - threading running +2023-08-22,18:13:32.638 - INFO - threading running +2023-08-22,18:13:32.648 - INFO - threading running +2023-08-22,18:13:32.658 - INFO - threading running +2023-08-22,18:13:32.668 - INFO - threading running +2023-08-22,18:13:32.678 - INFO - threading running +2023-08-22,18:13:32.688 - INFO - threading running +2023-08-22,18:13:32.698 - INFO - threading running +2023-08-22,18:13:32.709 - INFO - threading running +2023-08-22,18:13:32.720 - INFO - threading running +2023-08-22,18:13:32.730 - INFO - threading running +2023-08-22,18:13:32.739 - INFO - threading running +2023-08-22,18:13:32.749 - INFO - threading running +2023-08-22,18:13:32.759 - INFO - threading running +2023-08-22,18:13:32.769 - INFO - threading running +2023-08-22,18:13:32.779 - INFO - threading running +2023-08-22,18:13:32.789 - INFO - threading running +2023-08-22,18:13:32.799 - INFO - threading running +2023-08-22,18:13:32.810 - INFO - threading running +2023-08-22,18:13:32.820 - INFO - threading running +2023-08-22,18:13:32.830 - INFO - threading running +2023-08-22,18:13:32.840 - INFO - threading running +2023-08-22,18:13:32.849 - INFO - threading running +2023-08-22,18:13:32.860 - INFO - threading running +2023-08-22,18:13:32.870 - INFO - threading running +2023-08-22,18:13:32.880 - INFO - threading running +2023-08-22,18:13:32.890 - INFO - threading running +2023-08-22,18:13:32.900 - INFO - threading running +2023-08-22,18:13:32.910 - INFO - threading running +2023-08-22,18:13:32.920 - INFO - threading running +2023-08-22,18:13:32.930 - INFO - threading running +2023-08-22,18:13:32.940 - INFO - threading running +2023-08-22,18:13:32.951 - INFO - threading running +2023-08-22,18:13:32.960 - INFO - threading running +2023-08-22,18:13:32.970 - INFO - threading running +2023-08-22,18:13:32.981 - INFO - threading running +2023-08-22,18:13:32.991 - INFO - threading running +2023-08-22,18:13:33.001 - INFO - threading running +2023-08-22,18:13:33.012 - INFO - threading running +2023-08-22,18:13:33.016 - INFO - ---------------------------------------------------- +2023-08-22,18:13:33.016 - INFO - 131th iteration +2023-08-22,18:13:33.016 - INFO - average ll reward: 0.0996299097 +2023-08-22,18:13:33.016 - INFO - ---------------------------------------------------- + +2023-08-22,18:13:33.021 - INFO - updating finished +2023-08-22,18:13:37.066 - INFO - threading running +2023-08-22,18:13:37.077 - INFO - threading running +2023-08-22,18:13:37.088 - INFO - threading running +2023-08-22,18:13:37.098 - INFO - threading running +2023-08-22,18:13:37.108 - INFO - threading running +2023-08-22,18:13:37.118 - INFO - threading running +2023-08-22,18:13:37.128 - INFO - threading running +2023-08-22,18:13:37.138 - INFO - threading running +2023-08-22,18:13:37.149 - INFO - threading running +2023-08-22,18:13:37.158 - INFO - threading running +2023-08-22,18:13:37.168 - INFO - threading running +2023-08-22,18:13:37.179 - INFO - threading running +2023-08-22,18:13:37.188 - INFO - threading running +2023-08-22,18:13:37.198 - INFO - threading running +2023-08-22,18:13:37.208 - INFO - threading running +2023-08-22,18:13:37.218 - INFO - threading running +2023-08-22,18:13:37.228 - INFO - threading running +2023-08-22,18:13:37.238 - INFO - threading running +2023-08-22,18:13:37.248 - INFO - threading running +2023-08-22,18:13:37.258 - INFO - threading running +2023-08-22,18:13:37.269 - INFO - threading running +2023-08-22,18:13:37.279 - INFO - threading running +2023-08-22,18:13:37.288 - INFO - threading running +2023-08-22,18:13:37.298 - INFO - threading running +2023-08-22,18:13:37.308 - INFO - threading running +2023-08-22,18:13:37.318 - INFO - threading running +2023-08-22,18:13:37.328 - INFO - threading running +2023-08-22,18:13:37.338 - INFO - threading running +2023-08-22,18:13:37.348 - INFO - threading running +2023-08-22,18:13:37.358 - INFO - threading running +2023-08-22,18:13:37.368 - INFO - threading running +2023-08-22,18:13:37.378 - INFO - threading running +2023-08-22,18:13:37.388 - INFO - threading running +2023-08-22,18:13:37.398 - INFO - threading running +2023-08-22,18:13:37.408 - INFO - threading running +2023-08-22,18:13:37.418 - INFO - threading running +2023-08-22,18:13:37.429 - INFO - threading running +2023-08-22,18:13:37.440 - INFO - threading running +2023-08-22,18:13:37.451 - INFO - threading running +2023-08-22,18:13:37.460 - INFO - threading running +2023-08-22,18:13:37.470 - INFO - threading running +2023-08-22,18:13:37.480 - INFO - threading running +2023-08-22,18:13:37.490 - INFO - threading running +2023-08-22,18:13:37.500 - INFO - threading running +2023-08-22,18:13:37.510 - INFO - threading running +2023-08-22,18:13:37.520 - INFO - threading running +2023-08-22,18:13:37.530 - INFO - threading running +2023-08-22,18:13:37.541 - INFO - threading running +2023-08-22,18:13:37.550 - INFO - threading running +2023-08-22,18:13:37.560 - INFO - threading running +2023-08-22,18:13:37.570 - INFO - threading running +2023-08-22,18:13:37.580 - INFO - threading running +2023-08-22,18:13:37.591 - INFO - threading running +2023-08-22,18:13:37.601 - INFO - threading running +2023-08-22,18:13:37.611 - INFO - threading running +2023-08-22,18:13:37.621 - INFO - threading running +2023-08-22,18:13:37.631 - INFO - threading running +2023-08-22,18:13:37.641 - INFO - threading running +2023-08-22,18:13:37.651 - INFO - ---------------------------------------------------- +2023-08-22,18:13:37.651 - INFO - threading running +2023-08-22,18:13:37.651 - INFO - 132th iteration +2023-08-22,18:13:37.653 - INFO - average ll reward: 0.0954247780 +2023-08-22,18:13:37.653 - INFO - ---------------------------------------------------- + +2023-08-22,18:13:37.661 - INFO - updating finished +2023-08-22,18:13:38.704 - INFO - You pressed Ctrl+C! diff --git a/raisimUnity/linux/.gitignore b/raisimUnity/linux/.gitignore old mode 100644 new mode 100755 diff --git a/rsc/anymal_c/urdf/anymal.urdf b/rsc/anymal_c/urdf/anymal.urdf index 230fb2bf3..58e8f74ac 100755 --- a/rsc/anymal_c/urdf/anymal.urdf +++ b/rsc/anymal_c/urdf/anymal.urdf @@ -689,7 +689,7 @@ - + @@ -765,7 +765,7 @@ - + @@ -933,7 +933,7 @@ - + @@ -1009,7 +1009,7 @@ - + @@ -1177,7 +1177,7 @@ - + @@ -1253,7 +1253,7 @@ - + @@ -1421,7 +1421,7 @@ - + @@ -1497,7 +1497,7 @@ - + diff --git a/rsc/do_legs/do_legs.urdf b/rsc/do_legs/do_legs.urdf new file mode 100644 index 000000000..cdab0daf2 --- /dev/null +++ b/rsc/do_legs/do_legs.urdf @@ -0,0 +1,228 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + > + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/rsc/leg/a.urdf b/rsc/leg/a.urdf new file mode 100644 index 000000000..9f5b7d53f --- /dev/null +++ b/rsc/leg/a.urdf @@ -0,0 +1,512 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/rsc/leg/leg.urdf b/rsc/leg/leg.urdf new file mode 100644 index 000000000..a1fb77105 --- /dev/null +++ b/rsc/leg/leg.urdf @@ -0,0 +1,131 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/rsc/leg/leg1.urdf b/rsc/leg/leg1.urdf new file mode 100644 index 000000000..04a3cdc5b --- /dev/null +++ b/rsc/leg/leg1.urdf @@ -0,0 +1,224 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/rsc/leg/leg2.urdf b/rsc/leg/leg2.urdf new file mode 100644 index 000000000..5165e82c8 --- /dev/null +++ b/rsc/leg/leg2.urdf @@ -0,0 +1,128 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +