What is the velocity assigned to the gazebo-ros-conrtol controller
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?