Sensor Noise Model - modulabs/gazebo-tutorial GitHub Wiki

Introduction

Gazebo๋Š” ๋งŽ์€ ์„ผ์„œ ๋ชจ๋ธ์„ ์ œ๊ณตํ•œ๋‹ค. ํ˜„์‹ค์—์„œ๋Š” ์„ผ์„œ๋“ค์€ ๋…ธ์ด์ฆˆ๋ฅผ ๋ณด์ด๋Š”๋ฐ, ์ฆ‰ ์ด์ƒ์ ์ธ ํ™˜๊ฒฝ์„ ๊ด€์ฐฐํ•  ์ˆ˜ ์—†๋‹ค. ๊ธฐ๋ณธ์ ์œผ๋กœ, Gazebo์˜ ์„ผ์„œ๋“ค์€ ์ด์ƒ์ ์ธ ํ™˜๊ฒฝ์„ ๊ด€์ฐฐํ•  ์ˆ˜ ์žˆ๋‹ค (๊ทธ๋Ÿฌ๋‚˜ IMU๋Š” ์•„๋‹ˆ๋‹ค; ์•„๋ž˜๋ฅผ ๋” ์ฝ์–ด๋ณด์„ธ์š”). ์ธ์‹(Perception) ์ฝ”๋“œ๋ฅผ ๊ตฌํ˜„ํ•  ์ˆ˜ ์žˆ๋Š” ์ข€ ๋” ํ˜„์‹ค์ ์ธ ํ™˜๊ฒฝ์„ ์ œ๊ณตํ•˜๊ธฐ์œ„ํ•ด, ์šฐ๋ฆฌ๋Š” Gazebo์˜ ์„ผ์„œ์— ์˜ํ•ด ๋งŒ๋“ค์–ด์ง„ ๋ฐ์ดํ„ฐ์— ๋…ธ์ด์ฆˆ๋ฅผ ๋ช…๋ฐฑํ•˜๊ฒŒ ์ถ”๊ฐ€ํ•  ํ•„์š”๊ฐ€ ์žˆ๋‹ค.

Gazebo๋Š” ์•„๋ž˜์™€ ๊ฐ™์€ ์„ผ์„œ ํƒ€์ž…์— ๋…ธ์ด์ฆˆ๋ฅผ ์ถ”๊ฐ€ํ•  ์ˆ˜ ์žˆ๋‹ค:

  • Ray (e.g., lasers)
  • Camera
  • IMU

Ray (laser) noise

Ray ์„ผ์„œ์˜ ๊ฒฝ์šฐ, ์šฐ๋ฆฌ๋Š” ๊ฐ ๋น”์˜ ๋ฒ”์œ„์— Gaussian noise๋ฅผ ์ถ”๊ฐ€ํ•  ์ˆ˜ ์žˆ๋‹ค. ๋‹น์‹ ์€ ๋…ธ์ด์ฆˆ ๊ฐ’์„ ์ƒ˜ํ”Œ๋งํ•  ๊ฐ€์šฐ์Šค ๋ถ„ํฌ(Gaussian distribution)์˜ ํ‰๊ท ๊ฐ’(the mean), ํ‘œ์ค€ํŽธ์ฐจ(the standard deviation)๋ฅผ ์„ค์ •ํ•  ์ˆ˜ ์žˆ๋‹ค. ๋…ธ์ด์ฆˆ๊ฐ’์€ ๊ฐ ๋น”๋งˆ๋‹ค ๋…๋ฆฝ์ ์œผ๋กœ ์ƒ˜ํ”Œ๋ง๋œ๋‹ค. ๋…ธ์ด์ฆˆ๋ฅผ ์ถ”๊ฐ€ํ•œ ํ›„์—, ๊ฒฐ๊ณผ ๋ฒ”์œ„๋Š” ์„ผ์„œ์˜ ์ตœ์†Œ ๋ฐ ์ตœ๋Œ€ ๋ฒ”์œ„์— ๋†“์—ฌ์ง„๋‹ค? (ํฌํ•จ?)

