I’ll try to explain things a bit further…
First of all, the driver supports both, commanding positions or velocities.
In case of positions a servoj
command will be used here where the servoj target will be updated by the ROS side.
In case of velocity commands, speedj
is used to set the robot’s joint speeds directly.
As servoj
does an interpolation between the current state and the target command, it is a bit slower than speedj
which (as far as I know) directly copies the setpoint into the target velocity in the next control cycle. For details, please see this comment
Ontop if those interfaces, different ROS controllers can be started. As ROS-Control is designed in a way that all position- based controllers work as soon as a position interface is available and all velocity-based controllers will work with any velocity interface (given, we’re talking about joint space), there are loads of controllers available for the ROS driver.
As both, servoj
and speedj
as far as I know perform a low-level control (In case of servoj
it is a bit more, including interpolation as mentioned in the OP), ROS-Control basically sits outside this inner control mechanism.
The position-based JointTrajectoryController of ROS-Control is indeed an open-loop controller. Position commands are forwarded to the hardware interface and the deviation is measured inside the controller’s feedback. If the path deviation gets too large, the action sent to the controller will simply fail, there won’t be any corrections.
This is one reason why we created the scaled versions of controllers that will take the speed scaling done on the robot controller into account. Apart from that, they are identical to the normal, non-scaled versions.
In case of the velocity-based JointTrajectoryController there is a closed loop structure to reach the target setpoints using a PID controller. PID values inside the driver are currently not optimized as discussed in #124 and #119.
The JointGroupControllers indeed only do command-forwarding directly to the joints, so they are similar to writing the respective servoj
or speedj
commands into URScript directly.
pos_joint_traj_controller VS vel_joint_traj_controller
What is the difference between these 2 controllers. Is one of them suppose to make trajectories smoother?
As mentioned above, the differences are:
- open-loop position commands vs. closed loop velocity commands on ROS side
servoj
vs.speedj
implementation on URScript side
With the velocity-based implementation you might get a more responsive and maybe smoother trajectory execution, but I cannot guarantee that the default PID values will provide the best solution. Basically, with velocity control you move more of the actual control to the ROS side. You will loose one control cycle (2ms in case of an e-series robot) and an unknown (at least to me) amount of time to the control structure underneath.
I hope that this clarifies a lot of things, ideally we would get a document out of this, that we can add to the driver’s documentation. But I think, this would need some more elaboration. Please let me know, if there is anything unclear.