Open JanStaschulat opened 3 years ago
This issue has been mentioned on ROS Discourse. There might be relevant details there:
https://discourse.ros.org/t/ros-2-embedded-wg-meetings/15460/20
micro_rclcpp: a C++ API for micro-ROS
The following table compares a potential C++ API for micro-ROS, called micro_rclcpp
with the existing rclcpp
API. It consists of a number of C++ wrapper functions and uses the rclc package.
Feature | rclcpp | micro_rclcpp |
---|---|---|
Message type conversion | Message types need to converted from C++ template type argument to rosid_typesupport_t type in RCL. Example for Subscription: rclcpp::create_subscription() rclcpp::create_subscription_factory() rosidl_runtime_cpp::get_message_type_support_handle() |
similar approach can be used |
Callback function pointers | no restrictions for function pointers Message type in parameter declaration |
Only static member functions and capture-less lamda. There is also an article about how use member functions as C-function pointers only void * parameter for message type |
Message data types | staticly and dynamically allocated message variables (e.g. std::String and other STL containers) |
dynamic memory allocation shall be avoided, std::String and STL-containers are not supported. This is not a restriction of mirco_rclcpp but a requirement of programming on a micro-controller. Alternative: cxx::string in iceoryx |
Node Concept | Subscriptions, publishers, timers etc. are added to a Node |
RCLC does not have a Node concept. Subscriptions, publishers, timers are added directly to the Executor. One option would be to add a Node type in which the Executor is initialized and you can call Node.spin() |
Alternative: Full C++ Implementation with Executor has the
Benefits:
Limitations:
Summary micro_rclcpp
Benefits:
Limitations:
void *
as argument possiblestd::String
)Questionnaire to micro-ROS users
Looking forward to your feedback. Thank you.
This thread is looking a little sparse, I missed the meeting but I'll throw my opinion in
I've normally avoided C++ for microcontrollers because of how easy it is to accidentally pull in std::
types that enthusiastically re-allocate memory.
Arduino in relies heavily on std::string and permits concatenation and deep copy; It's often ok even if it's not desired for performance. If I were teaching with ROS on microcontrollers, I would appreciate an API that is more more congruent with the Arduino flavour. A Node would allow some neat namespacing tools, and would make sense as a tidy top-level C++ object to handle entity destruction.
I would like to see more type-safety in RCLC; it's getting tedious writing endless functions that take only void*
arguments. C++ templates are a good way of giving compile-time type-safety to the user. I think a templated wrapper could lead to some more type-names being migrated back to RCLC, which would be good for readability.
I'd really really want to see strongly-typed callbacks, and I would make extensive use of std::bind
to make very sure I can use callback context pointers to carry this
pointers for non-static class member functions. I would also make PRs to tweak callback argument order to make such hacks more seamless.
RCL offers allocation pointers and defined allocator structs, I'd personally default those to no-allocation, but I would want to see the custom-allocator feature of RCL exposed in micro_rclcpp as it is in rclcpp because of the zero-cost abstractions it offers.
Tangentially, I'm also interested in a Rust wrapper but that might be easier to build from scratch.
This issue has been mentioned on ROS Discourse. There might be relevant details there:
https://discourse.ros.org/t/ros-2-embedded-wg-meetings/15460/22
Example for C++ type support:
std_msgs::msg::String
)void *
)Demonstrated in rclc_examples/example_pingpong: https://github.com/ros2/rclc/pull/199
Hi
I was not able to make my mic work during today's meeting, so I'll add my few cents here.
One has to avoid using almost all STL containers, std::array
can be used with no risks. Even when exceptions are disabled, one can use at() with no more risks than the usual when working with arrays.
This added with all the benefits of type-safety, templates, and more. The overhead introduced by C++ can be substantial, however, from my point of view, it's none compared to the benefits.
We already work having wrappers on top of rclc or rcl depending on the use, and our biggest "struggle" is that we saw ourselves forced to make singletons to somehow get access to a class method during a callback (this was basically solved with the introduction of the context pointer).
Regarding RUST, it's interesting, but far from being mature enough to use it on product development.
@bjv-capra Thank you for your feedback. Regarding the access to class members, as you mentioned, we have now subscriptions with context pointers. Apart from access to class members (which should be solved), I see as main development points:
This issue has been mentioned on ROS Discourse. There might be relevant details there:
https://discourse.ros.org/t/microxrce-dds-on-ardupilot/29972/8
We have received a number of requests to provide a C++ API for micro-ROS. Therefore we would like to discuss how to develop a C++ API for micro-ROS as a community effort. The default rclcpp API uses dynamic memory allocation (STL containers) which is problematic for micro-controllers due to memory framentation and potentially allocating more memory than available. Completely re-writing rclcpp would be a large effort, therefore we see two basic strategies:
The decision might also depend on the requirements for such a C++ API. So please feel free to join the next EWG meeting on 27th July 2021 to share your opinion: https://discourse.ros.org/t/ros-2-embedded-wg-meetings/15460
You are also welcome to comment here below.