Ray ๋…ธ์ด์ฆˆ ๋ชจ๋ธ์„ ํ…Œ์ŠคํŠธ ํ•˜๊ธฐ ์œ„ํ•ด์„œ:

  1. ๋ชจ๋ธ ํด๋”๋ฅผ ๋งŒ๋“ ๋‹ค:

     mkdir -p ~/.gazebo/models/noisy_laser
    
  2. ๋ชจ๋ธ config file์„ ์ƒ์„ฑํ•œ๋‹ค:

    gedit ~/.gazebo/models/noisy_laser/model.config
    
  3. ์•„๋ž˜ ๋‚ด์šฉ์„ ๋ณต์‚ฌ, ๋ถ™์—ฌ๋„ฃ๊ธฐํ•œ๋‹ค:

    <?xml version="1.0"?>
    <model>
      <name>Noisy laser</name>
      <version>1.0</version>
      <sdf version='1.6'>model.sdf</sdf>
    
      <author>
       <name>My Name</name>
       <email>[email protected]</email>
      </author>
    
      <description>
        My noisy laser.
      </description>
    </model>
  4. ~/.gazebo/models/noisy_laser/model.sdf ํŒŒ์ผ์„ ์ƒ์„ฑํ•œ๋‹ค.

    gedit ~/.gazebo/models/noisy_laser/model.sdf
    
  5. ์•„๋ž˜ ๋‚ด์šฉ์„ ๋ณต์‚ฌ, ๋ถ™์—ฌ๋„ฃ๊ธฐํ•œ๋‹ค. ์ด ๋‚ด์šฉ์€ ๋ถ€๊ฐ€์ ์ธ ๋…ธ์ด์ฆˆ๊ฐ€ ํฌํ•จ๋œ ํ‘œ์ค€ Hokuyo model์˜ ๋ณต์‚ฌ๋ณธ์ด๋‹ค.

    <?xml version="1.0" ?>
    <sdf version="1.6">
      <model name="hokuyo">
        <link name="link">
          <gravity>false</gravity>
          <inertial>
            <mass>0.1</mass>
          </inertial>
          <visual name="visual">
            <geometry>
              <mesh>
                <uri>model://hokuyo/meshes/hokuyo.dae</uri>
              </mesh>
            </geometry>
          </visual>
          <sensor name="laser" type="ray">
            <pose>0.01 0 0.03 0 -0 0</pose>
            <ray>
              <scan>
                <horizontal>
                  <samples>640</samples>
                  <resolution>1</resolution>
                  <min_angle>-2.26889</min_angle>
                  <max_angle>2.268899</max_angle>
                </horizontal>
              </scan>
              <range>
                <min>0.08</min>
                <max>10</max>
                <resolution>0.01</resolution>
              </range>
              <noise>
                <type>gaussian</type>
                <mean>0.0</mean>
                <stddev>0.01</stddev>
              </noise>
            </ray>
            <plugin name="laser" filename="libRayPlugin.so" />
            <always_on>1</always_on>
            <update_rate>30</update_rate>
            <visualize>true</visualize>
          </sensor>
        </link>
      </model>
    </sdf>
  6. Gazebo๋ฅผ ์‹คํ–‰ํ•œ๋‹ค:

     gazebo
    
  7. noisy laser ๋ชจ๋ธ์„ ์‚ฝ์ž…ํ•œ๋‹ค: ์™ผ์ชฝ ํŒจ๋„์—์„œ, Insert ํƒญ์„ ์„ ํƒํ•˜๊ณ , ์ด์–ด์„œ Noisy laser๋ฅผ ์„ ํƒํ•œ๋‹ค. laser๋ฅผ world ์–ด๋”˜๊ฐ€์— ๋†“๊ณ , ๋ฐ•์Šค๋ฅผ ๊ทธ ์•ž์— ์œ„์น˜์‹œํ‚จ๋‹ค.

  8. noisy laser๋ฅผ Visualize ํ•œ๋‹ค: Topic selector๋ฅผ ๊ฐ€์ ธ์˜ค๊ธฐ ์œ„ํ•ด, Window->Topic Visualization (or press Ctrl-T) ํด๋ฆญํ•œ๋‹ค.

  9. /gazebo/default/hokuyo/link/laser/scan ์ด๋ฆ„์„ ๊ฐ€์ง„ topic์„ ์ฐพ๊ณ  ์ด๋ฅผ ํด๋ฆญํ•˜๊ณ , ์ด์–ด์„œ Okay๋ฅผ ํด๋ฆญํ•œ๋‹ค. ๋‹น์‹ ์€ Laser data๋ฅผ ๋ณด์—ฌ์ฃผ๋Š” Laser View window๋ฅผ ์–ป์„ ์ˆ˜ ์žˆ์„ ๊ฒƒ์ด๋‹ค.

