robot wheels go to zero position(blow up) when inertia values are small while controller is launched
Hi, I am trying to model a three-wheel omni-directional robot.
my model works fine with big inertia values for the wheels. But when I change the inertia wheels to the real values the model doesn't load properly in gazebo.
The robot looks like this when wheels inertia values are large(i adjust the inertia values by changing the mass)
after adjusting wheel mass the model blows up
This is how the model looks after updating mass values.
the following is a part of my urdf (xacro) model for base link and one of the wheels(rightwheel). leftwheel and left2_wheel have similar codes.
<xacro:property name="rob_scale" value="0.225"/>
<xacro:property name="right_wheel_x" value="${rob_scale*2.195}"/>
<xacro:property name="right_wheel_y" value="${rob_scale*0}"/>
<xacro:property name="right_wheel_z" value="${rob_scale*0.27}"/>
<xacro:property name="right_wheel_length" value="${rob_scale*0.07}"/>
<xacro:property name="right_wheel_radius" value="${rob_scale*0.27}"/>
<xacro:property name="right_wheel_mass" value="${rob_scale}"/>
<!--Interial macros-->
<xacro:macro name="cylinder_inertia" params="m r h">
<inertial>
<mass value="${m}"/>
<inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0" iyy="${m*(3*r*r+h*h)/12}" iyz = "0" izz="${m*r*r/2}"/>
</inertial>
</xacro:macro>
<xacro:macro name="box_inertia" params="m w h d">
<inertial>
<mass value="${m}"/>
<inertia ixx="${m / 12.0 * (d*d + h*h)}" ixy="0.0" ixz="0.0" iyy="${m / 12.0 * (w*w + h*h)}" iyz="0.0" izz="${m / 12.0 * (w*w + d*d)}"/>
</inertial>
</xacro:macro>
<link name="base_link">
<inertial>
<mass value="200"/>
<origin xyz="0 0 ${base_z}" rpy="0 0 3.14"/>
<inertia ixx="0.738" ixy="0" ixz="0" iyy="0.738" iyz="-0.000000" izz="1.304"/>
</inertial>
<visual>
<origin xyz="0 0 ${base_z}" rpy="0 0 3.14"/>
<geometry>
<mesh filename="package://rob_pkg/meshes/two_plate_s.dae" />
</geometry>
<material name="red"/>
</visual>
<collision >
<origin xyz="0 0 ${base_z}" rpy="0 0 3.14"/>
<geometry>
<mesh filename="package://rob_pkg/meshes/two_plate_s.dae" />
</geometry>
</collision>
</link>
<link name="link_right_wheel">
<mass value="${right_wheel_mass}"/>
<origin rpy="0 ${M_PI/2} 0" xyz="${right_wheel_x} ${right_wheel_y} ${right_wheel_z}"/>
<collision name="link_right_wheel_collision">
<geometry>
<cylinder length="${right_wheel_length}" radius="${right_wheel_radius}" />
</geometry>
<surface>
<bounce>
<restitution_coefficient>.2</restitution_coefficient>
</bounce>
<friction>
<ode>
<mu>1000000</mu>
<mu2>100</mu2>
<fdir1>1 0 0</fdir1>
<slip1> 0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<contact>
<ode/>
</contact>
</surface>
</collision>
<visual name="link_right_wheel_visual">
<geometry>
<cylinder length="${right_wheel_length}" radius="${right_wheel_radius}" />
</geometry>
</visual>
<xacro:cylinder_inertia m="${right_wheel_mass}" r="${right_wheel_radius}" h="${right_wheel_length}"/>
</link>
<joint name="joint_right_wheel" type="continuous">
<origin rpy="0 ${M_PI/2} 0" xyz="${right_wheel_x} 0 ${right_wheel_z}"/>
<child link="link_right_wheel"/>
<parent link="base_link"/>
<axis rpy="0 0 0" xyz="0 0 1"/>
</joint>
<!-- Rear wheels transmission -->
<transmission name="transmission_right_wheel">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_right_wheel">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_right_wheel">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
when i change rightwheelmass property to :
<xacro:property name="right_wheel_mass" value="${rob_scale * 100}"/>
the model workes fine.
the upper line increases wheel mass by a factor of 100
spawn_urdf.launch :
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find rob_pkg)/config/spawn_urdf.yaml" command="load"/>
<!-- load the controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/robot" args=" joint_state_controller
right_joint_velocity_controller
left_joint_velocity_controller
left2_joint_velocity_controller
"/>
<!-- convert joint states to TF transforms for rviz, etc -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
respawn="false" output="screen">
<remap from="/joint_states" to="/robot/joint_states" />
</node>
<param name="robot_description" command="$(find xacro)/xacro --inorder $(find rob_pkg)/urdf/my_model.xacro"/>
<!--Gazebo empty world launch file-->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="false" />
<arg name="gui" value="true" />
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="false"/>
<arg name="headless" value="false"/>
<arg name="verbose" value="true"/>
</include>
<node name="mybot_spawn" pkg="gazebo_ros" type="spawn_model" output="screen"
args="-urdf -param robot_description -model my_model" />
</launch>
spawn_urdf.yaml :
robot:
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 100
right_joint_velocity_controller:
type: effort_controllers/JointVelocityController
joint: joint_right_wheel
pid: {p: 10.0, i: 10.0, d: 0.01}
left_joint_velocity_controller:
type: effort_controllers/JointVelocityController
joint: joint_left_wheel
pid: {p: 10.0, i: 10.0, d: 0.01}
left2_joint_velocity_controller:
type: effort_controllers/JointVelocityController
joint: joint_left2_wheel
pid: {p: 10.0, i: 10.0, d: 0.01}
Asked by noyz on 2020-11-07 02:37:56 UTC
Comments
Did you solve the problem? I have the same situation and can't use real values.
Asked by muronglindong on 2021-11-01 04:44:59 UTC