--- /dev/null
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+ <xacro:macro name="imu" params="name parent *origin">
+ <xacro:include filename="$(find twil_description)/xacro/eurocard.urdf.xacro" />
+
+ <xacro:eurocard name="${name}" parent="${parent}">
+ <xacro:insert_block name="origin"/>
+ </xacro:eurocard>
+
+ <gazebo reference="imu">
+ <sensor name="imu_sensor" type="imu">
+ <plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
+ <ros>
+ <namespace>/demo</namespace>
+ <remapping>~/out:=imu</remapping>
+ </ros>
+ <initial_orientation_as_reference>false</initial_orientation_as_reference>
+ </plugin>
+ <always_on>true</always_on>
+ <update_rate>100</update_rate>
+ <visualize>true</visualize>
+ <imu>
+ <angular_velocity>
+ <x>
+ <noise type="gaussian">
+ <mean>0.0</mean>
+ <stddev>2e-4</stddev>
+ <bias_mean>0.0000075</bias_mean>
+ <bias_stddev>0.0000008</bias_stddev>
+ </noise>
+ </x>
+ <y>
+ <noise type="gaussian">
+ <mean>0.0</mean>
+ <stddev>2e-4</stddev>
+ <bias_mean>0.0000075</bias_mean>
+ <bias_stddev>0.0000008</bias_stddev>
+ </noise>
+ </y>
+ <z>
+ <noise type="gaussian">
+ <mean>0.0</mean>
+ <stddev>2e-4</stddev>
+ <bias_mean>0.0000075</bias_mean>
+ <bias_stddev>0.0000008</bias_stddev>
+ </noise>
+ </z>
+ </angular_velocity>
+ <linear_acceleration>
+ <x>
+ <noise type="gaussian">
+ <mean>0.0</mean>
+ <stddev>1.7e-2</stddev>
+ <bias_mean>0.1</bias_mean>
+ <bias_stddev>0.001</bias_stddev>
+ </noise>
+ </x>
+ <y>
+ <noise type="gaussian">
+ <mean>0.0</mean>
+ <stddev>1.7e-2</stddev>
+ <bias_mean>0.1</bias_mean>
+ <bias_stddev>0.001</bias_stddev>
+ </noise>
+ </y>
+ <z>
+ <noise type="gaussian">
+ <mean>0.0</mean>
+ <stddev>1.7e-2</stddev>
+ <bias_mean>0.1</bias_mean>
+ <bias_stddev>0.001</bias_stddev>
+ </noise>
+ </z>
+ </linear_acceleration>
+ </imu>
+ </sensor>
+ </gazebo>
+ </xacro:macro>
+</robot>
\ No newline at end of file
<xacro:include filename="$(find twil_description)/xacro/tower.urdf.xacro" />
<xacro:include filename="$(find twil_description)/xacro/step_motor.urdf.xacro" />
<xacro:include filename="$(find twil_description)/xacro/sonar.urdf.xacro" />
+ <xacro:include filename="$(find twil_description)/xacro/imu.urdf.xacro" />
<link name="twil_origin" />
<origin xyz="0 -0.1 ${0.0015+0.3+0.003+0.1/2}" rpy="0.0 0.0 0.0" />
</xacro:eurocard>
+ <xacro:imu name="imu" parent="chassis">
+ <origin xyz="0 -0.2 ${0.0015+0.3+0.003+0.1/2}" />
+ </xacro:imu>
+
<xacro:cpu name="cpu" parent="chassis">
<origin xyz="0 0.0 ${0.0015+0.3+0.003+0.127+0.003+0.17}" rpy="0.0 0.0 ${M_PI/2}" />
</xacro:cpu>
+
<link name="chassis_top" />
<joint name="chassis_top_joint" type="fixed">
<xacro:include filename="$(find twil_description)/xacro/d435.urdf.xacro"/>
</xacro:if>
+
</robot>