๋‹น์‹ ๋„ ์•Œ๋‹ค์‹œํ”ผ, Scan์€ noisyํ•˜๋‹ค. ๋…ธ์ด์ฆˆ๋ฅผ ์กฐ์ •ํ•˜๊ธฐ ์œ„ํ•ด, model.sdf ์— ์žˆ๋Š” ํ‰๊ท ๊ฐ’๊ณผ ํ‘œ์ค€ํŽธ์ฐจ๊ฐ’์„ ๊ฐ€์ง€๊ณ  ๊ฐ„๋‹จํžˆ ๋†€๋ฉด ๋œ๋‹ค (๋‹จ์œ„๋Š” m):

<noise>
  <type>gaussian</type>
  <mean>0.0</mean>
  <stddev>0.01</stddev>
</noise>

Hokuyo laser์˜ Reasonableํ•œ ๊ฐ’์„ ๋ณผ ์ˆ˜ ์žˆ์„ ๊ฒƒ์ด๋‹ค.

Camera noise

์นด๋ฉ”๋ผ ์„ผ์„œ ๊ฒฝ์šฐ, ์šฐ๋ฆฌ๋Š” ๊ฐ ํ”ฝ์…€์— ๋…๋ฆฝ์ ์œผ๋กœ Gaussian-sampled disturbance๋ฅผ ์ถ”๊ฐ€ํ•œ output amplifier noise๋ฅผ ๋ชจ๋ธ๋งํ•œ๋‹ค. ๋‹น์‹ ์€ ๋…ธ์ด์ฆˆ ๊ฐ’์„ ์ƒ˜ํ”Œ๋งํ•  ๊ฐ€์šฐ์Šค ๋ถ„ํฌ(Gaussian distribution)์˜ ํ‰๊ท ๊ฐ’(the mean), ํ‘œ์ค€ํŽธ์ฐจ(the standard deviation)๋ฅผ ์„ค์ •ํ•  ์ˆ˜ ์žˆ๋‹ค. ๋…ธ์ด์ฆˆ๊ฐ’์€ ๊ฐ pixel ๋งˆ๋‹ค ๋…๋ฆฝ์ ์œผ๋กœ ์ƒ˜ํ”Œ๋ง๋˜๋Š”๋ฐ, ์ฆ‰ ์ด ๋…ธ์ด์ฆˆ ๊ฐ’์€ ์ด ํ”ฝ์…€์˜ ๊ฐ๊ฐ์˜ color channel ๋งˆ๋‹ค ๋…๋ฆฝ์ ์œผ๋กœ ์ถ”๊ฐ€๋œ๋‹ค. ๋…ธ์ด์ฆˆ๋ฅผ ์ถ”๊ฐ€ํ•œ ํ›„์—, color channel์˜ ๊ฒฐ๊ณผ๊ฐ’์€ 0๊ณผ 1์‚ฌ์ด์— ๋†“์ธ๋‹ค; floating point color ๊ฐ’์€ ๊ฒฐ๊ตญ ์ด๋ฏธ์ง€ ์•ˆ์—์„œ ๋งˆ์น˜ unsigned integer๊ฐ€ ๋˜๋Š”๋ฐ, ๋Œ€๊ฒŒ 0๊ณผ 255์‚ฌ์ด๊ฐ€. (8bits per channel).

์ด ๋…ธ์ด์ฆˆ ๋ชจ๋ธ์€ GLSL shader๋กœ ์ˆ˜ํ–‰๋˜๊ณ , ๋™์ž‘ํ•˜๊ธฐ ์œ„ํ•œ GPU๊ฐ€ ํ•„์š”ํ•˜๋‹ค.

