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

Prefer rtcm_msgs over mavros_msgs #34

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
2 changes: 1 addition & 1 deletion README.md
Expand Up @@ -46,7 +46,7 @@ Optional launch parameters:

This node currently only has two topics of interest:

* **/rtcm**: This node will publish the RTCM corrections received from the server to this topic as [RTCM messages](http://docs.ros.org/en/noetic/api/mavros_msgs/html/msg/RTCM.html). These messages can be consumed by nodes such as the [microstrain_inertial_driver](https://github.com/LORD-MicroStrain/microstrain_inertial)
* **/rtcm**: This node will publish the RTCM corrections received from the server to this topic as [RTCM messages](https://github.com/tilk/rtcm_msgs/tree/master). These messages can be consumed by nodes such as the [microstrain_inertial_driver](https://github.com/LORD-MicroStrain/microstrain_inertial)
* **/nmea**: This node will subscribe on this topic and receive [NMEA sentence messages](http://docs.ros.org/en/api/nmea_msgs/html/msg/Sentence.html) which it will forward to the NTRIP server. This is only needed when using a virtual NTRIP server

## Docker Integration
Expand Down
142 changes: 68 additions & 74 deletions launch/ntrip_client_launch.py
Expand Up @@ -5,82 +5,76 @@
from launch.substitutions import EnvironmentVariable
from launch.actions import SetEnvironmentVariable

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('rtcm_message_package', default_value='mavros_msgs'),

# Pass an environment variable to the node
SetEnvironmentVariable(name='NTRIP_CLIENT_DEBUG', value=LaunchConfiguration('debug')),

# ******************************************************************
# NTRIP Client Node
# ******************************************************************
Node(
name='ntrip_client_node',
namespace='ntrip_client',
package='ntrip_client',
executable='ntrip_ros.py',
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("rtcm_message_package", default_value="mavros_msgs"),
# Pass an environment variable to the node
SetEnvironmentVariable(
name="NTRIP_CLIENT_DEBUG", value=LaunchConfiguration("debug")
),
# ******************************************************************
# NTRIP Client Node
# ******************************************************************
Node(
name="ntrip_client_node",
namespace="ntrip_client",
package="ntrip_client",
executable="ntrip_ros.py",
parameters=[
{
# Required parameters used to connect to the NTRIP server
'host': LaunchConfiguration('host'),
'port': LaunchConfiguration('port'),
'mountpoint': LaunchConfiguration('mountpoint'),

# Optional parameter that will set the NTRIP version in the initial HTTP request to the NTRIP caster.
'ntrip_version': LaunchConfiguration('ntrip_version'),

# If this is set to true, we will read the username and password and attempt to authenticate. If not, we will attempt to connect unauthenticated
'authenticate': LaunchConfiguration('authenticate'),

# If authenticate is set the true, we will use these to authenticate with the server
'username': LaunchConfiguration('username'),
'password': LaunchConfiguration('password'),

# Whether to connect with SSL. cert, key, and ca_cert options will only take effect if this is true
'ssl': LaunchConfiguration('ssl'),

# If the NTRIP caster uses cert based authentication, you can specify the cert and keys to use with these options
'cert': LaunchConfiguration('cert'),
'key': LaunchConfiguration('key'),

# If the NTRIP caster uses self signed certs, or you need to use a different CA chain, specify the path to the file here
'ca_cert': LaunchConfiguration('ca_cert'),

# 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',

# Optional parameters that will allow for longer or shorter NMEA messages. Standard max length for NMEA is 82
'nmea_max_length': 82,
'nmea_min_length': 3,

# 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,

# How many seconds is acceptable in between receiving RTCM. If RTCM is not received for this duration, the node will attempt to reconnect
'rtcm_timeout_seconds': 4
}
{
# Required parameters used to connect to the NTRIP server
"host": LaunchConfiguration("host"),
"port": LaunchConfiguration("port"),
"mountpoint": LaunchConfiguration("mountpoint"),
# Optional parameter that will set the NTRIP version in the initial HTTP request to the NTRIP caster.
"ntrip_version": LaunchConfiguration("ntrip_version"),
# If this is set to true, we will read the username and password and attempt to authenticate. If not, we will attempt to connect unauthenticated
"authenticate": LaunchConfiguration("authenticate"),
# If authenticate is set the true, we will use these to authenticate with the server
"username": LaunchConfiguration("username"),
"password": LaunchConfiguration("password"),
# Whether to connect with SSL. cert, key, and ca_cert options will only take effect if this is true
"ssl": LaunchConfiguration("ssl"),
# If the NTRIP caster uses cert based authentication, you can specify the cert and keys to use with these options
"cert": LaunchConfiguration("cert"),
"key": LaunchConfiguration("key"),
# If the NTRIP caster uses self signed certs, or you need to use a different CA chain, specify the path to the file here
"ca_cert": LaunchConfiguration("ca_cert"),
# 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",
# Optional parameters that will allow for longer or shorter NMEA messages. Standard max length for NMEA is 82
"nmea_max_length": 82,
"nmea_min_length": 3,
# 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,
# How many seconds is acceptable in between receiving RTCM. If RTCM is not received for this duration, the node will attempt to reconnect
"rtcm_timeout_seconds": 4,
}
],
# Uncomment the following section and replace "/gq7/nmea/sentence" with the topic you are sending NMEA on if it is not the one we requested
#remappings=[
# remappings=[
# ("/ntrip_client/nmea", "/gx5/nmea/sentence")
#],
)
])
# ],
),
]
)
2 changes: 1 addition & 1 deletion package.xml
Expand Up @@ -11,7 +11,7 @@

<depend>rclpy</depend>
<depend>std_msgs</depend>
<depend>mavros_msgs</depend>
<depend>rtcm_msgs</depend>
<depend>nmea_msgs</depend>

<!-- The export tag contains other, unspecified, tags -->
Expand Down