Setting wheel velocity control without oscillation ?
Hello altruists, I am having a hard time in simulation of a robot in Gazebo, all other joints are position control only wheel is velocity control. but in my robot is not jittering on surface. My goal is to move it smoothly over horizontal or sloped surface. What is better way to control velocity?Whole robot weights 130 Kg in simulation. I cant use skid steer or differential drive transmission as wheel separation varies.
In the URDF:
<gazebo reference="wheel_front_left">
<kp>1e+13</kp>
<kd>1.0</kd>
<mu1>2.9</mu1>
<mu2>1.45</mu2>
<maxVel>0.0</maxVel>
<minDepth>0.001</minDepth>
</gazebo>
<joint name="omega_front_left" type="continuous">
<parent link="force_torque_sensor_link_front_left"/>
<child link="wheel_front_left"/>
<origin rpy="0.0 -1.570796 0.0" xyz="-0.15 0 0 "/>
<axis xyz="0 0 1"/>
<limit effort="2000" velocity="1.570796327"/>
<dynamics damping="0.7" friction="0.02" /> <!-- -->
</joint>
<transmission name="t_omega_front_left">
<type>transmission_interface/SimpleTransmission</type>
<joint name="omega_front_left">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="m_omega_front_left">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
<!-- <motorTorqueConstant>1580</motorTorqueConstant> -->
</actuator>
<gazebo reference="omega_front_left">
<implicitSpringDamper>1</implicitSpringDamper>
<!-- <cfm_damping>1</cfm_damping>
<implicit_spring_damper>1</implicit_spring_damper> -->
</gazebo>
in the joint control configuration:
omega_front_left_velocity_controller:
type: effort_controllers/JointVelocityController
joint: omega_front_left
pid: {p: 5000.0, i: 0.01, d: 0.0}
any suggestion is welcome.
Asked by Nurul Karim on 2018-09-06 08:46:48 UTC
Comments