Camera ๋…ธ์ด์ฆˆ ๋ชจ๋ธ์„ ํ…Œ์ŠคํŠธ ํ•˜๊ธฐ ์œ„ํ•ด์„œ:

  1. ๋ชจ๋ธ ํด๋”๋ฅผ ๋งŒ๋“ ๋‹ค:

     mkdir -p ~/.gazebo/models/noisy_camera
    
  2. ๋ชจ๋ธ config file์„ ์ƒ์„ฑํ•œ๋‹ค:

    gedit ~/.gazebo/models/noisy_camera/model.config
    
  3. ์•„๋ž˜ ๋‚ด์šฉ์„ ๋ณต์‚ฌ, ๋ถ™์—ฌ๋„ฃ๊ธฐํ•œ๋‹ค:

    <?xml version="1.0"?>
    <model>
      <name>Noisy camera</name>
      <version>1.0</version>
      <sdf version='1.6'>model.sdf</sdf>
    
      <author>
       <name>My Name</name>
       <email>[email protected]</email>
      </author>
    
      <description>
        My noisy camera.
      </description>
    </model>
  4. ~/.gazebo/models/noisy_camera/model.sdf ํŒŒ์ผ์„ ์ƒ์„ฑํ•œ๋‹ค.

    gedit ~/.gazebo/models/noisy_camera/model.sdf
    
  5. ์•„๋ž˜ ๋‚ด์šฉ์„ ๋ณต์‚ฌ, ๋ถ™์—ฌ๋„ฃ๊ธฐํ•œ๋‹ค. ์ด ๋‚ด์šฉ์€ ๋ถ€๊ฐ€์ ์ธ ๋…ธ์ด์ฆˆ๊ฐ€ ํฌํ•จ๋œ ํ‘œ์ค€ camera model์˜ ๋ณต์‚ฌ๋ณธ์ด๋‹ค:

    <?xml version="1.0" ?>
    <sdf version="1.6">
      <model name="camera">
        <link name="link">
          <gravity>false</gravity>
          <pose>0.05 0.05 0.05 0 0 0</pose>
          <inertial>
            <mass>0.1</mass>
          </inertial>
          <visual name="visual">
            <geometry>
              <box>
                <size>0.1 0.1 0.1</size>
              </box>
            </geometry>
          </visual>
          <sensor name="camera" type="camera">
            <camera>
              <horizontal_fov>1.047</horizontal_fov>
              <image>
                <width>1024</width>
                <height>1024</height>
              </image>
              <clip>
                <near>0.1</near>
                <far>100</far>
              </clip>
              <noise>
                <type>gaussian</type>
                <mean>0.0</mean>
                <stddev>0.07</stddev>
              </noise>
            </camera>
            <always_on>1</always_on>
            <update_rate>30</update_rate>
            <visualize>true</visualize>
          </sensor>
        </link>
      </model>
    </sdf>
  6. Gazebo๋ฅผ ์‹คํ–‰ํ•œ๋‹ค:

    gazebo
    
  7. noisy camera ๋ชจ๋ธ์„ ์‚ฝ์ž…ํ•œ๋‹ค: ์™ผ์ชฝ ํŒจ๋„์—์„œ, Insert ํƒญ์„ ์„ ํƒํ•˜๊ณ , ์ด์–ด์„œ Noisy laser๋ฅผ ์„ ํƒํ•œ๋‹ค. laser๋ฅผ world ์–ด๋”˜๊ฐ€์— ๋†“๋Š”๋‹ค.

  8. noisy camera๋ฅผ Visualize ํ•œ๋‹ค: Topic selector๋ฅผ ๊ฐ€์ ธ์˜ค๊ธฐ ์œ„ํ•ด, Window->Topic Visualization (or press Ctrl-T) ํด๋ฆญํ•œ๋‹ค.

  9. /gazebo/default/camera/link/camera/image ์ด๋ฆ„์„ ๊ฐ€์ง„ topic์„ ์ฐพ๊ณ  ์ด๋ฅผ ํด๋ฆญํ•˜๊ณ , ์ด์–ด์„œ Okay๋ฅผ ํด๋ฆญํ•œ๋‹ค. ๋‹น์‹ ์€ Image data๋ฅผ ๋ณด์—ฌ์ฃผ๋Š” Image View window๋ฅผ ์–ป์„ ์ˆ˜ ์žˆ์„ ๊ฒƒ์ด๋‹ค.

