ros-controls / ros2_control

Generic and simple controls framework for ROS 2
https://control.ros.org
Apache License 2.0
515 stars 308 forks source link

hardware_interface - read/write are called before on_activate has finished #1891

Open firesurfer opened 2 days ago

firesurfer commented 2 days ago

Describe the bug

During our migration from Iron to Jazzy I ran into the issue of having random segfaults during startup in one of our hardware interfaces.

The cause of the issue seems to be that the read/write methods are called before the on_activate method has finished (It is actually random what is executed first). The segfault in our case was a pointer being accessed in the the read method that is initialized in the on_activate method

To Reproduce

Write a hardware interface, and simply check if read/write or on_activate is called first.

Expected behavior

on_activate should be called and should have finished before the read/write methods of a hardware interface are called.

Environment (please complete the following information):

Preliminary solution

I added a std::atomic_bool active_ flag to my hardware interface which I set after on_activate has finished.

In the read/write methods I then check it and return early if nessary

    if (!active_)
        return hardware_interface::return_type::OK;
christophfroehlich commented 2 days ago

I think it's not a bug, it's a feature.

AFAIK, the idea was that joint values are sent only in activated mode but all non-joint interfaces are read/written from configured on. But I think this distinction is not implemented yet and always sent.