To resolve the socketcan interface dying due to can errors and failing to recover#474
Open
akashmod wants to merge 2 commits intoros-industrial:melodic-develfrom
Open
To resolve the socketcan interface dying due to can errors and failing to recover#474akashmod wants to merge 2 commits intoros-industrial:melodic-develfrom
akashmod wants to merge 2 commits intoros-industrial:melodic-develfrom
Conversation
hellantos
reviewed
Jan 19, 2023
| can_topic_ = nh->advertise<can_msgs::Frame>("received_messages", | ||
| nh_param->param("received_messages_queue_size", 10)); | ||
| driver_ = driver; | ||
| timer = nh->createTimer(ros::Duration(0.1), std::bind(&SocketCANToTopic::timerCallback, this, std::placeholders::_1)); |
Member
There was a problem hiding this comment.
This is a polling approach. We should at least be able to configure the duration via for example a ROS parameter. Also there should be an option to disable this behaviour.
There was a problem hiding this comment.
Perhaps by treating a zero duration as disabled. Zero is a common exception used for this and save a new parameter.
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment
Add this suggestion to a batch that can be applied as a single commit.This suggestion is invalid because no changes were made to the code.Suggestions cannot be applied while the pull request is closed.Suggestions cannot be applied while viewing a subset of changes.Only one suggestion per line can be applied in a batch.Add this suggestion to a batch that can be applied as a single commit.Applying suggestions on deleted lines is not supported.You must change the existing code in this line in order to create a valid suggestion.Outdated suggestions cannot be applied.This suggestion has been applied or marked resolved.Suggestions cannot be applied from pending reviews.Suggestions cannot be applied on multi-line comments.Suggestions cannot be applied while the pull request is queued to merge.Suggestion cannot be applied right now. Please check back later.
This is to solve issue #468. A ros timer is started to check the driver state after every specified duration and to reinitialize the driver for the node if the driver has recovered.