๋งŒ์•ฝ ๋‹น์‹ ์ด ๊ฐ€๊นŒ์ด์—์„œ ๋ณธ๋‹ค๋ฉด, ์ด๋ฏธ์ง€๊ฐ€ noistํ•œ๊ฒƒ์„ ํ™•์ธํ•  ์ˆ˜ ์žˆ๋‹ค. ๋…ธ์ด์ฆˆ๋ฅผ ์กฐ์ •ํ•˜๊ธฐ ์œ„ํ•ด, model.sdf ์— ์žˆ๋Š” ํ‰๊ท ๊ฐ’๊ณผ ํ‘œ์ค€ํŽธ์ฐจ๊ฐ’์„ ๊ฐ€์ง€๊ณ  ๊ฐ„๋‹จํžˆ ๋†€๋ฉด ๋œ๋‹ค. ๋‹จ์œ„๋Š” ์—†๋‹ค; ๋…ธ์ด์ฆˆ๋Š” ์•„๋งˆ [0.0,1.0]์˜ ๋ฒ”์œ„๋ฅผ ๊ฐ–๋Š” ๊ฐ ์ปฌ๋Ÿฌ ์ฑ„๋„์— ๋”ํ•ด์งˆ ๊ฒƒ์ด๋‹ค.

์œ„ ์˜ˆ์ œ๋Š” ๋งค์šฐ ๋†’์€ <stddev>(ํ‘œ์ค€ํŽธ์ฐจ)๋ฅผ ๊ฐ–๋Š”๋‹ค. ์ด ๊ฐ’์„ ๋‚ด๋ ค๋ด๋ผ:

<noise>
  <type>gaussian</type>
  <mean>0.0</mean>
  <stddev>0.007</stddev>
</noise>

์ข‹์€ ๋””์ง€ํ„ธ ์นด๋ฉ”๋ผ์˜ Reasonableํ•œ ๊ฐ’์„ ๋ณผ ์ˆ˜ ์žˆ์„ ๊ฒƒ์ด๋‹ค.

IMU noise

IMU์„ผ์„œ์˜ ๊ฒฝ์šฐ, ์šฐ๋ฆฌ๋Š” angular rates, linear accelerations (์„ผ์„œ๊ฐ’)์— ์ž‘์šฉํ•˜๋Š” ๋‘ ์ข…๋ฅ˜์˜ disturbance๋ฅผ ๋ชจ๋ธ๋งํ•œ๋‹ค: noise and bias. Angular rates and linear accelerations๋Š” ๊ฐ๊ฐ ๊ณ ๋ คํ•ด์•ผ ํ•˜๋Š”๋ฐ, ์ด๋Š” 4 set์˜ ํŒŒ๋ผ๋ฏธํ„ฐ๊ฐ€ ํ•„์š”ํ•จ์„ ๋œปํ•œ๋‹ค: rate noise, rate bias, accel noise, and accel bias. IMU's orientation data์— ์ ์šฉ๋˜๋Š” ๋…ธ์ด์ฆˆ๊ฐ€ ์—†์Œ์€ world frame ์•ˆ์—์„œ ์ด์ƒ์ ์ธ ๋ฐ์ดํ„ฐ๋ฅผ ๋ฝ‘์•„๋ƒˆ๋‹ค๋Š” ๊ฒƒ์ด๋‹ค. (this should change in the future??).

Noise๋Š” Gaussian distribution์˜ sample์„ ํ†ตํ•ด ๋”ํ•  ์ˆ˜ ์žˆ๋‹ค. ๋‹น์‹ ์€ ๋…ธ์ด์ฆˆ ๊ฐ’์„ ์ƒ˜ํ”Œ๋งํ•  Gaussian distribution(ํ•˜๋‚˜๋Š” rates, ๋‹ค๋ฅธ ํ•˜๋‚˜๋Š” accels)์˜ ํ‰๊ท ๊ฐ’(the mean), ํ‘œ์ค€ํŽธ์ฐจ(the standard deviation)๋ฅผ ์„ค์ •ํ•  ์ˆ˜ ์žˆ๋‹ค. ๋…ธ์ด์ฆˆ๊ฐ’์€ ๊ฐ component (X,Y,Z) ๋งˆ๋‹ค ๋…๋ฆฝ์ ์œผ๋กœ ์ƒ˜ํ”Œ๋ง๋˜๊ณ , ๊ฐ component์— ๋”ํ•ด์ง„๋‹ค.

