Fixed joint not working properly
Hi everyone! I'm new in Gazebo. I created a laser rangefinder model and a robot model in which I want to use it. When I try to fix the imported model with fixed joint or revolute joint with 0 limit, and start the simulation, Gazebo shows the following:
If I don't use any joints, the sensor just falls far down. Without a sensor, the robot looks normal during the simulation, as it should:
Listing of laser model.sdf file:
<?xml version='1.0'?>
<sdf version='1.6'>
<model name="VL6180">
<link name='body'>
<visual name='visual'>
<pose>-0.0024 -0.0014 0 0 0 0</pose>
<geometry>
<mesh>
<uri> model://VL6180/meshes/STL/VL6180X.stl </uri>
<scale> .001 .001 .001 </scale>
</mesh>
</geometry>
</visual>
<collision name='collision'>
<pose> 0 0 .0005 0 0 0 </pose>
<geometry>
<box>
<size>.0048 .0028 .001</size>
</box>
</geometry>
</collision>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.00003</mass>
<inertia>
<ixx>0.00000000000000001</ixx>
<ixy>0.00000000000000001</ixy>
<ixz>0.00000000000000001</ixz>
<iyy>0.00000000000000001</iyy>
<iyz>0.00000000000000001</iyz>
<izz>0.00000000000000001</izz>
</inertia>
</inertial>
<sensor type="ray" name="sensor">
<pose>0.0018 0 0 0 -1.5708 0</pose>
<visualize>true</visualize>
<update_rate> 30 </update_rate>
<ray>
<scan>
<horizontal>
<samples>50</samples>
<resolution>1</resolution>
<min_angle>-0.174533</min_angle>
<max_angle>0.174533</max_angle>
</horizontal>
<vertical>
<samples>50</samples>
<resolution>1</resolution>
<min_angle>-0.174533</min_angle>
<max_angle>0.174533</max_angle>
</vertical>
</scan>
<range>
<min>0.000001</min>
<max>0.6</max>
</range>
</ray>
</sensor>
</link>
</model>
</sdf>
Listing of robot model.sdf file:
<?xml version='1.0'?>
<sdf version='1.6'>
<model name="my_robot">
<frame name="robot"></frame>
<pose>0 0 0.25 0 0 0</pose>
<!-- <include>
<name>laser_1</name>
<uri>model://VL6180</uri>
<pose>0 0.0425 .003 3.14159 0 3.14159</pose>
</include>
-->
<link name='sole'>
<pose>0 0 0 1.5708 0 0</pose>
<visual name='sole_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri> model://Robot_model/meshes/STL/Sole.stl </uri>
<scale> .001 .001 .001 </scale>
</mesh>
</geometry>
</visual>
<collision name='sole_collision_box'>
<pose> 0 .049 0 -1.5708 0 0 </pose>
<geometry>
<box>
<size>.026 .016 .068</size>
</box>
</geometry>
</collision>
<collision name='sole_collision_cylinder'>
<pose> 0 .0075 0 -1.5708 0 0 </pose>
<geometry>
<cylinder>
<radius>.05</radius>
<length>.015</length>
</cylinder>
</geometry>
</collision>
<inertial>
<pose>0 .0128 0 0 0 0</pose>
<mass>.370</mass>
<inertia>
<ixx>0.000270821</ixx>
<ixy>0.00</ixy>
<ixz>0.00</ixz>
<iyy>0.000402393</iyy>
<iyz>0.00000</iyz>
<izz>0.000273382</izz>
</inertia>
</inertial>
</link>
<link name = 'cross'>
<pose>0 0 0.0725 0 0 1.5708</pose>
<visual name='cross_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri> model://Robot_model/meshes/STL/Cross.stl </uri>
<scale> .01 .01 .01 </scale>
</mesh>
</geometry>
</visual>
<collision name='cross_collision'>
<pose> 0 0 .0025 0 0 0 </pose>
<geometry>
<box>
<size>.022 .014 .005</size>
</box>
</geometry>
</collision>
<inertial>
<pose>0 ...