はじめに
2018年11月1日、日本の衛星測位システム「みちびき」の運用が開始されました(記事)。
このニュースで精度の高い衛星測位ができると知った人も多いんじゃないかと思います。
この記事ではこのような精度の高い衛星測位システムをROSで使えるようにする方法を紹介します。
RTK-GNSSって何?って人はこことかこことか見ると簡単な説明が載ってます。
使用環境
以下が今回使用した開発環境です。
PC | lenovo ThinkPad X250 |
---|---|
CPU | Intel Core i7-5600U |
RAM | 4GB |
OS | Ubuntu 16.04 |
Kernel | 4.15 |
ROS | ROS Kinetic |
GNSS受信器 | Ublox c94-m8p |
---|---|
アンテナ | 付属品のアンテナ |
移動局 | 手元のm8p |
基準局 | Ntripサーバー(www.rtk2go.com) |
利用するパッケージ
リンクはそれぞれのGithubになってます。
-
KumarRobotics/Ublox
今回の主役。Ublox社製のGNSS受信器のためのROSパッケージ。このパッケージだけでRTKを行う事も可能。 -
RTKLIB
RTK-GNSSをやろうとすると必ずお世話になるライブラリ、アプリケーション群。今回はNtripサーバーから基準局情報を取得するために利用。
利用方法
簡単な手順としては
- RTKLIBの
str2str
を利用してRTK2GO
より付近の基準局情報を取得し,M8Pに送信する - M8Pを移動局モードで起動する
の2つです。
ただ、前提としてモバイルルータなどでグローバルネットに接続できているものとします。
1.RTKLIBを使って基準局情報を取得する
まずはRTKLIBからソースをダウンロードしてビルドします。
今回必要なのはstr2str
のみですが全てビルドするスクリプトが用意してあるので利用します。
git clone https://github.com/tomojitakasu/RTKLIB.git
cd RTKLIB/app
source makeall.sh
cd str2str/gcc
これでNtripサーバから基準局情報を取得する準備ができました。
後は以下のコマンドを入力すれば基準局情報を取得することが出来ます。
./str2str -in ntrip://[任意の基準局アドレス] -out serial://[m8pがついているポート]
仮に筑波大学の基準局とttyACM0
接続されているm8pを利用するとすると
./str2str -in ntrip://www.rtk2go.com/TSUKUBA-RTCM3 -out serial://ttyACM0
のようになります。
2.C94-M8Pを移動局として利用する
まずはROSパッケージをダウンロードしてビルドします。
cd <catkin_ws>/src
git clone https://github.com/KumarRobotics/ublox.git
cd ../
catkin_make
次にパラメータファイルを編集します。
ublox/ublox_gps/config/c94_m8p_rover.yaml
を以下のように編集します。
# Configuration Settings for C94-M8P device
debug: 1 # Range 0-4 (0 means no debug statements will print)
save:
mask: 3103 # Save I/O, Message, INF Message, Nav, Receiver
# Manager, Antenna, and Logging Configuration
device: 4 # Save to EEPROM
device: /dev/ttyACM0 #M8Pを挿しているポートを選択しましょう。
frame_id: gps
rate: 4 # in Hz
nav_rate: 4 # [# of measurement cycles], recommended 1 Hz, may
# be either 5 Hz (Dual constellation) or
# 8 Hz (GPS only)
dynamic_model: airborne2 # Airborne < 2G, 2D fix not supported (3D only),
# Max Alt: 50km
# Max Horizontal Velocity: 250 m/s,
# Max Vertical Velocity: 100 m/s
fix_mode: auto
enable_ppp: false # Not supported by C94-M8P
dr_limit: 0
uart1:
baudrate: 19200 # C94-M8P specific
in: 32 # RTCM 3 ここは取得する基準局情報のフォーマットに合わせます
out: 0 # No UART out for rover
gnss:
glonass: true # Supported by C94-M8P
beidou: false # 使用するGNSSを選択します。割とお好みで大丈夫ですが
qzss: false # 衛星数が多いのはbeidou、国産はqzssです。
dgnss_mode: 3 # Fixed mode
inf:
all: true # Whether to display all INF messages in console
# Enable u-blox message publishers
publish:
all: true
aid:
hui: false
nav:
posecef: false
# TMODE3 Config
tmode3: 1 # Survey-In Mode
sv_in:
reset: false # True: disables and re-enables survey-in (resets)
# False: Disables survey-in only if TMODE3 is
# disabled
min_dur: 300 # 計測する時間[s]です。十分な長さにします。
acc_lim: 3.0 # Survey-In Accuracy Limit [m]
ここまで来たら後は簡単です。
str2str
で基準局情報を取得している状態で、別端末を開いて
source <catkin_ws>/devel/setup.bash
roslaunch ublox_gps ublox_device.launch node_name:=ublox param_file_name:=c94_m8p_rover
必要なものはこれで終わりです。
解析解が得られているかを確認するにはnavsatus
メッセージを確認します。
得られた解析解はfix
メッセージに出力されています。
最初は解析解が得られず、エラーメッセージが出力されることがありますが暫く放置していると解が得られてどんどん値が収束していくのがわかると思います。
以上、簡単ではありますがROSでRTK-GNSSを利用する手順でした。
必要なことがあればまた追記することがあると思います。