Bias๋Š” ๋”ํ•  ์ˆ˜ ์žˆ์ง€๋งŒ, ์‹œ๋ฎฌ๋ ˆ์ด์…˜์ด ์‹œ์ž‘ํ•˜๋Š” ๋•Œ ํ•œ๋ฒˆ๋งŒ sampled ๋œ๋‹ค. ๋‹น์‹ ์€ ๋…ธ์ด์ฆˆ ๊ฐ’์„ ์ƒ˜ํ”Œ๋งํ•  Gaussian distribution(ํ•˜๋‚˜๋Š” rates, ๋‹ค๋ฅธ ํ•˜๋‚˜๋Š” accels)์˜ ํ‰๊ท ๊ฐ’(the mean), ํ‘œ์ค€ํŽธ์ฐจ(the standard deviation)๋ฅผ ์„ค์ •ํ•  ์ˆ˜ ์žˆ๋‹ค.Bias๋Š” ๋™์ผํ•œ ํ™•๋ฅ ์ด ๋ถ€์ •๋œ parameter์— ๋”ฐ๋ผ ํ•จ๊ป˜ ์ƒ˜ํ”Œ๋ง ๋  ๊ฒƒ์ด๋‹ค; ์ด ๊ฐ€์ •์€ ์ œ๊ณต๋œ ํ‰๊ท ๊ฐ’์ด bias์˜ ํฌ๊ธฐ๋ฅผ ์˜๋ฏธํ•˜๊ณ , ์ด๊ฒƒ์€ ์–‘์ชฝ ๋ฐฉํ–ฅ์œผ๋กœ ํŽธํ–ฅ๋œ(biased) ๊ฒƒ๊ณผ ๊ฐ™๋‹ค(?). ๊ทธ๋Ÿฌ๋ฏ€๋กœ, bias๋Š” ๊ณ ์ •๋œ ๊ฐ’์ด๊ณ , ๊ฐ sample๋งˆ๋‹ค ๊ฐ component (X,Y,Z)์— ๋”ํ•ด์ง„๋‹ค.

Note: ์‹œ๋ฎฌ๋ ˆ์ด์…˜ ์‹œ์Šคํ…œ, ๋ฌผ๋ฆฌ์—”์ง„์˜ ๊ตฌ์กฐ์— ๋”ฐ๋ผ, ์‹œ๋ฎฌ๋ ˆ์ด์…˜๋œ IMU ๋ฐ์ดํ„ฐ๊ฐ€ ๊ฝค noisyํ•˜๋Š” ๊ฒฝ์šฐ๊ฐ€ ๋ฐœ์ƒํ•  ์ˆ˜ ์žˆ๋‹ค. ์™œ๋ƒํ•˜๋ฉด, ์‹œ์Šคํ…œ์ด ํ•ญ์ƒ ์ˆ˜๋ ดํ•˜๋Š” ๋ฐฉํ–ฅ์œผ๋กœ ํ’€๋ฆฌ์ง„ ์•Š๊ธฐ ๋•Œ๋ฌธ์ด๋‹ค. ๋”ฐ๋ผ์„œ, ๋‹น์‹ ์ด ์ ์šฉํ•˜๋Š” application์— ๋”ฐ๋ผ์„œ, ์•„๋งˆ ๋…ธ์ด์ฆˆ๋ฅผ ์ถ”๊ฐ€ํ•˜๋Š”๊ฒƒ์ด ํ•„์š”ํ•˜์ง€ ์•Š์„์ˆ˜๋„ ์žˆ๋‹ค.

