Skip to content

Feature/ros2 ntrip rate control#56

Open
pondersome wants to merge 4 commits intoLORD-MicroStrain:ros2from
pondersome:feature/ros2_ntrip_rate_control
Open

Feature/ros2 ntrip rate control#56
pondersome wants to merge 4 commits intoLORD-MicroStrain:ros2from
pondersome:feature/ros2_ntrip_rate_control

Conversation

@pondersome
Copy link
Copy Markdown

This addresses SNIP sandboxing fix #55

Allows compliance with NTRIP servers with limits on how often communication is allowed.

New parameter  ntrip_server_hz sets the rate at which this client requests rtcm data from the server. defaults to the previous hard-coded 10hz, but  should be set to 1hz  for rtk2go.com

NMEA sentences are  cached and the latest one sent at the same time the rtcm data is requested.
Copy link
Copy Markdown
Contributor

@robbiefish robbiefish left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sorry this took me so long to get to. This looks like a very useful feature to have

@@ -15,8 +15,9 @@ def generate_launch_description():
DeclareLaunchArgument('port', default_value='2101'),
DeclareLaunchArgument('mountpoint', default_value='VTRI_RTCM3'),
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I like that you added an example of overriding in the README with rtk2go information. I think that would be the right thing to have in here as well. Can you update host, mountpoint, username, and password?

Comment thread scripts/ntrip_ros.py
self._rtcm_pub = self.create_publisher(self._rtcm_message_type, 'rtcm', 10)

# Setup a server frequency confirmation publisher
self._rate_confirm_pub = self.create_publisher(String, 'ntrip_server_hz', 10)
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this publisher should be removed.

Comment thread scripts/ntrip_ros.py
# Publish a confirmation message to indicate the send_rtcm_and_nmea call
confirmation_msg = String()
confirmation_msg.data = "RTCM request and NMEA receive set at rate: {} Hz".format(1.0 / self.rtcm_request_rate)
self._rate_confirm_pub.publish(confirmation_msg)
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same as above. I would be okay having this as a debug log, but would rather not have an extra string publisher

DEFAULT_RECONNECT_ATTEMPT_MAX = 10
DEFAULT_RECONNECT_ATEMPT_WAIT_SECONDS = 5
DEFAULT_RTCM_TIMEOUT_SECONDS = 4
DEFAULT_RECONNECT_ATEMPT_WAIT_SECONDS = 10 #was 5 - changed for rtk2go reqs
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These new defaults seem reasonable. The comment can be removed

time.sleep(self.reconnect_attempt_wait_seconds)
elif self._reconnect_attempt_count >= self.reconnect_attempt_max:
self._reconnect_attempt_count = 0
# self._reconnect_attempt_count = 0 #this hides the retry count from the excepton?
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yup this was a mistake. Just put this after the log, and that should be fine.

Realistically, it is probably fine to just not set it, but the ntrip_client.py is meant to be agnostic of how ROS runs it, so it is possible that someone could catch that exception and want the value to be updated properly

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants