Comments (4)
I was thinking about this use case and I believe relying on the processing order in the executors is fragile. Perhaps that's something we could ensure more in the future and therefore make this more reliable, but there are just so many implementation details here that must not change to keep this working, e.g. if the clock subscription was ever recreated sometime after start up, or some other seemingly innocuous change related to the clock topic.
Instead, I wonder if a customized executor that waits for a ROS time update before each wait-execute loop with the clock topic thread enabled might result in a better solution. That might even make sense as an executor option for the standard executors.
The reason I think so is that if you ever need to sleep_until or sleep_for in a callback you'll get into a dead lock without the clock topic thread, and I'm also worried about the executor waking up, handling the clock subscription first (as you desire in your above apporach), but then there are hundreds of clock messages which all get processed first and only after that do you start processing new messages from other subscriptions, all of which will "appear" to occur at the same time according to ros time (because while handling these the clock messages that are streaming in are not being handled). Or some other complex interaction with the clock topic.
from rclcpp.
I was thinking about this use case and I believe relying on the processing order in the executors is fragile.
I would agree with this statement for the standard executors. However, I think executing the timer callbacks in response to receipt of the /clock
message within the EventsExecutor
could be much more feasible.
Instead, I wonder if a customized executor that waits for a ROS time update before each wait-execute loop with the clock topic thread enabled might result in a better solution. That might even make sense as an executor option for the standard executors.
A potential concern with this is how only one message per subscription is processed per spin cycle. If there are multiple publishers to a topic and multiple messages arrive on that topic between /clock
messages, then those messages could be lost if only one is processed in the spin cycle and then spinning is delayed until a clock update occurs.
The reason I think so is that if you ever need to sleep_until or sleep_for in a callback you'll get into a dead lock without the clock topic thread
This is a valid concern. My thought was that this shortcut wouldn't work if the clock thread was explicitly disabled because having a clock thread inherently ensures that there will always be a race condition between timer and subscription callbacks.
To your point that the standard executors have no guarantee of ordering, it's seeming like the EventsExecutor
is definitely a better choice for this use case so I'll take a look at the TimersManager
to see if the shortcut approach could make sense there.
from rclcpp.
Related Issues (20)
- TimersManager doesn't follow ROS time HOT 4
- rclcpp_action: Provide enum class return ClientGoalHandle::get_status
- Callback works on Galactic but fails on Rolling - handle_message is not implemented for GenericSubscription HOT 1
- Clang warning: ordered comparison of function pointers (Rolling) HOT 1
- `-fanalyzer` warning: possible null dereference when using TypeAdapters HOT 4
- leak due to std::shared_ptr circular reference between Context and GuardCondition HOT 3
- :farmer: `rclcpp.test_executors` failing in Rolling and Jazzy CycloneDDS HOT 2
- rclcpp::Time(int64_t nanoseconds, ...) should check for negative time
- Regression : Executor::spin_some_impl is active waiting HOT 5
- Parameter service behavior is inconsistent with the documentation of rcl_interfaces HOT 9
- Lifecycle destructor calls shutdown while in shuttingdown intermediate state HOT 45
- Backport PR2063 to Humble for Windows HOT 2
- Executor callbacks are no longer in a predictable order HOT 25
- '/clock' Topic cannot change each loop step time from simulation time HOT 10
- Program exits with code -11 when using async_send_request to set parameters in ROS 2 C++ client HOT 1
- Possible regression in rcl preshutdown callbacks - context invalid? HOT 11
- Shutdown transition on base lifecycle node dtor may lead to segaults on subclass-registered shutdown callback HOT 6
- `on_shutdown` callback not called when `shutdown` transition is triggered on dtor HOT 2
- ABI/API Compliance Checker in github workflow HOT 2
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from rclcpp.