IMU noise ๋ชจ๋ธ์„ ํ…Œ์ŠคํŠธ ํ•˜๊ธฐ ์œ„ํ•ด:

  1. ๋ชจ๋ธ ํด๋”๋ฅผ ๋งŒ๋“ ๋‹ค:

     mkdir -p ~/.gazebo/models/noisy_imu
    
  2. ๋ชจ๋ธ config file์„ ์ƒ์„ฑํ•œ๋‹ค:

    gedit ~/.gazebo/models/noisy_imu/model.config
    
  3. ์•„๋ž˜ ๋‚ด์šฉ์„ ๋ณต์‚ฌ, ๋ถ™์—ฌ๋„ฃ๊ธฐํ•œ๋‹ค:

    <?xml version="1.0"?>
    <model>
      <name>Noisy IMU</name>
      <version>1.0</version>
      <sdf version='1.6'>model.sdf</sdf>
    
      <author>
       <name>My Name</name>
       <email>[email protected]</email>
      </author>
    
      <description>
        My noisy IMU.
      </description>
    </model>
  4. ~/.gazebo/models/noisy_imu/model.sdf ํŒŒ์ผ์„ ์ƒ์„ฑํ•œ๋‹ค.

    gedit ~/.gazebo/models/noisy_imu/model.sdf
    
  5. ์•„๋ž˜ ๋‚ด์šฉ์„ ๋ณต์‚ฌ, ๋ถ™์—ฌ๋„ฃ๊ธฐํ•œ๋‹ค.

    <?xml version="1.0" ?>
    <sdf version="1.6">
      <model name="imu">
        <link name="link">
          <inertial>
            <mass>0.1</mass>
          </inertial>
          <visual name="visual">
            <geometry>
              <box>
                <size>0.1 0.1 0.1</size>
              </box>
            </geometry>
          </visual>
          <collision name="collision">
            <geometry>
              <box>
                <size>0.1 0.1 0.1</size>
              </box>
            </geometry>
          </collision>
          <sensor name="imu" type="imu">
            <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>
            <always_on>1</always_on>
            <update_rate>1000</update_rate>
          </sensor>
        </link>
      </model>
    </sdf>
  6. Gazebo๋ฅผ ์‹คํ–‰ํ•œ๋‹ค:

     gazebo
    
  7. noisy IMU ๋ชจ๋ธ์„ ์‚ฝ์ž…ํ•œ๋‹ค: ์™ผ์ชฝ ํŒจ๋„์—์„œ, Insert ํƒญ์„ ์„ ํƒํ•˜๊ณ , ์ด์–ด์„œ Noisy IMU๋ฅผ ์„ ํƒํ•œ๋‹ค. IMU๋ฅผ world ์–ด๋”˜๊ฐ€์— ๋†“๋Š”๋‹ค.

  8. noisy IMU๋ฅผ Visualize ํ•œ๋‹ค: Topic selector๋ฅผ ๊ฐ€์ ธ์˜ค๊ธฐ ์œ„ํ•ด, Window->Topic Visualization (or press Ctrl-T) ํด๋ฆญํ•œ๋‹ค.

  9. /gazebo/default/imu/link/imu/imu ์ด๋ฆ„์„ ๊ฐ€์ง„ topic์„ ์ฐพ๊ณ  ์ด๋ฅผ ํด๋ฆญํ•˜๊ณ , ์ด์–ด์„œ Okay๋ฅผ ํด๋ฆญํ•œ๋‹ค. ๋‹น์‹ ์€ IMU data๋ฅผ ๋ณด์—ฌ์ฃผ๋Š” Text View window๋ฅผ ์–ป์„ ์ˆ˜ ์žˆ์„ ๊ฒƒ์ด๋‹ค.

IMU์™€ ๊ฐ™์€ ๋ณต์žกํ•œ ์‹œ์Šคํ…œ์„ ๊ฐ–๋Š” high-rate ์„ผ์„œ์˜ ๋…ธ์ด์ฆˆ๋ฅผ ํ‰๊ฐ€ํ•˜๋Š”๊ฒƒ์€ ๋งค์šฐ ์–ด๋ ต๋‹ค. ๋‹น์‹ ์€ noise and/or bias parameter์— ์˜ํ•ด ํฐ non-zero ํ‰๊ท ๊ฐ’์˜ ์˜ํ–ฅ์„ ๋ณผ ์ˆ˜ ์žˆ์„ ๊ฒƒ์ด๋‹ค.

๋…ธ์ด์ฆˆ๋ฅผ ์กฐ์ •ํ•˜๊ธฐ ์œ„ํ•ด, model.sdf ์— ์žˆ๋Š” ํ‰๊ท ๊ฐ’๊ณผ ํ‘œ์ค€ํŽธ์ฐจ๊ฐ’์„ ๊ฐ€์ง€๊ณ  ๊ฐ„๋‹จํžˆ ๋†€๋ฉด ๋œ๋‹ค. Rate noise, bias์˜ ๋‹จ์œ„๋Š” rad/s, accel noise, bias์˜ ๋‹จ์œ„๋Š” m/s^2.

<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>

high-quality ๋ฅผ ๊ฐ–๋Š” IMU์˜ Reasonableํ•œ ๊ฐ’์„ ๋ณผ ์ˆ˜ ์žˆ์„ ๊ฒƒ์ด๋‹ค.

โš ๏ธ **GitHub.com Fallback** โš ๏ธ