ros-controls / ros_control

Generic and simple controls framework for ROS
http://wiki.ros.org/ros_control
BSD 3-Clause "New" or "Revised" License
469 stars 307 forks source link

Stop the current controller within the `starting` method #521

Open captain-yoshi opened 5 months ago

captain-yoshi commented 5 months ago

See this issue https://github.com/fzi-forschungszentrum-informatik/cartesian_controllers/issues/170 for context.

I was wondering if there is a way to stop the controller within the controller API after starting it ? Is there a way to stop it before it sends (in this case) joint positions ? If not, I can set a safe position (e.g not clamped) but I would still want a way to stop the controller...

The controller does not override the method aborting. Not sure if it is necessary to stop the controller.

This is what I'm trying to do:

void JointPositionController::starting(const ros::Time& time)
{
  ...

  // Make sure joint is within limits, if not stop the controller
  bool error = validateJointLimits(pos_command);

  // Stop the controller
  if (error)
    this->abortRequest(ros::Time::now()) // Not working... 

  ...
}
BryanStuurman commented 3 months ago

I have the same issue with the trajectory controller, most controllers will display this behaviour as they call some kind of limiting function to keep the output within the joint limits.

While you can call the aborting method inside your controller, that doesn't prevent the controller manager from assuming your controller has started happily and calling your update() method as it sees fit. We need to fix it so that the call chain to starting() can fail and prevent the controller manager from setting your controller state_ to ControllerState::RUNNING. check the start controllers method here: https://github.com/ros-controls/ros_control/blob/noetic-devel/controller_manager/src/controller_manager.cpp#L150 and the startRequest() method here: https://github.com/ros-controls/ros_control/blob/noetic-devel/controller_interface/include/controller_interface/controller_base.h#L146 The way to do this with the existing code is to override switchResult() in your hardware driver class to return an error when out of bounds. This could be completely controller independent (I haven't thought this one through or implemented it yet!) and will cause all controllers in the start request to be aborted according to the controller manager. https://github.com/ros-controls/ros_control/blob/noetic-devel/hardware_interface/include/hardware_interface/robot_hw.h#L175

What I would like to see, and what I have about 80% of a PR for is using the bool return of startRequest() to flag individual controllers as unable to be started, and call their abortRequest():

    for (const auto& request : start_request_)
    {
      if(!request->startRequest(time)) 
      {
        request->abortRequest(time);
      }
    }

Then we can patch ControllerBase::startRequest() with a check to a new virtual function - say ControllerBase:switchResult() - and maintain compatibility with existing functions while offering a path forward for failing to start being managed at the controller level.