必要なもの
- ubuntu22.04LTS + ROS2 Humbleインストール済みのPC
- ZED-F9P の基板 (USB出力できれば何でもよい)
- アンテナ、アンテナケーブル
F9P基板とPCがUSBケーブルでつながっている状態で、単独測位で移動局として動かしているとする。
u-center の設定
具体的な設定方法についてはこの記事では省略。
以下書籍や記事などを参照のこと。
USB出力をNMEA出力できるように設定しGxGGAとGxRMCをUSB出力できれば、以下の手順でNavSatFixは取得できる。
Baud Rateはとりあえず230400
に設定。
ublox ros2 パッケージのインストール
いくつかgithubにZED-F9PのROS2パッケージがある中でこちらを採用
mkdir -p ~/gnss_ws/src
cd ~/gnss_ws/src
git clone -b ros2 https://github.com/KumarRobotics/ublox/tree/master
cd ~/gnss_ws/rosdep install --from-paths src --ignore-src -r -y
colcon build --symlink-install
CMake Error at /usr/share/cmake-3.22/Modules/FindPackageHandleStandardArgs.cmake:230 (message):
Could NOT find asio (missing: ASIO_INCLUDE_DIR)
Call Stack (most recent call first):
/usr/share/cmake-3.22/Modules/FindPackageHandleStandardArgs.cmake:594 (_FPHSA_FAILURE_MESSAGE)
cmake/Findasio.cmake:4 (find_package_handle_standard_args)
CMakeLists.txt:16 (find_package)
このエラーがでたらlibasio-devをインストールして再度colcon build
sudo apt-get install libasio-dev
=========================
追記:
普通にaptからインストールできました。
sudo apt install ros-humble-ublox
実行
設定ファイルの変更
ublox_gps/config/zed_f9p.yamlの編集
-
device
とbaudrate
を変更する。 -
config_on_startup: false
を追加する。
デフォルトではconfig_on_startupがtrueとなっており、ZED-F9P側の設定を書き換えた状態で動いてしまうので
u-centerで設定した状態で動かしたい時はfalseにしておく。
ZED-F9P最初に接続した時のdevice名は/dev/ttyACM0となっている。
# Configuration Settings for C94-M8P device
ublox_gps_node:
ros__parameters:
debug: 0 # Range 0-4 (0 means no debug statements will print)
device: /dev/ttyACM0
frame_id: gps
config_on_startup: false
uart1:
baudrate: 230400
# TMODE3 Config
tmode3: 1 # Survey-In Mode
sv_in:
reset: True # True: disables and re-enables survey-in (resets)
# False: Disables survey-in only if TMODE3 is
# disabled
min_dur: 300 # Survey-In Minimum Duration [s]
acc_lim: 3.0 # Survey-In Accuracy Limit [m]
inf:
all: true # Whether to display all INF messages in console
publish:
all: true
aid:
hui: false
nav:
posecef: false
launch ファイルの変更
ublox_gps/launch/ublox_gps_node-launch.py
のparamsの設定ファイル名をzed_f9p.yaml
に変更する。
def generate_launch_description():
config_directory = os.path.join(
ament_index_python.packages.get_package_share_directory('ublox_gps'),
'config')
params = os.path.join(config_directory, 'zed_f9p.yaml')
実行
source ~/gnss_ws/install/setup.bash
ros2 launch ublox_gps ublox_gps_node-launch.py
topic 一覧
$ ros2 topic list -t
/aidalm [ublox_msgs/msg/AidALM]
/aideph [ublox_msgs/msg/AidEPH]
/diagnostics [diagnostic_msgs/msg/DiagnosticArray]
/monhw [ublox_msgs/msg/MonHW]
/navclock [ublox_msgs/msg/NavCLOCK]
/navcov [ublox_msgs/msg/NavCOV]
/navheading [sensor_msgs/msg/Imu]
/navrelposned [ublox_msgs/msg/NavRELPOSNED9]
/navstate [ublox_msgs/msg/NavSAT]
/navstatus [ublox_msgs/msg/NavSTATUS]
/navsvin [ublox_msgs/msg/NavSVIN]
/nmea [nmea_msgs/msg/Sentence]
/parameter_events [rcl_interfaces/msg/ParameterEvent]
/rosout [rcl_interfaces/msg/Log]
/rtcm [rtcm_msgs/msg/Message]
/rxmrtcm [ublox_msgs/msg/RxmRTCM]
/ublox_gps_node/fix [sensor_msgs/msg/NavSatFix]
/ublox_gps_node/fix_velocity [geometry_msgs/msg/TwistWithCovarianceStamped]
/ublox_gps_node/navpvt [ublox_msgs/msg/NavPVT]
Nodeの情報
$ ros2 node info /ublox_gps_node
/ublox_gps_node
Subscribers:
/parameter_events: rcl_interfaces/msg/ParameterEvent
/rtcm: rtcm_msgs/msg/Message
Publishers:
/aidalm: ublox_msgs/msg/AidALM
/aideph: ublox_msgs/msg/AidEPH
/diagnostics: diagnostic_msgs/msg/DiagnosticArray
/monhw: ublox_msgs/msg/MonHW
/navclock: ublox_msgs/msg/NavCLOCK
/navcov: ublox_msgs/msg/NavCOV
/navheading: sensor_msgs/msg/Imu
/navrelposned: ublox_msgs/msg/NavRELPOSNED9
/navstate: ublox_msgs/msg/NavSAT
/navstatus: ublox_msgs/msg/NavSTATUS
/navsvin: ublox_msgs/msg/NavSVIN
/nmea: nmea_msgs/msg/Sentence
/parameter_events: rcl_interfaces/msg/ParameterEvent
/rosout: rcl_interfaces/msg/Log
/rxmrtcm: ublox_msgs/msg/RxmRTCM
/ublox_gps_node/fix: sensor_msgs/msg/NavSatFix
/ublox_gps_node/fix_velocity: geometry_msgs/msg/TwistWithCovarianceStamped
/ublox_gps_node/navpvt: ublox_msgs/msg/NavPVT
Service Servers:
/ublox_gps_node/describe_parameters: rcl_interfaces/srv/DescribeParameters
/ublox_gps_node/get_parameter_types: rcl_interfaces/srv/GetParameterTypes
/ublox_gps_node/get_parameters: rcl_interfaces/srv/GetParameters
/ublox_gps_node/list_parameters: rcl_interfaces/srv/ListParameters
/ublox_gps_node/set_parameters: rcl_interfaces/srv/SetParameters
/ublox_gps_node/set_parameters_atomically: rcl_interfaces/srv/SetParametersAtomically
Service Clients:
Action Servers:
Action Clients:
NavSatFixを見る。
ros2 topic echo /ublox_gps_node/fix
おわりに
ZED-F9Pを単独測位で移動局として動かし最新のROS2環境でNavSatFixを取得することができた。
参考