Configuring the controller.yaml file to use a velocity controller

5,193 views
Skip to first unread message

mfr...@vt.edu

unread,
Jul 2, 2014, 4:18:02 PM7/2/14
to ros-sig-ro...@googlegroups.com
Hey all,

So I am trying to use the effort_controller/JointVelocityController as a controller to interface with movegroup action service. In my urdf file I made sure to set the hardware interface to VelocityJointInterface, and when creating my RobotHW class I made sure to create a private variable hardware_interface::EffortJointInterface jnt_vel_interface; in order to register and connect the interface. Here is my controller.yaml file

atlasarm:

  # Trajectory Controllers ---------------------------------------
  arm_controller:
    type: effort_controllers/JointVelocityController
    joints:
      - base_to_azimuth
      - azimuth_to_upperArm
      - upperArm_to_lowerArm
      - lowerArm_to_forward_link
      - forward_link_to_wristlink_1
      - wristlink_1_to_wristlink_2
    gains:
       base_to_azimuth: {p: 100.0, i: 0.01, d: 10.0}
       azimuth_to_upperArm: {p: 100.0, i: 0.01, d: 10.0}
       upperArm_to_lowerArm: {p: 100.0, i: 0.01, d: 10.0}
       lowerArm_to_forward_link: {p: 100.0, i: 0.01, d: 10.0}
       forward_link_to_wristlink_1: {p: 100.0, i: 0.01, d: 10.0}
       wristlink_1_to_wristlink_2: {p: 100.0, i: 0.01, d: 10.0}
   

When I try to run a program using ros_control in order to create/start this velocity controller I get the following error:

[ERROR] [1404329741.678130586]: No joint given (namespace: /atlasarm/arm_controller)
[ERROR] [1404329741.678209566]: Failed to initialize the controller
[ERROR] [1404329741.678232210]: Initializing controller '/atlasarm/arm_controller' failed

Why is it that when I try to load the controller I get this error saying No joint given. But looking at the yaml file I see the list of joints?

Thanks
Mike
 

Adolfo Rodríguez Tsouroukdissian

unread,
Jul 3, 2014, 2:56:00 AM7/3/14
to Michael Francis, ros-sig-ro...@googlegroups.com
On Wed, Jul 2, 2014 at 10:18 PM, <mfr...@vt.edu> wrote:
Hey all,

So I am trying to use the effort_controller/JointVelocityController as a controller to interface with movegroup action service. In my urdf file I made sure to set the hardware interface to VelocityJointInterface, and when creating my RobotHW class I made sure to create a private variable hardware_interface::EffortJointInterface jnt_vel_interface; in order to register and connect the interface. Here is my controller.yaml file

If you're using the MoveitSimpleControllerManager (the most common usecase), then a effort_controller/JointVelocityController (from the ros_controllers project) will not do. The expected controller interface should implement a follow_joint_trajectoy action server. See [1] for more details. In ros_controllers, there's the joint_trajectory_controller that implements this interface. Position and effort interfaces are already supported, and velocity interfaces have an open PR [2], that is pending some validation.

[1] http://moveit.ros.org/wiki/Executing_Trajectories_with_MoveIt!
[2] https://github.com/ros-controls/ros_controllers/pull/64

--
You received this message because you are subscribed to the Google Groups "ROS/Orocos Robot Control Special Interest Group" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-robot-co...@googlegroups.com.
For more options, visit https://groups.google.com/d/optout.

Felix Meßmer

unread,
Jul 4, 2014, 2:24:40 AM7/4/14
to ros-sig-ro...@googlegroups.com, mfr...@vt.edu
I am also working with the effort_controller/JointVelocityController.
We are currently trying to figure out good PID gains for a 7DoF robot arm. I will post our experiences here, once we are done.

