Hi, I am trying to do simulate a differential robot (It's based on a real robot, so I can't change the position of things ). The robot got 2 motorized wheels and 3 casters wheels places as such :
The caster wheels don't have friction or joints, the mains wheels can touch the ground, and when I make it go straight the robot move. The problem is that when I when it to rotate (angular speed on Z ) the wheels rotates normally (each in opposite direction) but the robot doesn't move (the wheels accelerate at a moment, making it go forward then reverse to go back to the initial position, I guess it's the controller trying to fix it )
The urdf of the robot :
<!-- base -->
<xacro:property name="size_base" value="0.610" />
<xacro:property name="height_base" value="1.600" />
<xacro:property name="height_pillier" value="0.380" />
<xacro:property name="size_pillier" value="0.110" />
<xacro:property name="half_size_base" value="${size_base/2.0}" />
<xacro:property name="mass_pillier" value="0.1" />
<!-- WHEELS -->
<xacro:property name="wheel_length" value="0.045"/>
<xacro:property name="wheel_mass" value="5.05"/>
<xacro:property name="wheel_radius" value="0.100"/>
<xacro:property name="caster_wheel_length" value="0.030"/>
<xacro:property name="caster_wheel_mass" value="0.05"/>
<xacro:property name="caster_wheel_radius" value="0.040"/>
<xacro:property name="imu_offset_x" value="0.2085" />
<xacro:property name="imu_offset_y" value="-0.2902" />
<xacro:property name="imu_offset_z" value="0.1681" />
<xacro:property name="dummy_inertia" value="1e-09"/>
<material name="Black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<link name="base_footprint"/>
<joint name="base_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_footprint"/>
<child link="base_link" />
</joint>
<link name="base_link">
</link>
(I have troubles to put the whole urdf, I will try again tomorrow)
The wheels :
<xacro:macro name="origin_base">
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/>
</xacro:macro>
<xacro:macro name="wheel" params="rpy xyz name">
<xacro:macro name="origin_wheel">
<origin rpy="${rpy}" xyz="${xyz}"/>
</xacro:macro>
<link name="wheel_${name}_link">
<inertial>
<xacro:origin_base />
<mass value="${wheel_mass}" />
<inertia ixx="1.40041666667e-05" ixy="0" ixz="0" iyy="1.40041666667e-05" iyz="0" izz="2.56e-05" />
</inertial>
<collision>
<xacro:origin_base />
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
</collision>
<visual>
<xacro:origin_base />
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
<material name="green"/>
</visual>
</link>
<joint name="wheel_${name}_joint" type="continuous">
<parent link="wheel_axe"/>
<child link="wheel_${name}_link"/>
<xacro:origin_wheel />
<limit lower="-0.2" upper="0.2" effort="100" velocity="100"/>
<axis xyz="0 0 1"/>
</joint>
<gazebo reference="wheel_${name}_link">
<mu1 value="1.0"/>
<mu2 value="0.1"/>
<kp value="10000000.0" />
<kd value="1.0" />
<fdir1 value="1 0 0"/>
</gazebo>
<!-- transmission -->
<transmission name="wheel_${name}_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wheel_${name}_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="wheel_${name}_motor">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
And the control.yaml :
evt1_joint_publisher:
type: "joint_state_controller/JointStateController"
publish_rate: 50
evt1_velocity_controller:
type: "diff_drive_controller/DiffDriveController"
left_wheel: 'wheel_left_joint'
right_wheel: 'wheel_right_joint'
publish_rate: 50
pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
cmd_vel_timeout: 0.25
velocity_rolling_window_size: 2
# Base frame_id
base_frame_id: base_footprint
# Odometry fused with IMU is published by robot_localization, so
# no need to publish a TF based on encoders alone.
enable_odom_tf: false
# Husky hardware provides wheel velocities
estimate_velocity_from_position: false
# Wheel separation and radius multipliers
wheel_separation_multiplier: 1.0 # default: 1.0
wheel_radius_multiplier : 1.0 # default: 1.0
wheel_separation : 0.434
wheel_radius : 0.100
# Velocity and acceleration limits
# Whenever a min_* is unspecified, default to -max_*
linear:
x:
has_velocity_limits : true
max_velocity : 1.0 # m/s
min_velocity : -0.5 # m/s
has_acceleration_limits: true
max_acceleration : 0.8 # m/s^2
min_acceleration : -0.4 # m/s^2
has_jerk_limits : true
max_jerk : 5.0 # m/s^3
angular:
z:
has_velocity_limits : false
max_velocity : 1.7 # rad/s
has_acceleration_limits: false
max_acceleration : 1.5 # rad/s^2
has_jerk_limits : true
max_jerk : 2.5 # rad/s^3
the problem seems to be that the wheels don't stay straight (rotate on X ? ) and switch their contact, I don't know what cause it to occurs, or how to fix it. I tried a lot of things and can't figure out why this won't work. (I had made a robot with a different appearance, and it didn't have this type of behavior).
As anyone encounters that type of problems or know what can be the cause?
Thanks,
Jérémy