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

Why don't position_controllers publish the controller state like effort_controllers do? #606

Open
joaocandre opened this issue Aug 27, 2022 · 7 comments

Comments

@joaocandre
Copy link

I was forced to migrate from effort_controllers/JointPositionController to position_controllers/JointPositionController and I noticed I no longer get topics publishing the controller state for each controller joint. Is this by design (is there any particular reason for it?) or there was just never the need to implement it?

@bmagyar
Copy link
Member

bmagyar commented Aug 28, 2022 via email

@wxmerkt
Copy link
Contributor

wxmerkt commented Aug 29, 2022

I believe it's because it's a forward_controller rather than a PID controller. (I've implemented the controller state publishing for velocity_controllers/JointPositionController but it may not make sense for position_controller/JointPositionController - could PR that)

@joaocandre
Copy link
Author

I assume internally there is some kind of PID loop though, considering the PID gains can be tuned through parameters in the controller namespace? In truth when setting publish_state parameter to true the state is published, but not as a control_msgs::JointController message.

@wxmerkt
Copy link
Contributor

wxmerkt commented Aug 30, 2022

If we are speaking of a position_controller/JointPositionController, I don't think there are gains - it's a pure forward controller (cf.

void forward_command_controller::ForwardCommandController<T>::starting(const ros::Time& time)
{
// Start controller with current joint position
command_buffer_.writeFromNonRT(joint_.getPosition());
}
PLUGINLIB_EXPORT_CLASS(position_controllers::JointPositionController,controller_interface::ControllerBase)
). Can you point me to the config where you are seeing the parameters/topics?

@joaocandre
Copy link
Author

I haven't tried to tune these "PID" parameters to check whether they do anything at all, but I've seen some models/packages providing those parameters, and ROS complains about those missing parameters if not provided under gazebo_ros_control/pid_gains/[controller] (as error messages) .

For instance, we can see that in configuration files for simulating of a NAO humanoid with position controllers, whose hardware interface is defined in the URDF model as PositionJointInterface (albeit this is rather old repository, probably not actively maintained).

I've also seen it in some URDF tutorials that define PID gains for position-controlled joints. Again not sure if they are supposed to do anything because I've never tried to edit these values.

@wxmerkt
Copy link
Contributor

wxmerkt commented Aug 30, 2022

Thank you for providing the references and links. The links above refer to an issue present in older versions of Gazebo (7, available with ROS Kinetic) for which a workaround was to set the PID gains for the PositionJointInterface. The position_controllers in ros_controllers do not use these gains - as thus, there wouldn't be modifications that could be made to publish the controller state

@lprobsth
Copy link

lprobsth commented Mar 10, 2023

I haven't tried to tune these "PID" parameters to check whether they do anything at all, but I've seen some models/packages providing those parameters, and ROS complains about those missing parameters if not provided under gazebo_ros_control/pid_gains/[controller] (as error messages) .

For instance, we can see that in configuration files for simulating of a NAO humanoid with position controllers, whose hardware interface is defined in the URDF model as PositionJointInterface (albeit this is rather old repository, probably not actively maintained).

I've also seen it in some URDF tutorials that define PID gains for position-controlled joints. Again not sure if they are supposed to do anything because I've never tried to edit these values.

The PID gains for gazebo_ros_control are for setting either forces or velocities and positions in the simulation directly. If you omit the PID gains for gazebo_ros_control, the control_toolbox's PID controller throws an error during initialization (https://github.com/ros-simulation/gazebo_ros_pkgs/blob/noetic-devel/gazebo_ros_control/src/default_robot_hw_sim.cpp#L222). If the PID controller could be initialized, the hardware interface sets effort commands (https://github.com/ros-simulation/gazebo_ros_pkgs/blob/noetic-devel/gazebo_ros_control/src/default_robot_hw_sim.cpp#L351 and https://github.com/ros-simulation/gazebo_ros_pkgs/blob/noetic-devel/gazebo_ros_control/src/default_robot_hw_sim.cpp#L379). If the PID controller could not be initialized, the commanded position or velocity are set directly in the simulation, which sometimes results in weird behavior for mobile robots (sliding, wobbling).

(i think that multiple people are finding this issue when attempting to tune the gazebo controller from gazebo_ros_control - so I'm writing this here)
Since the forward controllers in ros_control don't publish the state of the controller, the PID controllers from gazebo_ros_control are hard to tune (people migrating from other controllers from ros_control probably look first for the state topic). The other controllers (e.g. trajectory + velocity) publish the state including the set forces from gazebo correctly. Having the forward controllers publish the full state through a topic would be nice for both real and simulated robots (e.g. our rover also sends back efforts when controlling with velocities from a forward controller). But for gazebo the best approach is probably publishing the state directly in gazebo_ros_control since then we see the control error for the PID controller.

Edit

I just realized there is a parameter for the PID controller that is used in ros_gazebo_control publish_state (https://github.com/ros-controls/control_toolbox/blob/melodic-devel/src/pid.cpp#L141), that can be used to obtain the internal state of the controller. This includes the error and the individual P, I and D parts of the controller.

But still - having a publisher for the feed forward controllers from ROS control might be good for real robots that use external motor controllers that itself publish their internal controller states.

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

4 participants