For our robot, we will be using the
GazeboRosImuSensor which is a SensorPlugin. A SensorPlugin must be attached to a link,
thus we will create an imu_link to which the IMU sensor will be attached. This link
will be referenced under the
Next, we will set /demo/imu as the topic to which the IMU will be publishing its information, and we will comply with REP145 by setting initalOrientationAsReference to false.
We will also add some noise to the sensor configuration using Gazebo's sensor noise model.
Note that if we have a lidar, we do not need IMU sensor: the nice thing about navigation packages of ROS2 is, they can merge sensors, when available, to increase accuracy, but can, if necessary, stick to a bare minimum.
<?xml version="1.0"?> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="navigation_bot"> <xacro:include filename="inertial_macros.xacro" /> <xacro:include filename="lidar.xacro" /> <xacro:include filename="camera.xacro" /> <xacro:include filename="imu_sensor.xacro" /> <xacro:include filename="gazebo_control.xacro" /> <xacro:include filename="robot_core.xacro" /> </robot>
<?xml version="1.0"?> <robot xmlns:xacro="http://www.ros.org/wiki/xacro"> <link name="imu_link"> <visual> <geometry> <box size="0.1 0.1 0.1"/> </geometry> </visual> <collision> <geometry> <box size="0.1 0.1 0.1"/> </geometry> </collision> <xacro:box_inertia m="0.1" w="0.1" d="0.1" h="0.1"/> </link> <joint name="imu_joint" type="fixed"> <parent link="base_link"/> <child link="imu_link"/> <origin xyz="0 0 0.01"/> </joint> <gazebo reference="imu_link"> <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> </robot>