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

Add Timestamping to socketcan_interface #188

Open
Worldman2 opened this issue Aug 10, 2016 · 4 comments
Open

Add Timestamping to socketcan_interface #188

Worldman2 opened this issue Aug 10, 2016 · 4 comments

Comments

@Worldman2
Copy link

Worldman2 commented Aug 10, 2016

There should be a way to obtain the timestamp of receiption for a CAN-frame. Ideally, this should be the HW-timestamp, if the device supports it (using SIOCSHWTSTAMP). According to the socketcan documentation, timestamps can be obtained by an ioctl-call after reading a message from the socket.

I tried hacking something into socketcan.h but failed.
My approach was to just add

ioctl(socket_.native_handle(), SIOCGSTAMP, &tv);

at the beginning of SocketCANInterface::readFrame(...) and

setsockopt(sc, SOL_SOCKET, SO_TIMESTAMP, &timestamp_on, sizeof(timestamp_on));

in the init(...) method.
However, the values seem wrong (inconsistent, jumping, in the range of 10^12). So it probably just proves how few I understand about socketcan and boost::asio.

Is there a possibility for a recent implementation of this feature request or could you provide some hints how to realize this? Thanks!

@mathias-luedtke
Copy link
Member

mathias-luedtke commented Aug 10, 2016

I tried it myself some time ago, but for some reason I did not include it somewhere.
If I remember it correctly, not all devices set these time stamps and in addition it is unclear what time base they use.

However, timestamps would be a nice feature!

ioctl(socket_.native_handle(), SIOCGSTAMP, &tv);

This looks right, not sure why it is delayed.

@Worldman2
Copy link
Author

As far as I understand, even if the hardware does not support it, there is at least the option to retrieve the socket timestamp (SO_TIMESTAMP) of the last received packet. I think, this is also what candump does: https://github.com/linux-can/can-utils/blob/master/candump.c#L676

@mathias-luedtke
Copy link
Member

mathias-luedtke commented Dec 21, 2016

Found my implementation again: https://github.com/ipa-mdl/ros_canopen/tree/stamped_data
However, this does not use CAN-based timestamps.

@ozzdemir
Copy link

This source mentions the following. It might the reason for the inconsistent timestamp.

Note that SIOCGSTAMP and SO_TIMESTAMP are mutually exclusive - if you're going to use SIOCGSTAMP you should disable SO_TIMESTAMP (with enabled = 0). This is because SO_TIMESTAMP directs the kernel to make the timestamp available via recvmmsg ancillary data instead of via SIOCGSTAMP.

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

No branches or pull requests

3 participants