I've noticed that there are two related ROS packages: ros_control
and ros_controller
. What is the difference between them?
ros_control
is the repository that hosts the main packages to do with the ros_control
infrastructure: controller managers, various provided hardware_interface
implementations, a default transmission implementation and an RQT plugin that lets you control a ControllerManager
using a UI.
ros_controllers
is the repository that hosts various controller implementations (and only those): position, velocity, effort controllers, joint state, imu, F/T sensor broadcasting "controllers" and controllers for more high-level kinematic setups such as Ackermann, four-wheel and differential drive steering platforms.
When should I use one over the other?
I hope it's clear now that this question isn't really a valid one: you could certainly use the packages in ros_control
without the ones from ros_controllers
, but not much would happen in that case. Unless of course you write your own controllers.
Can I use these packages to e.g. control a specific robot? For example, a thymio robot? If yes, what is the overall approach to perform such task? For example, if I wanted a robot to be move around until it detects an obstacle in front of it, can these packages be used to do such thing? If not, what exactly then do these packages provide?
Tbh I feel you're asking too many questions in a single post, but shortly: no, that is not what these controllers do. What they do allow you to do is pretty well described on the ROS wiki for each respective controller actually. Take a look at the wiki page for the diff_drive_controller for instance:
Controller for differential drive wheel systems. Control is in the form of a velocity command, that is split then sent on the two wheels of a differential drive wheel base. Odometry is computed from the feedback from the hardware, and published.
So for Thymio specifically, you'd write (or find somewhere) a hardware_interface
implementation that exposes a set of actuators and sensors in a ros_control
compatible way, configure your setup to use that hardware_interface
and then load the diff_drive_controller
on top of that. If a hardware_interface
for your specific robot already exists, that saves you quite a lot of time, as instead of implementing both hardware access and a differential drive controller yourself, you get to reuse at least the latter, and possibly the former.
(note: I have no experience with Thymio robots, so don't know whether they are differential drive or not).
The more "simple" controllers allow you to control a group of joints (revolute, prismatic, or something else) in various ways (position, velocity and effort).
Edit:
I asked these "simple" questions because it might not be easy for a newcomer (to the field of robotics and ROS) to understand what the purpose of these package is. Anyway, I asked many questions, but they are all related.
I may be misunderstanding this comment, but I don't believe I refer to your question as simple. I merely stated ... (more)