Ublox ZED-F9P RTK-GNSS 移動局を ROS で使用


通常、UbloxのRTK-GNSSがu-center、RTKLIBで使用していますが、今回ROSで使用するように試しました。

使用環境

  • Ubuntu 18.04
  • Qt Creator 4.12.4
  • QT 5.12.5 GCC 64bit
  • RTKLIB 2.4.3 b33
  • ROS Melodic
  • Ublox ZED-F9P (GNSS受信器)
  • Ntripサーバー (www.rtk2go.com)

使用パッケージ

Ntripサーバーから基準局情報を取得してUblox ZED-F9Pの移動局に入力する。

Ublox ZED-F9PのRTK-GNSS Fix解をシリアルポートから取得してROS Topic sensor_msgs/NavSatFix で発信。

1. RTKLIBを使って基準局情報をUblox ZED-F9Pの移動局に入力

  • RTKLIBからソースをダウンロードしてビルド

RTKLIB 2.4.3 b33

git clone -b rtklib_2.4.3 https://github.com/tomojitakasu/RTKLIB.git
cd RTKLIB/lib/iers/gcc/
make   
cd RTKLIB/app/consapp
make  

注:RTKLIB GUI版のインストールは、RTKLIB 2.4.3 CLI版 GUI版 をUbuntu18.04にインストール参考します。

  • Ntripサーバーから基準局情報を取得してUblox ZED-F9Pの移動局のserial portに入力

Ublox ZED-F9PはRTK測位演算エンジンを内蔵したので、基準局情報を入力すると、RTK測位を行います。

cd str2str/gcc
./str2str -in ntrip://rtk2go.com:2101/[基準局のMountPoint] -out serial://ttyACM0:230400

str2str の実行ログ

stream server start
2020/08/15 12:27:23 [WC---]          0 B       0 bps (0) connecting... (1) /dev/ttyACM0 
2020/08/15 12:27:28 [CC---]       3297 B    6527 bps (0) rtk2go.com/[基準局のMountPoint] (1) /dev/ttyACM0

ttyACM0: PCに挿した移動局ZED-F9Pのシリアルポート
230400: u-centerで移動局ZED-F9Pのserial baud rateの設定値

(注:RTKLIB GUI版のSTRSVR-QTでも同じ機能を実行できます。)

2. ublox ROS packageで移動局RTK演算結果をROS Topicで発信

  • RTKLIBからソースをダウンロードしてビルド

ublox ROSパッケージ

cd <catkin_ws>/src
git clone https://github.com/KumarRobotics/ublox.git
cd ../
catkin_make
  • ublox ROSパッケージのパラメータファイルを生成

ublox/ublox_gps/config/zed_f9p_rover.yamlを以下のように生成します。

# Configuration Settings for ZED-F9P device
debug: 1                 # Range 0-4 (0 means no debug statements will print)

device: /dev/ttyACM0     # ZED-F9P rover serial port
frame_id: gps

config_on_startup: false # use chip config

uart1:
  baudrate: 230400       # serial port baudrate
  in: 32
  out: 3

# Enable u-blox message publishers
publish:
  all: false
  nav:
    all: true
    relposned: true
    posllh: true
    posecef: true

config_on_startupにtrueを設定した場合、ROSパッケージのRTK-GNSS設定でZED-F9Pチップ設定が上書きされるので、解析Fix解が得られない可能性があります。

  • ublox ROSパッケージの起動
roslaunch ublox_gps ublox_device.launch node_name:=ublox param_file_name:=zed_f9p_rover

roslaunch の実行ログ

SUMMARY
========

CLEAR PARAMETERS
 * /ublox/

PARAMETERS
 * /rosdistro: melodic
 * /rosversion: 1.14.3
 * /ublox/config_on_startup: False
 * /ublox/debug: 1
 * /ublox/device: /dev/ttyACM0
 * /ublox/frame_id: gps
 * /ublox/publish/all: False
 * /ublox/publish/nav/all: True
 * /ublox/publish/nav/posecef: True
 * /ublox/publish/nav/posllh: True
 * /ublox/publish/nav/relposned: True
 * /ublox/uart1/baudrate: 230400
 * /ublox/uart1/in: 32
 * /ublox/uart1/out: 3

NODES
  /
    ublox (ublox_gps/ublox_gps)

auto-starting new master
process[master]: started with pid [7994]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 9536ba60-def3-11ea-b404-60f81dc512a8
process[rosout-1]: started with pid [8005]
started core service [/rosout]
process[ublox-2]: started with pid [8009]
[ INFO] [1597494836.219074203]: U-Blox: Opened serial port /dev/ttyACM0
[DEBUG] [1597494836.219916723]: U-Blox: current_baudrate 230400
[DEBUG] [1597494836.220839605]: EXT CORE 1.00 (61b2dd), HW VER: 00190000
[DEBUG] [1597494836.220867963]: ROM BASE 0x118B2060
[DEBUG] [1597494836.220893785]: FWVER=HPG 1.12
[DEBUG] [1597494836.220917198]: PROTVER=27.11
[DEBUG] [1597494836.220937605]: MOD=ZED-F9P
[DEBUG] [1597494836.220956464]: GPS;GLO;GAL;BDS
[DEBUG] [1597494836.220976395]: QZSS
[ INFO] [1597494836.221016654]: U-Blox Firmware Version: 9
[ INFO] [1597494836.225839094]: U-Blox configured successfully.
[DEBUG] [1597494836.225872645]: Subscribing to U-Blox messages
[DEBUG] [1597494836.237840788]: Configuring INF messages
[ WARN] [1597494837.616917996]: INF: DGNSS long baseline (62 km)

Ros Topic /ublox/fix (sensor_msgs/NavSatFix) ログ

$ rostopic echo /ublox/fix

---
header: 
  seq: 250
  stamp: 
    secs: 1597544202
    nsecs:     13159
  frame_id: "gps"
status: 
  status: 2
  service: 1
latitude: XX.6383066
longitude: XXX.0486526
altitude: 46.18
position_covariance: [0.002209, 0.0, 0.0, 0.0, 0.002209, 0.0, 0.0, 0.0, 0.0047610000000000005]
position_covariance_type: 2
---

status.status = 2 は、基準局を基づいて解析Fix解が得られています。

sensor_msgs/NavSatStatusの定義:

# fix is valid when status >= STATUS_FIX.

int8 STATUS_NO_FIX =  -1        # unable to fix position
int8 STATUS_FIX =      0        # unaugmented fix
int8 STATUS_SBAS_FIX = 1        # with satellite-based augmentation
int8 STATUS_GBAS_FIX = 2        # with ground-based augmentation

GoogleMAPで/ublox/fixの表示確認は、
RTK-GNSSのNavSatFixデータをGoogleMAPでリアルタイム表示を参考します。