Gazebo | Ignition | Community
Ask Your Question
0

What is the velocity assigned to the gazebo-ros-conrtol controller

asked 2019-01-30 03:29:33 -0600

kumpakri gravatar image

When I create a transmission for the wheels of my robot like this

  <transmission name="tran_robot_wheel">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wheel_joint">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="wheel_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>

or

  <transmission name="tran_robot_wheel">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wheel_joint">
      <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
    </joint>
    <actuator name="wheel_motor">
      <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>

And I configure the controller as so

  joint_wheel_controller:
    type: effort_controllers/JointVelocityController
    joint: wheel_joint
    pid: {p: 100, i: 10, d: 0.1}

or

  joint_wheel_controller:
    type: velocity_controllers/JointVelocityController
    joint: wheel_joint
    pid: {p: 100, i: 10, d: 0.1}

And I run the simulation and sent a command to both left and right wheel to set velocity to 1.0

rostopic pub /robot/joint_wheel_controller/command std_msgs/Float64 "data: 1.0"

The robot moves about 1 meter in 10 second. The robot wheel turns once around in about 8 seconds. What kind of velocity unit is that? How do I convert it to m/s?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-02-22 03:39:31 -0600

kumpakri gravatar image

updated 2019-02-22 03:43:03 -0600

The robot wheel turns around once in about 8 seconds (6.283, actually), because the value assigned as velocity is angular velocity omega

omega = 2 * pi * f

that means the time t it takes to turn the wheel all the way around

t = 1/f

is

t = ( 2 * pi ) / omega = 2 * 3.1415 / 1 = 6.283 s

and you need to assign the velocity omega of 6.283 to achieve 1 rotation per second

omega = 2 * pi * f = 2 * 3.1415 * 1 = 6.283

To get the desired linear velocity v you divide the desired linear velocity v with the radius r of the wheel in meters.

v = 2 * pi * f * r = omega * r

omega = v / r

edit flag offensive delete link more

Comments

I noticed that, right after controllers are spawned. They start to receive some noise as commands. is this normal?

vaichu gravatar imagevaichu ( 2020-03-20 14:12:02 -0600 )edit

Why do you think they receive noise as commands? Do you see that on the command topic?

kumpakri gravatar imagekumpakri ( 2020-03-30 01:06:10 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2019-01-30 03:29:33 -0600

Seen: 15,848 times

Last updated: Feb 22 '19