FBTUG-FarmHarvestBot 驗證記錄
整合
SI-V004:小單-ROS+Mini FarmBot
驗證主過程
- 取得 Mini FarmBot 的 code
- 確認 console 可以用 Gcode 溝通
- +FBTUG-FarmBot 韌體設計: Arduino-命令介面驗證
- Trace code, 看預期怎麼改
- 測試 Second debug serial
- FT232 https://www.icshop.com.tw/product_info.php/products_id/23612
- MEGA https://store.arduino.cc/usa/arduino-mega-2560-rev3
- pin map: http://techtonic10.blogspot.com/2016/06/arduino-mega-2560-pin-mapping.html
- 接線
- FT232:GND-MEGA GND
- FT232:VCCIO-MEGA 3.3
- FT232:TXD-MEGA RX2
- FT232:RXD-MEGA TX2
- 測試
- Serial1 可以看到 status string, Serial2 可以看到=>不知為何 Serial2 不能看到 command status
- Serial1 可以打 command 看到結果
- 好像 ROS 可以跟 Serial1 相容。先不測這個
- ROS String Trx 整合確認能與 某個簡單的 CLI 溝通
- 試試這個 https://github.com/scogswell/ArduinoSerialCommand
- pass ON/OFF command
- Code: ROS_SerialCommandExample
- commit id: a08a2af3e83154c516c7394982614ea91867c722
- Serial2 supported
- Code: https://github.com/FBTUG/FarmHarvestBot/tree/master/software/bring_up/ros_arduino/ROS_SerialCommandExample
- commit id:
- [TBD]
- 將 ROS 相關的 code 用 define 包起來,可以用來改成不支援 ROS 的原始模式
- 命令參數的實作可以加強
- 整合到 ROS CLI node
- 開發打算改在 debug_ros.py, 也參考 camera_commander_prototype.py
- Code: https://github.com/FBTUG/FarmHarvestBot/blob/master/software/debug_ros/src/debug_ros.py
- commit id
- +FBTUG-FarmHarvestBot 研究筆記-如何 Debug ROS 系統: Demo-ROS-CLI(-serial-CLI-enabl
- 如何將 item 7 的移植到自己的系統
- 大部分的 Arduino 沒有需要 CLI, 所以第一部分的說明沒不包含 CLI 的部分
- Arduino 部分
- 安裝 Arduino ros_lib
- +FBTUG-FarmHarvestBot 研究筆記-玩 OpenCR: 用-RPI-接上-Arduino-MEGA
- 更改自己的 Arduino code, enable ROS
- 參考 +FBTUG-FarmHarvestBot 研究筆記-玩 OpenCR: 用-ROS-方式讓-OpenCR-LED-亮
- 將 範例中,跟 ROS 有關係的 include, define, 變數宣告,function, code 等,都貼到自己的 code 中
- 到這裡就可以 build 以及測試
- 將原本的 Serial(UART), 轉移到 其他 port (ex: Serial2)
- 由於接上 ROS 後就會沒有 Serial console, 如何想要有 console 的話,就需要這個步驟
- 最簡單的方法就是將所有的 Serial 改成 Serial2(ex)
- 本範例用的方法可能比較適用於大系統,又三不五時想要換來換去的
- #define TERMINAL Serial2
- Serial.begin(115200)=>TERMINAL.begin(115200);
- ROS 測試
- CLI 部分請多參考 5.b 過程
- 加上 CLI
- Arduino 部分
- code 的部分,除 a 以外,請多參考 item7
- 主要就是如何讓收到的 string message 導入原來系統的 parsing
- 大部分的 Arduino CLI parsing 都滿複雜,也都是很類似的方法與過程,重點就是將 paring function 的 input 從硬體取得的部分換成用軟體給
- 即是在目前這麼簡單的 CLI 中,這個部分就有點頭大了,而且這個原始範例裡面還一些不同的情境需要支援,最簡單的方式就是另外開一個,讓用硬體的方式,跟用軟體的方式直接切開,Code 清爽與好維護
- 由於一般的 console 是一個字一個字處理,但從 ROS 來或許可以簡化成一行一行來(所謂的 line mode), 此範例是直接轉成 line mode
- ROS 測試
- 請參考 5.c, 6.a
- 真正上到 Mini FarmBot 看是不是之後請夥伴處理
驗證細部過程
1.使用 FarmHarvestBot-arduino-6.0.2.CGH
2.
R00 Q0
R82 X0.00 Y0.00 Z0.00 Q0
R81 XA1 XB1 YA1 YB1 ZA1 ZB1 0 Q0
R88
R08 *F83*
R01 Q0
R83 6.0.1.R Q0
R02 Q0
5.
sudo usermod -a -G dialout ubuntu
rosrun rosserial_python serial_node.py /dev/ttyACM0
osboxes@osboxes:~$ rostopic echo /Tx
osboxes@osboxes:~$ rostopic pub -r 2 /Rx std_msgs/String '{data : "fdadafd"}'
5b.
Running example:
ubuntu@ha:~$ rosrun rosserial_python serial_node.py /dev/ttyACM0
[INFO] [1540425253.412201]: ROS Serial Python Node
[INFO] [1540425253.435285]: Connecting to /dev/ttyACM0 at 57600 baud
[INFO] [1540425255.571703]: Note: publish buffer size is 512 bytes
[INFO] [1540425255.573582]: Setup publisher on Tx [std_msgs/String]
[INFO] [1540425255.589281]: Note: subscribe buffer size is 512 bytes
[INFO] [1540425255.590872]: Setup subscriber on Rx [std_msgs/String]
ubuntu@ha:~$ rostopic pub -r 0.5 /Rx std_msgs/String '{data : "OFF"}'
ubuntu@ha:~$ rostopic pub -r 0.5 /Rx std_msgs/String '{data : "ON"}'
osboxes@osboxes:~$ rostopic echo /Tx
data: "HELLO"
---
data: "ON"
5c.
ROS和Serial2 debug console 同時支援
接線:如接線與環境
韌體:github
ROS CLI control by ROS string messagae
Description:
Arduino sub /Rx: std_msg:String, if match command, process as CLI command, and reply confirmation by topic /Tx
if not match, discard it without reply.
Debug console set to Serial2( pin TX2), It show debug message also accept command, this work with ROS at the same time.
Terminal should setup to line mode with \r as enter key
Demo command list:
ON: turn on LED
OFF: turn off LED
HELLO: do nothing.
Running example:
ubuntu@ha:~$ rosrun rosserial_python serial_node.py /dev/ttyACM0
[INFO] [1540425253.412201]: ROS Serial Python Node
[INFO] [1540425253.435285]: Connecting to /dev/ttyACM0 at 57600 baud
[INFO] [1540425255.571703]: Note: publish buffer size is 512 bytes
[INFO] [1540425255.573582]: Setup publisher on Tx [std_msgs/String]
[INFO] [1540425255.589281]: Note: subscribe buffer size is 512 bytes
[INFO] [1540425255.590872]: Setup subscriber on Rx [std_msgs/String]
ubuntu@ha:~$ rostopic pub -r 0.5 /Rx std_msgs/String '{data : "OFF"}'
ubuntu@ha:~$ rostopic pub -r 0.5 /Rx std_msgs/String '{data : "ON"}'
ubuntu@ha:~$ rostopic pub -r 0.5 /Rx std_msgs/String '{data : "HELLO"}'
osboxes@osboxes:~$ rostopic echo /Tx
data: "HELLO"
---
data: "ON"
6.a
ubuntu@ha:~$ ./debug_ros.py
CLI>help
Documented commands (type help ):
========================================
bag dump help quit scli scli_enable test version
CLI>version
V0.0.2
CLI>scli_enable 0
[INFO] [1540496065.112951]: scli disabled
CLI>help scli
send cli command to serial
scli {serial_cli_command}
ex: scli ON
demo rosserial CLI have ON/OFF/HELLO command
CLI>help scli_enable
setup rosserial CLI pub/sub support
scli_enable [setting]
setting:
0: disable
1: enable (default)
ex: scli_enable 1
CLI>scli_enable 1
[INFO] [1540496217.518510]: scli enabled
CLI>scli ON
CLI>[INFO] [1540496220.445105]: SCLI Rx:ON # you should also see LED turn on at Arduino MEGA
scli OFF
CLI>[INFO] [1540496227.389690]: SCLI Rx:OFF
scli abc
8.b.i 改 code 的重點
diff SerialCommand.cpp
除了 Serial 被換掉,就加入了這個 function
SerialCommand::readSerialByBuffer(char *fun_buffer)
從 .h 看,就只有加入一個 function, 跟為了不要跟 debug console 打架,多用了一個 token pointer
wuulong-pro:ROS_SerialCommandExample wuulong$ diff SerialCommand.h /Users/wuulong/MakerBk/Arduino/workspace/libraries_bk/ArduinoSerialCommand/SerialCommand.h
73d72
< #define TERMINAL Serial2
87d85
< char* readSerialByBuffer(char *fun_buffer); // used in ROS enabled
96d93
< char *tokenBuf; // Returned token from the fun_buffer as returned by strtok_r
111c108
< #endif //SerialCommand_h
---
> #endif //SerialCommand_h
wuulong-pro:ROS_SerialCommandExample wuulong$ diff ROS_SerialCommandExample.ino /Users/wuulong/MakerBk/Arduino/workspace/libraries_bk/ArduinoSerialCommand/examples/SerialCommandHardwareOnlyExample/SerialCommandHardwareOnlyExample.ino
< #include "SerialCommand.h"
< #include
< #include
43,62d16
< ros::NodeHandle nh;
<
< std_msgs::String tx_str_msg;
< ros::Publisher chatter("Tx", &tx_str_msg);
<
< void messageCb( const std_msgs::String& rx_str_msg) {
< char* return_str;
< TERMINAL.println(rx_str_msg.data);
< tx_str_msg.data = rx_str_msg.data;
< return_str= SCmd.readSerialByBuffer(rx_str_msg.data);
< if(return_str) {
< tx_str_msg.data = return_str;
< chatter.publish( &tx_str_msg );
< }
<
<
< }
< ros::Subscriber sub("Rx", messageCb );
<
<
68,70c22
<
< TERMINAL.begin(115200);
<
---
> Serial.begin(9600);
78,83c30
< TERMINAL.println("Ready1");
<
< nh.initNode();
< nh.advertise(chatter);
< nh.subscribe(sub);
<
---
> Serial.println("Ready");
90d36
< nh.spinOnce();
96c42
變異中關於 Serial->TERMINAL 被移除了
雜項紀錄
#ifdef Serial2_Use //-2018.08.15
Serial2.begin(lBaudRate);
#endif
Serial.print("Serial2 BaudRate = "); Serial.println(lBaudRate);
//-2018.08.15 -鮑率(baud rate)- 0.9600, 1.19200, 2.38400, 3.57600, 4.115200 ; Serial2_BaudRate = 250
int vBaudRate = ParameterList::getInstance()->getValue(Serial2_BaudRate);
long lBaudRate = cBaudRate[vBaudRate];
long cBaudRate[5] = {9600, 19200, 38400, 57600, 115200}; //-2018.08.15
Serial2 BaudRate = 9600
R99 ARDUINO STARTUP COMPLETE
The Arduino Mega has three additional serial ports: Serial1 on pins 19 (RX) and 18 (TX), Serial2 on pins 17 (RX) and 16 (TX),
https://www.arduino.cc/en/Hacking/PinMapping2560
SW-V010:單元-rosserial 穩定性驗證
目的:
有高人夥伴提醒 rosserial 穩定性需注意,所以來玩玩看,穩定性的狀態是如何
說明:了解一下 rosserial 的穩定性
驗證項目發想:
- 看發多快,多少會漏
- receive jitter 是多大
- 是否跟 serial 的 buffer 有關,是否跟發端突然爆量的 message 有關?
快速結論
Serial 因為 baudrate 的限制,能傳的頻寬是有限的,看包的大小,每個包約能傳 2.3ms, 約為 434 Hz.
經實測,系統可能可以穩定在 344 Hz, 實測穩定在 360Hz
實測推論,python 會實際 buffer 住還不能送出的 msg, 而且 buffer 容量還滿大。所以只要有足夠的時間,基本上是沒有漏。這只限於目前很簡單的情境。
當 msg size 變化,內容變化(聽說 Array type 要多注意, topic太多 有些會沒辦法傳輸),更多同步的問題發生,也可能造成問題。另外相關的 Limitations 也要注意
- 目前最長只測過 100Hz, 360000(約一小時),沒漏
Study
7+8+N if N=2 => 17
>>> 1/(57600.0/8/17)
0.002361111111111111
最快每個包得花 2.36ms
>>> 1/(57600.0/8/21)
0.002916666666666667
目前不漏平均時間可有 2.9ms , 估計封包約為 21 byte
驗證過程
ubuntu@ha:~$ ./debug_ros.py
CLI>help
Documented commands (type help ):
========================================
bag dump help quit scli scli_enable scli_stabletest test version
CLI>help scli_stabletest
check how stable rosserial demo can be, send cmd with count and speed, check how many reply (speed: time/s)
scli_stabletest [speed] [count]
ex: scli_stabletest 100 1000
send 100 times per second with 1000 commands
CLI>scli_enable 1
[INFO] [1540519189.943629]: scli enabled
CLI>scli_stabletest 1000 1000
[INFO] [1540519202.905114]: scli stable test result: setup speed=1000, count=1000
result pub_cnt=1000,sub_cnt=695,receive rate=0.695000
CLI>scli_stabletest 1000 1000
[INFO] [1540519208.041393]: scli stable test result: setup speed=1000, count=1000
result pub_cnt=1000,sub_cnt=690,receive rate=0.690000
CLI>scli_stabletest 1000 1000
[INFO] [1540519211.987681]: scli stable test result: setup speed=1000, count=1000
result pub_cnt=1000,sub_cnt=687,receive rate=0.687000
CLI>scli_stabletest 10000 1000
[INFO] [1540519217.349348]: scli stable test result: setup speed=10000, count=1000
result pub_cnt=1000,sub_cnt=486,receive rate=0.486000
CLI>scli_stabletest 30000 1000
[INFO] [1540519223.629941]: scli stable test result: setup speed=30000, count=1000
result pub_cnt=1000,sub_cnt=488,receive rate=0.488000
CLI>scli_stabletest 500 1000
[INFO] [1540519239.462990]: scli stable test result: setup speed=500, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000
CLI>scli_stabletest 500 10000
[INFO] [1540519264.064050]: scli stable test result: setup speed=500, count=10000
result pub_cnt=10000,sub_cnt=7224,receive rate=0.722400
CLI>scli_stabletest 100 10000
[INFO] [1540519375.677029]: scli stable test result: setup speed=100, count=10000
result pub_cnt=10000,sub_cnt=10000,receive rate=1.000000
CLI>scli_stabletest 200 10000
[INFO] [1540519435.340176]: scli stable test result: setup speed=200, count=10000
result pub_cnt=10000,sub_cnt=10000,receive rate=1.000000
CLI>scli_stabletest 300 10000
[INFO] [1540519519.615070]: scli stable test result: setup speed=300, count=10000
result pub_cnt=10000,sub_cnt=10000,receive rate=1.000000
CLI>scli_stabletest 400 10000
[INFO] [1540519553.830436]: scli stable test result: setup speed=400, count=10000
result pub_cnt=10000,sub_cnt=8974,receive rate=0.897400
CLI>scli_stabletest 100 360000
[INFO] [1540524030.395446]: scli stable test result: setup speed=100, count=360000
result pub_cnt=360000,sub_cnt=360000,receive rate=1.000000
CLI>
截止時間為發完後 1s
CLI>help scli_stabletest_range
check how stable rosserial demo can be, send cmd with count and speed, check how many reply (speed: time/s)
scli_stabletest_range [start] [end] [step] [count]
ex: scli_stabletest_range 100 900 50 1000
send range(100,900,50) , everytime send 1000 commands
CLI>scli_stabletest_range 100 900 100 1000
[INFO] [1540537860.940812]: scli stable test result: setup speed=100, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=9.990812
[INFO] [1540537860.992570]: nmean=9999027
[INFO] [1540537861.009987]: nmax=13444186
[INFO] [1540537861.027599]: nmin=5868912
[INFO] [1540537867.027052]: scli stable test result: setup speed=200, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=4.995995
[INFO] [1540537867.084192]: nmean=5001029
[INFO] [1540537867.104678]: nmax=11622191
[INFO] [1540537867.122549]: nmin=1678943
[INFO] [1540537871.456411]: scli stable test result: setup speed=300, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=3.330420
[INFO] [1540537871.512056]: nmean=3331405
[INFO] [1540537871.546985]: nmax=6186008
[INFO] [1540537871.583684]: nmin=1258135
[INFO] [1540537875.085905]: scli stable test result: setup speed=400, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=2.497890
[INFO] [1540537875.114176]: nmean=2903563
[INFO] [1540537875.131926]: nmax=9689808
[INFO] [1540537875.149662]: nmin=1209974
[INFO] [1540537878.151131]: scli stable test result: setup speed=500, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=1.998373
[INFO] [1540537878.178462]: nmean=2899423
[INFO] [1540537878.196120]: nmax=9978056
[INFO] [1540537878.214610]: nmin=1301050
[INFO] [1540537880.883513]: scli stable test result: setup speed=600, count=1000
result pub_cnt=1000,sub_cnt=916,receive rate=0.916000,duration seconds=1.665419
[INFO] [1540537880.936662]: nmean=2901253
[INFO] [1540537880.972745]: nmax=51687002
[INFO] [1540537880.999922]: nmin=117063
[INFO] [1540537883.431497]: scli stable test result: setup speed=700, count=1000
result pub_cnt=1000,sub_cnt=838,receive rate=0.838000,duration seconds=1.427489
[INFO] [1540537883.456221]: nmean=2898468
[INFO] [1540537883.473618]: nmax=24147987
[INFO] [1540537883.490337]: nmin=45777
[INFO] [1540537885.743606]: scli stable test result: setup speed=800, count=1000
result pub_cnt=1000,sub_cnt=779,receive rate=0.779000,duration seconds=1.249143
[INFO] [1540537885.790356]: nmean=2890635
[INFO] [1540537885.807418]: nmax=45366049
[INFO] [1540537885.823537]: nmin=56982
截止時間為發完後 10s
CLI>scli_stabletest_range 100 900 100 1000
[INFO] [1540538894.727185]: scli stable test result: setup speed=100, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=9.991117
[INFO] [1540538894.785865]: nmean=9999969
[INFO] [1540538894.809113]: nmax=13170004
[INFO] [1540538894.829774]: nmin=6149053
[INFO] [1540538909.827572]: scli stable test result: setup speed=200, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=4.995458
[INFO] [1540538909.887178]: nmean=5001461
[INFO] [1540538909.907040]: nmax=9006023
[INFO] [1540538909.926038]: nmin=1650095
[INFO] [1540538923.260236]: scli stable test result: setup speed=300, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=3.330516
[INFO] [1540538923.316715]: nmean=3332213
[INFO] [1540538923.353691]: nmax=6386996
[INFO] [1540538923.390176]: nmin=1257181
[INFO] [1540538935.896047]: scli stable test result: setup speed=400, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=2.497906
[INFO] [1540538935.951107]: nmean=2870618
[INFO] [1540538935.986290]: nmax=69477082
[INFO] [1540538936.006118]: nmin=1171827
[INFO] [1540538948.017109]: scli stable test result: setup speed=500, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=1.998639
[INFO] [1540538948.072480]: nmean=2891492
[INFO] [1540538948.099080]: nmax=7931948
[INFO] [1540538948.116820]: nmin=954867
[INFO] [1540538959.791969]: scli stable test result: setup speed=600, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=1.665416
[INFO] [1540538959.849328]: nmean=2894683
[INFO] [1540538959.886214]: nmax=10215044
[INFO] [1540538959.906309]: nmin=1497984
[INFO] [1540538971.336295]: scli stable test result: setup speed=700, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=1.427549
[INFO] [1540538971.391963]: nmean=2883048
[INFO] [1540538971.410874]: nmax=10548830
[INFO] [1540538971.429368]: nmin=1236915
[INFO] [1540538982.689602]: scli stable test result: setup speed=800, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=1.252875
[INFO] [1540538982.746419]: nmean=2886959
[INFO] [1540538982.784445]: nmax=10091781
[INFO] [1540538982.805442]: nmin=1202107
=> python 應該會 buffer 住,等 serial 有空才發
CLI>help scli_maxstablerate_search
using binary search to find the max stable rate
max rate should setup a rate that can't reach
scli_maxstablerate_search [max] [min] [step] [count]
ex: scli_maxstablerate_search 1000 100 50 1000
CLI>scli_maxstablerate_search 1000 100 10 5000
[INFO] [1540555555.498076]: Using search setting max=1000,min=100,step=10,count=5000
[INFO] [1540555606.496119]: scli stable test result: setup speed=100, count=5000
result pub_cnt=5000,sub_cnt=5000,receive rate=1.000000,duration seconds=49.990950
[INFO] [1540555606.499119]: PASS rate: 100
[INFO] [1540555616.595341]: scli stable test result: setup speed=550, count=5000
result pub_cnt=5000,sub_cnt=3481,receive rate=0.696200,duration seconds=9.089382
[INFO] [1540555616.596948]: FAIL rate: 550
[INFO] [1540555643.234688]: scli stable test result: setup speed=320, count=5000
result pub_cnt=5000,sub_cnt=5000,receive rate=1.000000,duration seconds=15.622209
[INFO] [1540555643.236382]: PASS rate: 320
[INFO] [1540555655.866656]: scli stable test result: setup speed=430, count=5000
result pub_cnt=5000,sub_cnt=4358,receive rate=0.871600,duration seconds=11.625571
[INFO] [1540555655.868283]: FAIL rate: 430
[INFO] [1540555680.394007]: scli stable test result: setup speed=370, count=5000
result pub_cnt=5000,sub_cnt=4971,receive rate=0.994200,duration seconds=13.511161
[INFO] [1540555680.395300]: FAIL rate: 370
[INFO] [1540555706.163217]: scli stable test result: setup speed=340, count=5000
result pub_cnt=5000,sub_cnt=5000,receive rate=1.000000,duration seconds=14.751231
[INFO] [1540555706.165877]: PASS rate: 340
[INFO] [1540555721.456265]: scli stable test result: setup speed=350, count=5000
result pub_cnt=5000,sub_cnt=5000,receive rate=1.000000,duration seconds=14.283161
[INFO] [1540555721.458819]: PASS rate: 350
[INFO] [1540555736.352474]: scli stable test result: setup speed=360, count=5000
result pub_cnt=5000,sub_cnt=5000,receive rate=1.000000,duration seconds=13.886556
[INFO] [1540555736.353864]: PASS rate: 360
[INFO] [1540555736.355192]: maxstablerate_search result rate=360
CLI>scli_stabletest_range 100 900 100 1000
[INFO] [1540556153.765125]: test setting: cli_test_rxtimeout=1
[INFO] [1540556164.760271]: scli stable test result: setup speed=100, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=9.990790
[INFO] [1540556164.817523]: mean=9998558
[INFO] [1540556164.854896]: max=19767046
[INFO] [1540556164.891151]: min=3890038
[INFO] [1540556165.034792]: median=9967088
[INFO] [1540556165.062243]: ptp=15877008
[INFO] [1540556171.061709]: scli stable test result: setup speed=200, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=4.995793
[INFO] [1540556171.117936]: mean=5000111
[INFO] [1540556171.154139]: max=8756160
[INFO] [1540556171.190839]: min=2407789
[INFO] [1540556171.329094]: median=4585028
[INFO] [1540556171.356906]: ptp=6348371
[INFO] [1540556175.690879]: scli stable test result: setup speed=300, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=3.330442
[INFO] [1540556175.747373]: mean=3337106
[INFO] [1540556175.784148]: max=6985187
[INFO] [1540556175.805271]: min=936985
[INFO] [1540556175.950509]: median=3539086
[INFO] [1540556175.978657]: ptp=6048202
[INFO] [1540556179.480011]: scli stable test result: setup speed=400, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=2.498162
[INFO] [1540556179.508287]: mean=2894584
[INFO] [1540556179.526670]: max=8114814
[INFO] [1540556179.545010]: min=1231909
[INFO] [1540556179.700374]: median=2844810
[INFO] [1540556179.729478]: ptp=6882905
[INFO] [1540556182.730406]: scli stable test result: setup speed=500, count=1000
result pub_cnt=1000,sub_cnt=1000,receive rate=1.000000,duration seconds=1.998443
[INFO] [1540556182.758347]: mean=2889060
[INFO] [1540556182.776784]: max=8728027
[INFO] [1540556182.795131]: min=1274109
[INFO] [1540556182.937312]: median=2856016
[INFO] [1540556182.965425]: ptp=7453918
[INFO] [1540556185.639317]: scli stable test result: setup speed=600, count=1000
result pub_cnt=1000,sub_cnt=917,receive rate=0.917000,duration seconds=1.670845
[INFO] [1540556185.665966]: mean=2905608
[INFO] [1540556185.683958]: max=83289147
[INFO] [1540556185.715491]: min=1252174
[INFO] [1540556185.893198]: median=2574920
[INFO] [1540556185.918673]: ptp=82036973
[INFO] [1540556188.352474]: scli stable test result: setup speed=700, count=1000
result pub_cnt=1000,sub_cnt=836,receive rate=0.836000,duration seconds=1.430536
[INFO] [1540556188.377103]: mean=2899422
[INFO] [1540556188.393774]: max=10576010
[INFO] [1540556188.410335]: min=1226902
[INFO] [1540556188.534095]: median=2763033
[INFO] [1540556188.559752]: ptp=9349108
[INFO] [1540556190.812582]: scli stable test result: setup speed=800, count=1000
result pub_cnt=1000,sub_cnt=776,receive rate=0.776000,duration seconds=1.249059
[INFO] [1540556190.835350]: mean=2899322
[INFO] [1540556190.851192]: max=11769056
[INFO] [1540556190.866509]: min=638008
[INFO] [1540556190.982909]: median=2804041
[INFO] [1540556191.006135]: ptp=11131048
留言
張貼留言