ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

How to control velocity of joints in gazebo using ros_controllers?

asked 2019-06-22 04:55:39 -0500

asudot gravatar image

updated 2019-06-22 07:10:59 -0500

gvdhoorn gravatar image

I have four wheels connected to my robot base in gazebo and want to move the wheels at a desired velocity using Ros_Controllers. I am unable to set up the velocity controllers correctly.

<transmission name="tran6">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="youbot__wheel_joint_bl">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="motor6">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
</transmission>

Also in my config file i have included the controller as

wheel_bl_velocity_controller:
    type: effort_controllers/JointVelocityController
    joint: youbot__wheel_joint_bl
    pid: {p: 100.0, i: 0.01, d: 10.0

I then send the velocity command on the respective topic but the joint does not move at all in gazebo.

I gave also tried the velocity controller (loaded another file specifying the PID gains on the parameter server) instead of the effort controller but still it doesn't work.

The joint does move on using the effort_controllers/JointPositionController but velocity control is what I need. The joint position limits were excluded from the urdf while trying out the velocity controllers

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2019-11-28 08:08:29 -0500

lotfishtaine gravatar image

Try with :

<transmission name="tran6">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="youbot__wheel_joint_bl">
      <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
    </joint>
    <actuator name="motor6">
      <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
</transmission>

and for the yaml file, you need to specify : type: velocity_controllers/JointVelocityController

wheel_bl_velocity_controller:
    type: velocity_controllers/JointVelocityController
    joint: youbot__wheel_joint_bl
    pid: {p: 100.0, i: 0.01, d: 10.0

make sure you're using gazebo_ros_control

   <gazebo>
      <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
      </plugin>
    </gazebo>

and you spawn the controller and load yaml file in the launch file.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-06-22 04:55:39 -0500

Seen: 4,430 times

Last updated: Nov 28 '19