Banana rotates by itself in Gazebo, I don't know why
I'm using gazebo7 in ubuntu16.04.
I launch a bannana model in gazebo,everything is ok but the bannana will rotate slowly by itself.
urdf below:
<?xml version="1.0" ?>
<robot name="Bannana">
<material name="yellow">
<color rgba="1 0.4 0 1"/>
</material>
<link name="Bannana">
<inertial>
<origin
xyz="0.0014177 4.15280000000162E-06 0.026526"
rpy="0.0 0.0 0.0" />
<mass
value="0.11082" />
<inertia
ixx="2.48347659000621E-05"
ixy="1.68484882757417E-06"
ixz="-1.05360215654521E-06"
iyy="0.000186690109925898"
iyz="1.13501975389491E-08"
izz="0.000175609996584435" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="1.5707963267949 0 0" />
<geometry>
<mesh
filename="package://object_description/meshes/Bannana.STL" />
</geometry>
<material name="yellow" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="1.5707963267949 0 0" />
<geometry>
<mesh
filename="package://object_description/meshes/Bannana.STL" />
</geometry>
</collision>
</link>
<gazebo reference="Bannana">
<material>Gazebo/Yellow</material>
</gazebo>
</robot>
launch file below:
<launch>
<!-- these are the arguments you can pass this launch file, for example paused:=true -->
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<arg name="world_name" default="$(find object_gazebo)/world/table.world"/>
<!-- We resume the logic in empty_world.launch -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
<arg name="world_name" value="$(arg world_name)" />
</include>
<!-- Load the URDF into the ROS Parameter Server -->
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find object_description)/urdf/Bannana.urdf'" />
<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf
-model Bannana
-param robot_description
-x 0
-y 0
-z 1 "/>
</launch>
Here is the workspace link,and there is a bannana.gif in the home directory to describe the question.
Can you give me some advice? Thanks a lot!