Choosing the right controller

These questions are related to ros_controllers represented in the ur3_controllers.yaml file. Specifically the pos_joint_traj_controller, vel_joint_traj_controller and joint_group_vel_controller.

In the first part I ask questions about the 3 controllers separatly. This is also to validated my comprehension of the controllers. In the last section, I ask a question about the difference between 2 controllers.

position_controllers/JointTrajectoryController

Per the joint_trajectory_controller wiki: For position-controlled joints, desired positions are simply forwarded to the joints.

Does this mean that this is just a feedforward controller (open-loop) from ros_control perspective?

At the lower level, the servoj command is used which will do a little bit of interpolation (comment). There is also a proportionnal gain for following target position (taken from the URScript API Referrence).

So basically this controller is a joint trajectory controller with a P feedback loop where the loop closure is done with the internal UR controller, not with ros_control framework?

velocity_controllers/JointTrajectoryController

Per the joint_trajectory_controller wiki: while for velocity (effort) joints, the position+velocity trajectory following error is mapped to velocity (effort) commands through a PID loop

This is a joint trajectory controller which outputs velocities to reach a position (comment)

Is the servoj command used? If so the only valuable information used is the position. So the the robot is controlled via position.

Is this a feedforward + PID external feedback controller (image from the free reprint of Modern Robotics p.421) aimed for velocity inputs but is derived to feed positions instead? There would also be an internal P feedback loop from the servoj command.

Untitled

velocity_controllers/JointGroupVelocityController

This is a forwarding-controller which takes in velocity setpoints and simply forwards it to the robot controller. (comment)

This simply forwards the velocity inputs through the speedj command as a feedforward controller. It is up to the person to close the loop to achieve what they want (Ex. to create an admittance controller).

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?

I am interested in this as well!

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.

3 Likes

Thank you for your great explanation!

Does the speedj implementation compensates for gravity with the payload mass and COG?

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.

That would be awesome!

I would assume, it does, as it is controlling a joint speed. If the speed gets higher due to gravity pulling a joint down, currents should be reduced to achieve the desired velocity. But that’s just my understanding, as I don’t know the internals of speedj.

Hi,I have two questions.

I want to use the vel_joint_traj_controllerr to control ur5 constant motion (the end link keep one speed).I send a string points with constant vel but i cannot get constant motion. what can i do, i need change the pid values or …?

I try use the joint_group_vel_controller to control ur5 constant motion,but when i start this control,the ur5 urdf model falls in gazebo. I can not solve this problem

I need your help, thank you very much!

Answered inside Ur5 constant motion

1 Like