I just have a few questions:
- Isn't the effort_controller/JointVelocityController a single joint controller? Thus only capable of having one joint being set in the joint tag?
- What we are currently trying to do is figure out good PIDs for each revolute joint separately (separate controllers with separate yaml files) by making all but the current joint a fixed joint in the URDF.
- Another thing that we recognized is that the JointVelocityController only publishes state information only every 10th time update() is called (https://github.com/ros-controls/ros_controllers/blob/indigo-devel/effort_controllers/src/joint_velocity_controller.cpp#L140). For our initial PIDs the rqt_plots looked quite ok/smooth, but the arm kept dropping and was totally unstable. When I then published to the state topic every update(), I found the controller heavily oscillating changing sign every message. By only publishing every even message, you did not see this...;-)
- Now we are trying to find the PIDs using Ziegler-Nichols strategy for each joint controller separately and then hope that it still works when me make all joints revolute again. Would you say this approach is feasible? Are there any other suggestions?
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-robot-control+unsub...@googlegroups.com.

Adolfo Rodríguez Tsouroukdissian

unread,
Jul 4, 2014, 2:49:55 AM7/4/14
to Felix Meßmer, ros-sig-ro...@googlegroups.com, Michael Francis
On Fri, Jul 4, 2014 at 8:24 AM, Felix Meßmer <felixm...@gmail.com> wrote:
I am also working with the effort_controller/JointVelocityController.
We are currently trying to figure out good PID gains for a 7DoF robot arm. I will post our experiences here, once we are done.

I just have a few questions:
- Isn't the effort_controller/JointVelocityController a single joint controller? Thus only capable of having one joint being set in the joint tag?

Yes, it's a single-joint controller.
 
- What we are currently trying to do is figure out good PIDs for each revolute joint separately (separate controllers with separate yaml files) by making all but the current joint a fixed joint in the URDF.

If a joint is part of a chain, it's dynamics will be affected by the dynamic coupling with upstream and downsteam links. That is, as the robot changes configuration, it's mass distribution will also change, as well as the joint accelerations. In the absence of a controller that compensates dynamics, as in pure PID control, these dynamic effects are disturbances the PID must be effective at rejecting. If you tune a joint PID in a fixed configuration, you could be underestimating the disturbances it must reject. If your robot does not do very dynamic motions, you can probably get a good starting point by using the most demanding fixed configurations (eg. tune a shoulder joint with the arm stretched, oriented for max gravity load).
 
- Another thing that we recognized is that the JointVelocityController only publishes state information only every 10th time update() is called (https://github.com/ros-controls/ros_controllers/blob/indigo-devel/effort_controllers/src/joint_velocity_controller.cpp#L140). For our initial PIDs the rqt_plots looked quite ok/smooth, but the arm kept dropping and was totally unstable. When I then published to the state topic every update(), I found the controller heavily oscillating changing sign every message. By only publishing every even message, you did not see this...;-)

If you want to make this a configurable parameter, as other controller do, I'd be happy to review a patch.
 
- Now we are trying to find the PIDs using Ziegler-Nichols strategy for each joint controller separately and then hope that it still works when me make all joints revolute again. Would you say this approach is feasible? Are there any other suggestions?

We tune our hardware PIDs using frequency-domain tools. We've so far been more heuristic when tuning our simulation gains, definitely something to improve.

Best,

Adolfo.


To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-robot-co...@googlegroups.com.

For more options, visit https://groups.google.com/d/optout.



--
Adolfo Rodríguez Tsouroukdissian
Senior robotics engineer
adolfo.r...@pal-robotics.com
http://www.pal-robotics.com

PAL ROBOTICS S.L
c/ Pujades 77-79, 4º4ª
08005 Barcelona, Spain.
Tel. +34.93.414.53.47
Fax.+34.93.209.11.09
Skype: adolfo.pal-robotics
Facebook - Twitter - PAL Robotics YouTube Channel

AVISO DE CONFIDENCIALIDAD: Este mensaje y sus documentos adjuntos, pueden contener información privilegiada y/o confidencial que está dirigida exclusivamente a su destinatario. Si usted recibe este mensaje y no es el destinatario indicado, o el empleado encargado de su entrega a dicha persona, por favor, notifíquelo inmediatamente y remita el mensaje original a la dirección de correo electrónico indicada. Cualquier copia, uso o distribución no autorizados de esta comunicación queda estrictamente prohibida.

CONFIDENTIALITY NOTICE: This e-mail and the accompanying document(s) may contain confidential information which is privileged and intended only for the individual or entity to whom they are addressed.  If you are not the intended recipient, you are hereby notified that any disclosure, copying, distribution or use of this e-mail and/or accompanying document(s) is strictly prohibited.  If you have received this e-mail in error, please immediately notify the sender at the above e-mail address.

Felix Meßmer

unread,
Jul 4, 2014, 8:30:56 AM7/4/14
to ros-sig-ro...@googlegroups.com, felixm...@gmail.com, mfr...@vt.edu, adolfo.r...@pal-robotics.com
Thanks for the comments,

it seems that we are able to find (more or less) good/satisfying PIDs for all separate joint respectively following the approach mentioned above.
However, as soon as we allow several joints to be revolute again at the same time, The behaviour is bad again - as Adolfo already expected for the obvious reasons.
We again see highly oscillating values in the joint controllers changing the sign evey update cycle.

Some things that we are currently thinking about:
- As we do not know realistic values for damping, friction and so on, so far, we tried to use default values (or simply remove the respective tags from the URDF or the gazebo extension XACRO). In fact, we currently only set the <matrial> in the gazebo extension and use damping=0 and friction=0 in the URDF. (Friction is not implemented in Gazebo anyway, isn't it?)
Maybe setting some of these values would help reduce the oscillation and help in the PID tuning. However, I don't know what should be set or how we could approximate the respective values for our robot. Any good default values? Ideas?

- We also have had the <safety_controller> tag in our URDF. There were values for k_p and k_v, where I don't know where they come from. When I removed the tag, the controller seems to behave (at least a bit) better. Any counter-arguments against removing this tag from the URDF?

- Is it possible that a slower update frequency for the JointVelocityController might help the problem? Is this update frequency parameterizable? Where can I set it? I think the default is the gazebo tick rate, isn't it?


@Adolfo:
Can you elaborate a bit more on what frequency-domain tools you were using? Do you mean Bode-Diagram and stuff like that?
So you have a mathematical model for your hardware, right?



Best,
Felix
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-robot-control+unsubscri...@googlegroups.com.

For more options, visit https://groups.google.com/d/optout.

--
You received this message because you are subscribed to the Google Groups "ROS/Orocos Robot Control Special Interest Group" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-robot-control+unsub...@googlegroups.com.
For more options, visit https://groups.google.com/d/optout.



--

Felix Meßmer

unread,
Jul 4, 2014, 8:45:04 AM7/4/14
to ros-sig-ro...@googlegroups.com, felixm...@gmail.com, mfr...@vt.edu, adolfo.r...@pal-robotics.com
Oh, two more things, that I cannot explain at the moment:

When I have a look at the process_value entry in the JointVelocityController state message, this should be the actual/current joint velocity, right?
This value is retrieved directly from the HardwareInterface/GazeboHandle joint_->getVelocity(),right?
How can it be that the process_value sometimes is higher than the velocity limit specified in the URDF? This mainly happens, when in the oscillation case, where it the arm is actually not moving at all (probably because the velocities equalize themselves).

Similar thing with the efforts.
When looking at the /joint_states/effort[] values, they seem to be correctly clamped to the effort limit as specified in the URDF.
However, using only one revolute joint (the others fixed) this effort sometimes is already used up just to keep the joint at velocity 0.
When we now command a velocity in the same direction as the effort (e.g. send negative velocity in case current effort is -effort_limit), the arm move but the current effort still is equal to the previous effort value (still -effort_limit).
How is it possible to move without being allowed to exceed the effort limit? (I saw that the command value in the state message of the JointVelocityController has values much higher than the effort limit (which seems to be ok, as the documentation for SetForce() says that the commanded effort is truncated to the effort limit).

....Strange things, I cannot explain....

Adolfo Rodríguez Tsouroukdissian

unread,
Jul 7, 2014, 4:47:35 AM7/7/14
to Felix Meßmer, ros-sig-ro...@googlegroups.com, Michael Francis
On Fri, Jul 4, 2014 at 2:30 PM, Felix Meßmer <felixm...@gmail.com> wrote:
Thanks for the comments,

it seems that we are able to find (more or less) good/satisfying PIDs for all separate joint respectively following the approach mentioned above.
However, as soon as we allow several joints to be revolute again at the same time, The behaviour is bad again - as Adolfo already expected for the obvious reasons.
We again see highly oscillating values in the joint controllers changing the sign evey update cycle.

Some things that we are currently thinking about:
- As we do not know realistic values for damping, friction and so on, so far, we tried to use default values (or simply remove the respective tags from the URDF or the gazebo extension XACRO). In fact, we currently only set the <matrial> in the gazebo extension and use damping=0 and friction=0 in the URDF. (Friction is not implemented in Gazebo anyway, isn't it?)

I think not, and I couldn't find 
Maybe setting some of these values would help reduce the oscillation and help in the PID tuning. However, I don't know what should be set or how we could approximate the respective values for our robot. Any good default values? Ideas?

I'm not sure. Gazebo's changelog and roadmap don't make much mention of it. Some time ago it was in the roadmap, but not anymore.

- We also have had the <safety_controller> tag in our URDF. There were values for k_p and k_v, where I don't know where they come from.

You can find some doc in the PR2 pages, which has not been migrated to the ros_control wiki:

http://wiki.ros.org/pr2_controller_manager/safety_limits
 
When I removed the tag, the controller seems to behave (at least a bit) better.

Maybe the gains are not set correctly.
 
Any counter-arguments against removing this tag from the URDF?

Using the safety controller specification is not mandatory.

- Is it possible that a slower update frequency for the JointVelocityController might help the problem? Is this update frequency parameterizable? Where can I set it? I think the default is the gazebo tick rate, isn't it?

All controllers will get their update() method called at the same periodic frequency. For the GazeboRosControlPlugin plugin, you can set it like so from the URDF:

<gazebo>
  <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
    <controlPeriod>0.001</controlPeriod>
  </plugin>
</gazebo>
The code that does this is here:

https://github.com/ros-simulation/gazebo_ros_pkgs/blob/hydro-devel/gazebo_ros_control/src/gazebo_ros_control_plugin.cpp#L117

You can additionally decide to skip doing work on a per-controller basis if you want, say to run a controllers computations every n controller_manager updates.
 


@Adolfo:
Can you elaborate a bit more on what frequency-domain tools you were using? Do you mean Bode-Diagram and stuff like that?
So you have a mathematical model for your hardware, right?

We identify the plant by exciting it with signals of varying frequency, and then run some frequency-domain tools from Matlab. There are some building blocks for  doing a sine sweep in the control_toolbox package.

https://github.com/ros-controls/control_toolbox/tree/indigo-devel/include/control_toolbox

Adolfo Rodríguez Tsouroukdissian

unread,
Jul 7, 2014, 5:04:56 AM7/7/14
to Felix Meßmer, ros-sig-ro...@googlegroups.com, Michael Francis
On Fri, Jul 4, 2014 at 2:45 PM, Felix Meßmer <felixm...@gmail.com> wrote:
Oh, two more things, that I cannot explain at the moment:

When I have a look at the process_value entry in the JointVelocityController state message, this should be the actual/current joint velocity, right?
This value is retrieved directly from the HardwareInterface/GazeboHandle joint_->getVelocity(),right?

How can it be that the process_value sometimes is higher than the velocity limit specified in the URDF? This mainly happens, when in the oscillation case, where it the arm is actually not moving at all (probably because the velocities equalize themselves).

Do you get constant high velocities, isolated peaks or noise?.

Similar thing with the efforts.
When looking at the /joint_states/effort[] values, they seem to be correctly clamped to the effort limit as specified in the URDF.
However, using only one revolute joint (the others fixed) this effort sometimes is already used up just to keep the joint at velocity 0.

If there's a load to overcome, like gravity, it makes sense to have a nonzero effort to keep the joint velocity equal to zero.
 
When we now command a velocity in the same direction as the effort (e.g. send negative velocity in case current effort is -effort_limit), the arm move but the current effort still is equal to the previous effort value (still -effort_limit).

This sounds unexpected.
 
How is it possible to move without being allowed to exceed the effort limit? (I saw that the command value in the state message of the JointVelocityController has values much higher than the effort limit (which seems to be ok, as the documentation for SetForce() says that the commanded effort is truncated to the effort limit).

I don't know what can be happening here. I suggest using a debugger and follow the trail until the unexpected action happens, which can be on how commands are sent to Gazebo, within Gazebo itself, or on how the state is read from Gazebo.

HTH,

Adolfo.

P.S. This thread has diverged significantly from its subject. Since very interesting discussions are taking place here, it would be nice for others to easily find them. I appreciate it if we create a new thread with an appropriate title the next time the subject strays from the original post. Smaller, focused threads are easier to find.

mfr...@vt.edu

unread,
Jul 8, 2014, 1:53:14 PM7/8/14
to ros-sig-ro...@googlegroups.com, mfr...@vt.edu
Sorry for the late response Adolfo,

First of all thanks for the feedback. I guess what my main concern is how can I extract the velocity data being sent through the trajectory msg? I started digging around and came to the conclusion that I dont fully understand the difference between "effort_controllers/JointTrajectoryController" and "position_controllers/JointTrajectoryController".

At first I thought "effort_controllers/JointTrajectoryController" was giving me the relative position to which my joint should move to. It did this by connecting and registering a  "hardware_interface::EffortJointInterface jnt_pos_interface" object to a array named cmd[ ] (This is all from this tutorial). The cmd array had only one value for each joint, that being the relative position. Adolfo am I correct in assuming that? Or is the value being sent something different?

If  I am correct in my assumption from above what is "position_controllers/JointTrajectoryController" for (I havent tried to use this controller yet)?

Also I was wondering does "effort_controllers/JointTrajectoryController" use joint_position_controller.cpp located in ros_controllers/effort_controllers/src directory? If so does the cmd [ ] (mentioned above) use the setCommand() function to get its target position data?

Finally I just wanted to know if I could use "effort_controllers/JointTrajectoryController" and some how grab the velocity values coming from the trajectory msg from moveit using it?

Mike 
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-robot-control+unsub...@googlegroups.com.

Adolfo Rodríguez Tsouroukdissian

unread,
Jul 9, 2014, 2:45:06 AM7/9/14
to Michael Francis, ros-sig-ro...@googlegroups.com
On Tue, Jul 8, 2014 at 7:53 PM, <mfr...@vt.edu> wrote:
Sorry for the late response Adolfo,

First of all thanks for the feedback. I guess what my main concern is how can I extract the velocity data being sent through the trajectory msg? I started digging around and came to the conclusion that I dont fully understand the difference between "effort_controllers/JointTrajectoryController" and "position_controllers/JointTrajectoryController".

The former produces effort commands that realize the desired trajectory, while the latter produces position commands that do the same thing. You use one or the other depending on whether your hardware exposes effort or position controlled joints.

Internally, when the trajectory is sampled, one has access to the desired position, velocity and acceleration. For position controlled joints it suffices to forward the desired position. For effort controlled joints, a PID around position is implemented (note that we also have access to the current position and velocity to compute errors).

At first I thought "effort_controllers/JointTrajectoryController" was giving me the relative position to which my joint should move to.

No, it does not produce relative increments.
 
It did this by connecting and registering a  "hardware_interface::EffortJointInterface jnt_pos_interface" object to a array named cmd[ ] (This is all from this tutorial). The cmd array had only one value for each joint, that being the relative position. Adolfo am I correct in assuming that? Or is the value being sent something different?

cmd[] contains the joint effort to apply in this control cycle. It's not a relative value. The same applies for position references, they are not relative.

 
If  I am correct in my assumption from above what is "position_controllers/JointTrajectoryController" for (I havent tried to use this controller yet)?

Also I was wondering does "effort_controllers/JointTrajectoryController" use joint_position_controller.cpp located in ros_controllers/effort_controllers/src directory? If so does the cmd [ ] (mentioned above) use the setCommand() function to get its target position data?

No, "effort_controllers/JointTrajectoryController" does not depend on the "effort_controllers" package. What lead you to believe this?. You can verify dependencies of a package by using rospack:

rospack depends joint_trajectory_controller | grep effort_controllers  # returns an empty list


Finally I just wanted to know if I could use "effort_controllers/JointTrajectoryController" and some how grab the velocity values coming from the trajectory msg from moveit using it?

If you have velocity-controlled joints, keep an eye on https://github.com/ros-controls/ros_controllers/issues/43
This would be the right way to do it.

Adolfo.

To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-robot-co...@googlegroups.com.

For more options, visit https://groups.google.com/d/optout.

mfr...@vt.edu

unread,
Jul 10, 2014, 1:10:18 PM7/10/14
to ros-sig-ro...@googlegroups.com, mfr...@vt.edu, adolfo.r...@pal-robotics.com
How exactly is the effort value calculated?
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-robot-control+unsubscri...@googlegroups.com.

For more options, visit https://groups.google.com/d/optout.

--
You received this message because you are subscribed to the Google Groups "ROS/Orocos Robot Control Special Interest Group" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-robot-control+unsub...@googlegroups.com.
For more options, visit https://groups.google.com/d/optout.



--

Adolfo Rodríguez Tsouroukdissian

unread,
Jul 11, 2014, 10:38:21 AM7/11/14
to Michael Francis, ros-sig-ro...@googlegroups.com
On Thu, Jul 10, 2014 at 7:10 PM, <mfr...@vt.edu> wrote:
How exactly is the effort value calculated?

mfr...@vt.edu

unread,
Jul 11, 2014, 10:57:26 AM7/11/14
to ros-sig-ro...@googlegroups.com, mfr...@vt.edu, adolfo.r...@pal-robotics.com
Adolfo

Thank you soo much for the link, it really helped me break down the confusion :).  My next question then is if the effort controller is outputing a position that uses the position error, and velocity error, how can I extract the velocity error? If possible I would like to continue using the effort controller and extract the velocity error from the command  , so that I can control the arm using the velocity error. This way i can use velocity to control the arm and use the position error to determine other factors. Or should I go another route and use the velocity controller created for the joint_trajectory_controllers but still not released(https://github.com/ros-controls/ros_controllers/pull/64)?

Mike

Adolfo Rodríguez Tsouroukdissian

unread,
Jul 14, 2014, 4:01:10 AM7/14/14
to Michael Francis, ros-sig-ro...@googlegroups.com
On Fri, Jul 11, 2014 at 4:57 PM, <mfr...@vt.edu> wrote:
Adolfo

Thank you soo much for the link, it really helped me break down the confusion :).  My next question then is if the effort controller is outputing a position that uses the position error, and velocity error, how can I extract the velocity error? If possible I would like to continue using the effort controller and extract the velocity error from the command  , so that I can control the arm using the velocity error. This way i can use velocity to control the arm and use the position error to determine other factors. Or should I go another route and use the velocity controller created for the joint_trajectory_controllers but still not released(https://github.com/ros-controls/ros_controllers/pull/64)?

Mike,

You already asked this question, the original answer still holds:

If you have velocity-controlled joints, keep an eye on https://github.com/ros-controls/ros_controllers/issues/43
This would be the right way to do it.

Supporting velocity-controlled joints implies implementing a new specialization for the HardwareInterfaceAdapter class. Only this file needs to be touched:

https://github.com/ros-controls/ros_controllers/blob/indigo-devel/joint_trajectory_controller/include/joint_trajectory_controller/hardware_interface_adapter.h
Reply all
Reply to author
Forward
0 new messages