Problems with controlling joint velocity

466 views
Skip to first unread message

Raghav Malik

unread,
May 31, 2017, 3:38:20 PM5/31/17
to ROS/Orocos Robot Control Special Interest Group
Hi everybody,

I followed along with the Gazebo and ROS JointPositionController tutorial for RRBot here, and got it working just fine. However, when I tried modifying it to control velocity instead of position the setup immediately broke. The only change I made to the original was replacing "type: effort_controllers/JointPositionController" with "type: effort_controllers/JointVelocityController". Loading the controller through a service call returns success, but the visualization in gazebo immediately breaks and the joint velocities are set to "nan". Any ideas what I am doing wrong? Perhaps there are additional steps one must take when creating a velocity controller? I've been looking online for some kind of explanation but haven't had much luck so far. 

Any help is appreciated.

Cheers,
Raghav Malik


Toni Oliver

unread,
Jun 1, 2017, 7:51:02 AM6/1/17
to Raghav Malik, ROS/Orocos Robot Control Special Interest Group
Hi Raghav,

I think you will need to modify your xacro so that the transmissions have a VelocityJointInterface instead of an EffortJointInterface.

<transmission name="tran1">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="joint1">
      <hardwareInterface>VelocityJointInterface</hardwareInterface>
    </joint>
    <actuator name="motor1">
      <hardwareInterface>VelocityJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>

--
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.



--

Toni Oliver
Head of Software
+44 20 7700 2487
 


Shadow Robot Company Ltd.
251 Liverpool Road, N1 1LX, UK
Registered Number 3308007 (England & Wales)


 


We're hiring Software Developers! - visit our website for more details.

Shadow Robot Company Ltd.
251 Liverpool Road, N1 1LX, UK
Registered Number 3308007 (England & Wales)

Raghav Malik

unread,
Jun 1, 2017, 9:17:44 AM6/1/17
to ROS/Orocos Robot Control Special Interest Group, malikr...@gmail.com
Hi Toni,

Thank you for your response. To clarify, I would like to be able to achieve a certain angular velocity to a joint by changing the effort about that joint. I was under the impression that the hardware interfaces represent what the controller is outputting? I would still like the controller to give me values for effort, but this time to maintain a velocity instead of a position. Do I still need the hardware interface to be a velocity interface?

Cheers,
Raghav Malik

Andriy Petlovanyy

unread,
Jun 1, 2017, 10:07:32 AM6/1/17
to Raghav Malik, ROS/Orocos Robot Control Special Interest Group

Hi Raghav,

Please find my small project here
It is basically vertical motor with attached wheel to it (I have used it as demo for simple ROS serial integration).
I have managed to use effort_controllers/JointVelocityController with EffortJointInterface.
Here you can find joint definition.
Hope you'll find it useful.

Thanks

Best regards,
Andriy

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.

Toni Oliver

unread,
Jun 1, 2017, 11:04:03 AM6/1/17
to Raghav Malik, ROS/Orocos Robot Control Special Interest Group
Hi Raghav,

You are right, I misread your email and thought you were trying to use velocity_controllers/JointVelocityController.

Andriy's example should help you find the problem.

Cheers,
Toni

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

Raghav Malik

unread,
Jun 2, 2017, 9:06:39 AM6/2/17
to ROS/Orocos Robot Control Special Interest Group, malikr...@gmail.com
Hi Andriy,

Thank you very much. It was looking at your project that got me to the answer. My mistake was in not adjusting the PID gains for velocity control which is why it quickly grew out of bounds and became unstable. Adding the effort limits and adjusting my gains fixed the issue.

Cheers,
Raghav
Reply all
Reply to author
Forward
0 new messages