How to avoid the joint deformed
Hi guys, I build an Ackermann car. Now I meet a problem, the joint is deformed by gravity, which is shown in the gazebo. But in Rviz or lift the car on a plant with front wheels not attach to the ground, the deform will not happen. If I cancel the gravity on the chassis, the deformation will also disappear, but gravity is necessary for driving test and simulation. These are my .xacro code for one side front wheel:
<link name="link_front_right_wheel">
<inertial>
<mass value="0.04"/>
<origin rpy="0 -1.5707 -1.5707" xyz="0 0 0"/>
<inertia ixx="1.36433e-5" ixy="0" ixz="0" iyy="1.36433e-5" iyz="0" izz="0.00002312"/> <!--ixx=iyy=mass*(L^2+3*R^2)/12;izz=mass*R*R/2-->>
</inertial>
<collision name="link_front_right_wheel_collision">
<origin rpy="0 -1.5707 -1.5707" xyz="0 0 0"/>
<geometry>
<cylinder length="0.025" radius="0.034"/>
</geometry>
</collision>
<visual>
<origin rpy="0 -1.5707 -1.5707" xyz="0 0 0"/>
<geometry>
<cylinder length="0.025" radius="0.034"/>
</geometry>
</visual>
</link>
<joint name="joint_front_right_wheel" type="continuous">
<origin rpy="0 0 0" xyz="0 -0.015 0"/>
<child link="link_front_right_wheel"/>
<parent link="link_front_right_axle"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
<limit effort="0.1" velocity="38"/>
<joint_properties damping="0.01" friction="0.3"/>
</joint>
<link name="link_front_right_axle">
<inertial>
<mass value="1e-5"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
<collision name="link_front_left_axle_collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.002"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.002"/>
</geometry>
</visual>
</link>
<joint name="joint_front_right_axle" type="continuous">
<origin rpy="0 0 0" xyz="0.06 -0.05 0.0"/>
<child link="link_front_right_axle"/>
<parent link="link_chassis"/>
<axis rpy="0 0 0" xyz="0 0 -1"/>
<limit lower="-0.610865" upper="0.523599"
effort="5" velocity="10"/>
<joint_properties damping="0.01" friction="0.3"/>
</joint>
Asked by wwxEnd on 2021-04-07 17:08:26 UTC
Comments