123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657 |
- <?xml version="1.0"?>
- <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="imu">
- <xacro:macro name="imu" params="prefix:=imu">
- <!-- Create laser reference frame -->
- <link name="${prefix}_link">
- <inertial>
- <mass value="0.001" />
- <origin xyz="0 0 0" />
- <inertia ixx="0.001" ixy="0.0" ixz="0.0"
- iyy="0.001" iyz="0.0"
- izz="0.001" />
- </inertial>
- <visual>
- <origin xyz=" 0 0 0 " rpy="0 0 0" />
- <geometry>
- <box size="0.04 0.04 0.03" />
- </geometry>
- <material name="tire_mat"/>
- </visual>
- <collision>
- <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
- <geometry>
- <box size="0.04 0.04 0.03" />
- </geometry>
- </collision>
- </link>
- <gazebo reference="${prefix}_link">
- <material>Gazebo/Black</material>
- </gazebo>
- <gazebo reference="${prefix}_link">
- <gravity>true</gravity>
- <sensor name="imu_sensor" type="imu">
- <always_on>true</always_on>
- <update_rate>100</update_rate>
- <visualize>true</visualize>
- <topic>/imu_data</topic>
- <plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
- <topicName>/imu_data</topicName>
- <bodyName>imu_link</bodyName>
- <updateRateHZ>100.0</updateRateHZ>
- <gaussianNoise>0.0</gaussianNoise>
- <xyzOffset>0 0 0</xyzOffset>
- <rpyOffset>0 0 0</rpyOffset>
- <frameName>imu_link</frameName>
- </plugin>
- <pose>0 0 0 0 0 0</pose>
- </sensor>
- </gazebo>
- </xacro:macro>
- <xacro:imu prefix="imu"/>
- </robot>
|