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

Fix unit conversion bug in to_timeval() #24

Merged
merged 1 commit into from Oct 27, 2022

Conversation

LukaJuricic
Copy link
Contributor

Small fix for a bug which caused incorrect waiting intervals when accessing the CAN socket.

@kenji-miyake
Copy link
Contributor

@ljuricic @MarcelDudek Hello, thank you for fixing it. And we're sorry for the late reply.
Would it be possible for you to show me how to reproduce the bug? For example, like this issue #17.

@JWhitleyWork cc @mitsudome-r @xmfcx Would you review this PR since you are the original author?

@LukaJuricic
Copy link
Contributor Author

Hello @kenji-miyake, here is how you can easily show the issue functionally.

  1. In terminal 1: start the CAN module, setup vcan0 interface and generate there random messages every 50ms
sudo apt install can-utils
sudo modprobe vcan
sudo ip link add dev vcan0 type vcan
sudo ip link set up vcan0
cangen vcan0 -g 50
  1. In terminal 2: start top to check the CPU load
  2. In terminal 3: start a socket_can_receiver node on vcan0 interface and theoretical 100ms polling period
ros2 launch ros2_socketcan socket_can_receiver.launch.py interface:=vcan0 interval_sec:=1e-1

The socket_can_receiver thread loads the CPU to 100% and receives a warning with 1Hz (due to the warning throttling)

[socket_can_receiver_node_exe-1] [WARN] [1666111964.538596370] [socket_can_receiver]: Error receiving CAN message: vcan0 - Resource temporarily unavailable
  1. In terminal 3: stop the current process with Ctrl+C and restart the socket_can_receiver by compensating the factor 1e6 bug
ros2 launch ros2_socketcan socket_can_receiver.launch.py interface:=vcan0 interval_sec:=1e-7

Now the socket_can_receiver does not load the CPU anymore by freewheeling and the warning is gone

@kenji-miyake
Copy link
Contributor

I'm sorry to be late, and thank you for your information!

In terminal 3: start a socket_can_receiver node on vcan0 interface and theoretical 100ms polling period
ros2 launch ros2_socketcan socket_can_receiver.launch.py interface:=vcan0 interval_sec:=1e-1
The socket_can_receiver thread loads the CPU to 100% and receives a warning with 1Hz (due to the warning throttling)

Unfortunately, I couldn't reproduce it. There was no warning.

ros2 launch ros2_socketcan socket_can_receiver.launch.py interface:=vcan0 interval_sec:=1e-7

Also, nor by this command.
However, considering the bug that the timeout becomes too big, it would be the correct behavior.

And after applying your fix, there are warnings shown, but considering the interval, it seems to be the correct behavior.

$ ros2 launch ros2_socketcan socket_can_receiver.launch.py interface:=vcan0 interval_sec:=1e-7
[INFO] [launch]: All log files can be found below /home/kenji/.ros/log/2022-10-20-20-54-22-601501-DPC2108002-52466
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [socket_can_receiver_node_exe-1]: process started with pid [52480]
[socket_can_receiver_node_exe-1] [INFO 1666266862.707317456] [socket_can_receiver]: interface: vcan0
[socket_can_receiver_node_exe-1] [INFO 1666266862.707357515] [socket_can_receiver]: interval(s): 0.000000
[socket_can_receiver_node_exe-1] [INFO 1666266862.707367662] [socket_can_receiver]: use bus time: 0
[socket_can_receiver_node_exe-1] [WARN 1666266863.052225989] [socket_can_receiver]: Error receiving CAN message: vcan0 - CAN Receive Timeout
[socket_can_receiver_node_exe-1] [WARN 1666266864.052222490] [socket_can_receiver]: Error receiving CAN message: vcan0 - CAN Receive Timeout

But anyway, since the change looks reasonable, I'll approve it.
And @xmfcx will review this after he comes back from ROSCon.

Copy link
Collaborator

@JWhitleyWork JWhitleyWork left a comment

Choose a reason for hiding this comment

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

This was a bug and the fix is correct.

Copy link
Contributor

@xmfcx xmfcx left a comment

Choose a reason for hiding this comment

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

number in nanosecs / 1000 = number in microseconds, thanks for fixing it.

@xmfcx xmfcx enabled auto-merge (squash) October 26, 2022 07:10
@xmfcx
Copy link
Contributor

xmfcx commented Oct 26, 2022

@ljuricic can you rebase this onto main? I don't seem to have the rights to do it myself on your fork.

@xmfcx xmfcx disabled auto-merge October 26, 2022 07:13
@xmfcx
Copy link
Contributor

xmfcx commented Oct 26, 2022

@ljuricic or if you want, I can reopen another PR with a branch I rebased your commit.

Signed-off-by: ljuricic <98381369+ljuricic@users.noreply.github.com>
@LukaJuricic
Copy link
Contributor Author

@xmfcx sorry for the delay, it should be fixed now, let me know if there is anything else

@xmfcx xmfcx merged commit 76873db into autowarefoundation:main Oct 27, 2022
h-ohta pushed a commit to tier4/ros2_socketcan that referenced this pull request Jun 13, 2023
… (#2)

Signed-off-by: v-nojiri7841-esol <v-nojiri7841@esol.co.jp>
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.

None yet

4 participants