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

Hard coded loop rate #23

Open
jlack1987 opened this issue Nov 16, 2017 · 11 comments
Open

Hard coded loop rate #23

jlack1987 opened this issue Nov 16, 2017 · 11 comments

Comments

@jlack1987
Copy link

jlack1987 commented Nov 16, 2017

Forgive my ignorance if my issue is interpreting the code incorrectly as i'm pretty new to realtime_tools. In this line the loop rate is hard coded to 750Hz. To me this means that if you're running at loop rates greater than 750Hz then you should probably not use this clock tool correct? It seems it would be very easy to make this a configurable argument perhaps with a default rate of 750Hz to not break backwards compatibility.

Additionally i'm a bit confused about the realtime clock implementation here. I'm unable to find anywhere in any documentation here or otherwise that ros::Time::now() is not a real time safe call to make. If it's not safe, then I do see the use of this except the return of getSystemTime is a ros::Time object that, to get time I would still need to call ::now().

Sorry for the questions, but I'm working on a hard real time system so i'm very interested in making sure my method of getting time is a real time safe call. Thanks!

@bmagyar
Copy link
Member

bmagyar commented Nov 17, 2017

Seems like a pretty good point. I personally haven't hit that limit yet.

@graiola , haven't you guys ran stuff on Meka at 1KHz? Perhaps you didn't use this class?

@mathias-luedtke
Copy link
Contributor

mathias-luedtke commented Nov 17, 2017

I have not found any user on GitHub for this class, only file copies.
I am not sure if ros::Time::now() is using a syscall underneath.

However, I don't see any reason why the loop rate should be hard-coded.

@jlack1987
Copy link
Author

Just wondering bc I just stumbled upon this class and was a bit surprised to see, what looks to me, a wrapper around ros::Time to make it real time safe when I wasn't aware that it ever was not real time safe. It got me thinking that for my own stuff perhaps I should be swapping out my calls using regular ole ros::Time to using this for better RT performance.

@mathias-luedtke
Copy link
Contributor

it uses gettimeofday, which will make as syscall and so might lead to context switch.
I guess this is the reason for passing the time to the update function in ros_control.

@jlack1987
Copy link
Author

Ah ok that was what I didn't know, thanks for the explanation. Based on the source code chunk here,

#if HAS_CLOCK_GETTIME
           timespec start;
           clock_gettime(CLOCK_REALTIME, &start);
           sec  = start.tv_sec;
           nsec = start.tv_nsec;
         #else
           struct timeval timeofday;
           gettimeofday(&timeofday,NULL);
           sec  = timeofday.tv_sec;
           nsec = timeofday.tv_usec * 1000;
         #endif

it looks like we are probably ok as long as HAS_CLOCK_GETTIME is defined.

@graiola
Copy link
Member

graiola commented Nov 17, 2017

If I remember correctly ros::Time::now(); is not real-time safe.
You should use the time implementation provided by your rtos and pass the time information to the update function in ros_control. For example (with RTAI):

const uint64_t one_E9 = 1000000000ULL;
uint64_t nsec64 = rt_get_cpu_time_ns();
uint32_t sec32_part = nsec64 / one_E9;
uint32_t nsec32_part = nsec64 % one_E9;
ros::Time now(sec32_part, nsec32_part);
cm_ptr_->update(now, period_);

@graiola graiola closed this as completed Nov 17, 2017
@graiola graiola reopened this Nov 17, 2017
@graiola
Copy link
Member

graiola commented Nov 17, 2017

I closed it by mistake, sorry.

@jlack1987
Copy link
Author

Thanks so much this is really good info, and sorry for sidetracking things from the issue's real purpose. If you all are interested I can make a PR to add that loop rate as an arg with default value of 750.

@bmagyar
Copy link
Member

bmagyar commented Nov 17, 2017 via email

@JimmyDaSilva
Copy link

Hi folks. I see the 750Hz hard-coded value is still here.
Should we do something about this? Add a parameter, or up the value to 1 kHz?

@bmagyar
Copy link
Member

bmagyar commented Dec 5, 2020

Happy to review a PR to add that loop rate as an arg with default value of 750.

matthias-mayr added a commit to matthias-mayr/iiwa_ros that referenced this issue Nov 23, 2022
- ros_control expects the actual time difference
- Did not use the actually measured time in safety checks and vel. calculation yet
- ros::Time::now() is not realtime safe. However realtime_tools' clock limited to 750Hz right now:
  ros-controls/realtime_tools#23
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

No branches or pull requests

5 participants