Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ROS2 Adds ability to publish an rtcm_msgs Message instead of a mavros_msgs RTCM #21

Merged
merged 2 commits into from
Aug 17, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 16 additions & 12 deletions launch/ntrip_client_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,18 +8,19 @@
def generate_launch_description():
return LaunchDescription([
# Declare arguments with default values
DeclareLaunchArgument('host', default_value='20.185.11.35'),
DeclareLaunchArgument('port', default_value='2101'),
DeclareLaunchArgument('mountpoint', default_value='VTRI_RTCM3'),
DeclareLaunchArgument('ntrip_version', default_value='None'),
DeclareLaunchArgument('authenticate', default_value='True'),
DeclareLaunchArgument('username', default_value='user'),
DeclareLaunchArgument('password', default_value='pass'),
DeclareLaunchArgument('ssl', default_value='False'),
DeclareLaunchArgument('cert', default_value='None'),
DeclareLaunchArgument('key', default_value='None'),
DeclareLaunchArgument('ca_cert', default_value='None'),
DeclareLaunchArgument('debug', default_value='false'),
DeclareLaunchArgument('host', default_value='20.185.11.35'),
DeclareLaunchArgument('port', default_value='2101'),
DeclareLaunchArgument('mountpoint', default_value='VTRI_RTCM3'),
DeclareLaunchArgument('ntrip_version', default_value='None'),
DeclareLaunchArgument('authenticate', default_value='True'),
DeclareLaunchArgument('username', default_value='user'),
DeclareLaunchArgument('password', default_value='pass'),
DeclareLaunchArgument('ssl', default_value='False'),
DeclareLaunchArgument('cert', default_value='None'),
DeclareLaunchArgument('key', default_value='None'),
DeclareLaunchArgument('ca_cert', default_value='None'),
DeclareLaunchArgument('debug', default_value='false'),
DeclareLaunchArgument('rtcm_message_package', default_value='mavros_msgs'),

# Pass an environment variable to the node
SetEnvironmentVariable(name='NTRIP_CLIENT_DEBUG', value=LaunchConfiguration('debug')),
Expand Down Expand Up @@ -62,6 +63,9 @@ def generate_launch_description():
# Not sure if this will be looked at by other ndoes, but this frame ID will be added to the RTCM messages published by this node
'rtcm_frame_id': 'odom',

# Use this parameter to change the type of RTCM message published by the node. Defaults to "mavros_msgs", but we also support "rtcm_msgs"
'rtcm_message_package': LaunchConfiguration('rtcm_message_package'),

# Will affect how many times the node will attempt to reconnect before exiting, and how long it will wait in between attempts when a reconnect occurs
'reconnect_attempt_max': 10,
'reconnect_attempt_wait_seconds': 5,
Expand Down
59 changes: 50 additions & 9 deletions scripts/ntrip_ros.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,26 @@
import os
import sys
import json
import importlib.util

import rclpy
from rclpy.node import Node
from std_msgs.msg import Header
from mavros_msgs.msg import RTCM
from nmea_msgs.msg import Sentence

from ntrip_client.ntrip_client import NTRIPClient

# Try to import a couple different types of RTCM messages
_MAVROS_MSGS_NAME = "mavros_msgs"
_RTCM_MSGS_NAME = "rtcm_msgs"
have_mavros_msgs = False
have_rtcm_msgs = False
if importlib.util.find_spec(_MAVROS_MSGS_NAME) is not None:
have_mavros_msgs = True
from mavros_msgs.msg import RTCM as mavros_msgs_RTCM
if importlib.util.find_spec(_RTCM_MSGS_NAME) is not None:
have_rtcm_msgs = True
from rtcm_msgs.msg import Message as rtcm_msgs_RTCM

class NTRIPRos(Node):
def __init__(self):
Expand All @@ -38,6 +49,7 @@ def __init__(self):
('key', 'None'),
('ca_cert', 'None'),
('rtcm_frame_id', 'odom'),
('rtcm_message_package', _MAVROS_MSGS_NAME),
('reconnect_attempt_max', NTRIPClient.DEFAULT_RECONNECT_ATTEMPT_MAX),
('reconnect_attempt_wait_seconds', NTRIPClient.DEFAULT_RECONNECT_ATEMPT_WAIT_SECONDS),
('rtcm_timeout_seconds', NTRIPClient.DEFAULT_RTCM_TIMEOUT_SECONDS),
Expand Down Expand Up @@ -76,8 +88,26 @@ def __init__(self):
# Read an optional Frame ID from the config
self._rtcm_frame_id = self.get_parameter('rtcm_frame_id').value

# Determine the type of RTCM message that will be published
rtcm_message_package = self.get_parameter('rtcm_message_package').value
if rtcm_message_package == _MAVROS_MSGS_NAME:
if have_mavros_msgs:
self._rtcm_message_type = mavros_msgs_RTCM
self._create_rtcm_message = self._create_mavros_msgs_rtcm_message
else:
self.get_logger().fatal('The requested RTCM package {} is a valid option, but we were unable to import it. Please make sure you have it installed'.format(rtcm_message_package))
elif rtcm_message_package == _RTCM_MSGS_NAME:
if have_rtcm_msgs:
self._rtcm_message_type = rtcm_msgs_RTCM
self._create_rtcm_message = self._create_rtcm_msgs_rtcm_message
else:
self.get_logger().fatal('The requested RTCM package {} is a valid option, but we were unable to import it. Please make sure you have it installed'.format(rtcm_message_package))
else:
self.get_logger().fatal('The RTCM package {} is not a valid option. Please choose between the following packages {}'.format(rtcm_message_package, ','.join([_MAVROS_MSGS_NAME, _RTCM_MSGS_NAME])))


# Setup the RTCM publisher
self._rtcm_pub = self.create_publisher(RTCM, 'rtcm', 10)
self._rtcm_pub = self.create_publisher(self._rtcm_message_type, 'rtcm', 10)

# Initialize the client
self._client = NTRIPClient(
Expand Down Expand Up @@ -138,14 +168,25 @@ def subscribe_nmea(self, nmea):

def publish_rtcm(self):
for raw_rtcm in self._client.recv_rtcm():
self._rtcm_pub.publish(RTCM(
header=Header(
stamp=self.get_clock().now().to_msg(),
frame_id=self._rtcm_frame_id
),
data=raw_rtcm
))
self._rtcm_pub.publish(self._create_rtcm_message(raw_rtcm))

def _create_mavros_msgs_rtcm_message(self, rtcm):
return mavros_msgs_RTCM(
header=Header(
stamp=self.get_clock().now().to_msg(),
frame_id=self._rtcm_frame_id
),
data=rtcm
)

def _create_rtcm_msgs_rtcm_message(self, rtcm):
return rtcm_msgs_RTCM(
header=Header(
stamp=self.get_clock().now().to_msg(),
frame_id=self._rtcm_frame_id
),
message=rtcm
)

if __name__ == '__main__':
# Start the node
Expand Down