ppovb5fc7/gazebo/test/worlds/imu_sensor_test.world

518 lines
16 KiB
XML

<?xml version="1.0" ?>
<sdf version="1.4">
<world name="default">
<physics type="ode">
<gravity>0.000000 0.000000 -9.810000</gravity>
<ode>
<solver>
<type>quick</type>
<iters>1000</iters>
<precon_iters>0</precon_iters>
<sor>1.000000</sor>
</solver>
<constraints>
<cfm>0.000000</cfm>
<erp>0.200000</erp>
<contact_max_correcting_vel>100.000000</contact_max_correcting_vel>
<contact_surface_layer>0.01000</contact_surface_layer>
</constraints>
</ode>
<bullet>
<solver>
<type>sequential_impulse</type>
<iters>1000</iters>
<sor>1.000000</sor>
</solver>
<constraints>
<cfm>0.000000</cfm>
<erp>0.200000</erp>
<split_impulse>true</split_impulse>
<split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
<contact_surface_layer>0.00000</contact_surface_layer>
</constraints>
</bullet>
<real_time_update_rate>0.000000</real_time_update_rate>
<max_step_size>0.001</max_step_size>
</physics>
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://ground_plane</uri>
</include>
<model name="model_pendulum">
<pose>0.0 0.0 10.2 1.57079633 0.0 0.0</pose>
<link name="link_pendulum_rod">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 -10.0 0.0 0.0 0.0</pose>
<inertia>
<ixx>1e-1</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>1e-1</iyy>
<iyz>0.0</iyz>
<izz>1e-1</izz>
</inertia>
<mass>5.0</mass>
</inertial>
<velocity_decay>
<linear>0.0</linear>
<angular>0.0</angular>
</velocity_decay>
<visual name="visual_cylinder">
<pose>0.0 0.0 -5.0 0.0 0.0 0.0</pose>
<geometry>
<cylinder>
<radius>0.05</radius>
<length>10.0</length>
</cylinder>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Green</name></script>
</material>
</visual>
<collision name="collision_cylinder">
<pose>0.0 0.0 -5.0 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<cylinder>
<radius>0.05</radius>
<length>10.0</length>
</cylinder>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
</link>
<joint name="joint_0" type="revolute">
<parent>world</parent>
<child>link_pendulum_rod</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<xyz>1.0 0.0 0.0</xyz>
</axis>
</joint>
<link name="link_pendulum_ball">
<pose>0.0 0.0 -10.0 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertia>
<ixx>1e-1</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>1e-1</iyy>
<iyz>0.0</iyz>
<izz>1e-1</izz>
</inertia>
<mass>5.0</mass>
</inertial>
<velocity_decay>
<linear>0.0</linear>
<angular>0.0</angular>
</velocity_decay>
<visual name="visual_sphere">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name="collision_sphere">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
<sensor name="pendulum_imu_sensor" type="imu">
<always_on>1</always_on>
<plugin name="pendulum_imu_sensor_plugin" filename="libImuSensorPlugin.so">
<custom>1</custom>
</plugin>
</sensor>
</link>
<joint name="joint_1" type="revolute">
<parent>link_pendulum_rod</parent>
<child>link_pendulum_ball</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>0</lower>
<upper>0</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<static>false</static>
</model>
<model name="model_ramp">
<pose>3.0 0.0 1.0 0.0 0.5 0.0</pose>
<link name="link_ramp">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 -10.0 0.0 0.0 0.0</pose>
<inertia>
<ixx>1e-1</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>1e-1</iyy>
<iyz>0.0</iyz>
<izz>1e-1</izz>
</inertia>
<mass>5.0</mass>
</inertial>
<velocity_decay>
<linear>0.0</linear>
<angular>0.0</angular>
</velocity_decay>
<visual name="visual_sphere">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>5 5 0.01</size>
</box>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Green</name></script>
</material>
</visual>
<collision name="collision_box">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<box>
<size>5 5 0.01</size>
</box>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
</link>
<static>true</static>
</model>
<model name="model_ball">
<pose>2.0 -0.5 10.0 0.0 0.0 0.0</pose>
<link name="link_ball">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertia>
<ixx>1e-1</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>1e-1</iyy>
<iyz>0.0</iyz>
<izz>1e-1</izz>
</inertia>
<mass>5.0</mass>
</inertial>
<velocity_decay>
<linear>0.0</linear>
<angular>0.0</angular>
</velocity_decay>
<visual name="visual_sphere">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<geometry>
<sphere>
<radius>0.3</radius>
</sphere>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Green</name></script>
</material>
</visual>
<collision name="collision_sphere">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.3</radius>
</sphere>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
<sensor name="ball_imu_sensor" type="imu">
<always_on>1</always_on>
<plugin name="ball_imu_sensor_plugin" filename="libImuSensorPlugin.so">
<custom>1</custom>
</plugin>
</sensor>
</link>
<static>false</static>
</model>
<model name="model_ball_no_friction">
<pose>2.0 0.5 10.0 0.0 0 0.0</pose>
<link name="link_ball_no_friction">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertia>
<ixx>1e-1</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>1e-1</iyy>
<iyz>0.0</iyz>
<izz>1e-1</izz>
</inertia>
<mass>5.0</mass>
</inertial>
<velocity_decay>
<linear>0.0</linear>
<angular>0.0</angular>
</velocity_decay>
<visual name="visual_sphere">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<geometry>
<sphere>
<radius>0.3</radius>
</sphere>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Green</name></script>
</material>
</visual>
<collision name="collision_sphere">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.3</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
</ode>
</friction>
</surface>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
<sensor name="ball_no_friction_imu_sensor" type="imu">
<always_on>1</always_on>
<plugin name="ball_no_friction_imu_sensor_plugin" filename="libImuSensorPlugin.so">
<custom>1</custom>
</plugin>
</sensor>
</link>
<static>false</static>
</model>
<model name="model_floating_imu">
<pose>3.0 -3.0 1.0 0.0 0.0 0.0</pose>
<link name="link_floating_imu">
<pose>0.0 0.0 -0.05 0.0 0.0 0.0</pose>
<inertial>
<inertia>
<ixx>1e-1</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>1e-1</iyy>
<iyz>0.0</iyz>
<izz>1e-1</izz>
</inertia>
<mass>5.0</mass>
</inertial>
<visual name="visual_sphere">
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/PaintedWall</name>
</script>
</material>
</visual>
<visual name="visual_x">
<pose>0.15 0.1 0.0 0.0 1.5708 0.0</pose>
<geometry>
<cylinder>
<length>0.30</length>
<radius>0.01</radius>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Red</name>
</script>
</material>
</visual>
<visual name="visual_y">
<pose>0.0 0.25 0.0 1.5708 0.0 0.0</pose>
<geometry>
<cylinder>
<length>0.30</length>
<radius>0.01</radius>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Green</name>
</script>
</material>
</visual>
<visual name="visual_z">
<pose>0.0 0.1 0.15 0.0 0.0 0.0</pose>
<geometry>
<cylinder>
<length>0.30</length>
<radius>0.01</radius>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Blue</name>
</script>
</material>
</visual>
<collision name="collision_sphere">
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
</collision>
<gravity>false</gravity>
<self_collide>false</self_collide>
<kinematic>false</kinematic>
<sensor name="ball_floating_imu_sensor" type="imu">
<pose>0 0.1 0 0 0 0</pose>
<always_on>1</always_on>
<plugin name="ball_floating_imu_sensor_plugin" filename="libImuSensorPlugin.so">
<custom>1</custom>
</plugin>
</sensor>
</link>
<!-- link_floating_imu_2 has a different orientation than
link_floating_imu. The purpose of this link is to test
a scenario where two robots are spawned in a world
facing different directions. And assuming
ImuSensor::SetWorldToReferencePose is called for each
IMU the same way, then the two imu's should have the same
reference frame for orientation.
-->
<link name="link_floating_imu_2">
<pose>0.0 -0.40 -0.05 0.0 0.0 1.8</pose>
<inertial>
<inertia>
<ixx>1e-1</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>1e-1</iyy>
<iyz>0.0</iyz>
<izz>1e-1</izz>
</inertia>
<mass>5.0</mass>
</inertial>
<visual name="visual_sphere">
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/WoodFloor</name>
</script>
</material>
</visual>
<visual name="visual_x">
<pose>0.21 0.0 0.0 0.0 1.5708 0.0</pose>
<geometry>
<cylinder>
<length>0.30</length>
<radius>0.01</radius>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Red</name>
</script>
</material>
</visual>
<visual name="visual_y">
<pose>0.1 0.15 0.0 1.5708 0.0 0.0</pose>
<geometry>
<cylinder>
<length>0.30</length>
<radius>0.01</radius>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Green</name>
</script>
</material>
</visual>
<visual name="visual_z">
<pose>0.1 0.0 0.15 0.0 0.0 0.0</pose>
<geometry>
<cylinder>
<length>0.30</length>
<radius>0.01</radius>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Blue</name>
</script>
</material>
</visual>
<collision name="collision_sphere">
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
</collision>
<gravity>false</gravity>
<self_collide>false</self_collide>
<kinematic>false</kinematic>
<sensor name="ball_floating_imu_sensor_2" type="imu">
<pose>0.10 0 0 0 0 0</pose>
<always_on>1</always_on>
<plugin name="ball_floating_imu_sensor_plugin_2" filename="libImuSensorPlugin.so">
<custom>1</custom>
</plugin>
</sensor>
</link>
</model>
</world>
</sdf>