【RTK21】Base-Rover間RTCM通信をESP32経由トライ<不安定でNGだった>

MovingBaseモードのRover-Base間をUDP無線通信で結ぶため、
MovingBaseのRTCMデータのパケットのサイズと周期を実測しました。
UDP通信の基礎実験はこちらでやりました。

●実験方法と結果

Base-Rover間 結果
実験1 BaseのSimpleRTK2B liteとRoverのSimpleRTK2Bを

シールド線接続(シールドは片GND配線)
速度:460800bps

OK
2dAcc=1cmでFIX
実験2 Base-Rover間にESP32をいれて
ESP32のSerial2でBaseから受信してSerial1でRoverへ送信する
速度 460800bps
1度めはOKだったが、後日やると全然RTKができなかったのでNGだった

loopにSerial.printなどの道草をつけるとNGになるvoid loop() {
if (Serial2.available()) {
uint8_t inByte = Serial2.read();
Serial1.write(inByte);
}

●実験2でSerial.printが入ると通信がNGになる現象を解析
if文内でdigitalWrite(2, HIGH);をいれてオンにして
if文出たところでdigitalWrite(2, LOW);でオフにする信号を作成
オシロにつないで、通信実験した。
1:RTK周期125msecで送信の塊がでているが一部離れてばらつく部分がある。
2:送信の塊の幅は30msecの塊と50msecの塊に2分割されて送信されている

●下図をみると30msecの塊を拡大すると300nsec幅でif文を1回通過して次に10μsec後に2回目を通過している。460800bps周期は2.6μsecなのでオシロの1目盛くらいの周期になりますが、CPUループ速くて300nsecで回っていて、シリアルのバッファで保持しながら送信しているのではないかと思います。
●if文を出たところでSerialPrintをいれてNGになった原因
1Bytex10μsecだと1000Byteだと10msecで送信する速度になる。この速度を守らないとRoverが受信できないので、if文から出たところで、Serial.printをいれたら数msec食うのでデータ通信がNGになるということが理解できます。

=>そこで、データ送信の塊を認識して、送信が終わったところでSerialPrintをいれいれば100msec程度余裕があるのでいろいろな仕事ができるので、塊を認識するアルゴリズムを作りました。

 

 

●RTCM通信の塊を認識するプログラム
if文内の時刻tinを測定記録しておく
if文外で時刻toutを測定してtout-tin>50msecならRTCMデータの
塊の送信が終わった状態と認識するアルゴリズムにしてみた。

int n;
int tin,tout;void setup()
{
Serial.begin(460800);
Serial1.begin(460800, SERIAL_8N1,19, 27);//GPIO19:RX ,GPIO27:TX
Serial2.begin(460800, SERIAL_8N1,16, 17);//GPIO16:RX ,GPIO17:TX
n=0;
}void loop()
{
if (Serial2.available())
{
uint8_t inByte = Serial2.read();
Serial1.write(inByte);
tin=millis();
n++;
}tout=millis();
if(tout-tin>50 && n>0)
{
Serial.print(n);
Serial.print(“,”);
Serial.println(millis());
n=0;
}}

 このプログラムで実際にRTK MovingBaseモードを稼働させながら
1塊のデータ数と塊間の周期を測定しました。
①tout-tin>30msecとした場合
30msecで切った場合は、データ数のばらつきが大きいのでデータの塊の途中 切ってしまっているので30msecだと短すぎる。
RTKデータも収束が遅い感じがした。

49801 データ数 周期
average 827.3 112
3sigma 728.1 84.07

②tout-tin>50msecとした場合
50msecで切った場合は、データ数のばらつきも10%以内で周期が125msec丁度でているので、OKであった。
RTKデータも収束も有線直接接続と同じ収束状態であった。

6575 データ数 周期
average 912.622 124.999
3sigma 90.2858 12.0802

●結果
ESP32でシリアル受信してそのままシリアル送信する方法でRTCMが接続できたり
できなかったりする現象があるのでそこを解析していかないと無線接続には行きつきませんので
ロジアナで解析を進めていきます。はまったので数カ月かかるかもしれません。

MovingBaseモードでBaseから送信されるRTCMデータは
912Byte±90Byteで50msec内に送信されている。
周期は、RTKの指定周期で125msecなので、空き時間が75msec程度存在する。

●以後
if文から抜けたあと50msec空き時間が経過したら次の動作に
入ることにする。次の動作としては、UDPを使った無線で
RoverのESP32へ無線送信する実験に移ります。
※その後ロジアナでBase信号をデコードしてみました。
順序と長さのばらつきが目に見えて解析できました。

【RTK21】RTKの無線化その2<Base出力をロジアナで見た>

 

コメントを残す

メールアドレスが公開されることはありません。 が付いている欄は必須項目です