Sensor Noise Model - modulabs/gazebo-tutorial GitHub Wiki
Gazebo๋ ๋ง์ ์ผ์ ๋ชจ๋ธ์ ์ ๊ณตํ๋ค. ํ์ค์์๋ ์ผ์๋ค์ ๋ ธ์ด์ฆ๋ฅผ ๋ณด์ด๋๋ฐ, ์ฆ ์ด์์ ์ธ ํ๊ฒฝ์ ๊ด์ฐฐํ ์ ์๋ค. ๊ธฐ๋ณธ์ ์ผ๋ก, Gazebo์ ์ผ์๋ค์ ์ด์์ ์ธ ํ๊ฒฝ์ ๊ด์ฐฐํ ์ ์๋ค (๊ทธ๋ฌ๋ IMU๋ ์๋๋ค; ์๋๋ฅผ ๋ ์ฝ์ด๋ณด์ธ์). ์ธ์(Perception) ์ฝ๋๋ฅผ ๊ตฌํํ ์ ์๋ ์ข ๋ ํ์ค์ ์ธ ํ๊ฒฝ์ ์ ๊ณตํ๊ธฐ์ํด, ์ฐ๋ฆฌ๋ Gazebo์ ์ผ์์ ์ํด ๋ง๋ค์ด์ง ๋ฐ์ดํฐ์ ๋ ธ์ด์ฆ๋ฅผ ๋ช ๋ฐฑํ๊ฒ ์ถ๊ฐํ ํ์๊ฐ ์๋ค.
Gazebo๋ ์๋์ ๊ฐ์ ์ผ์ ํ์ ์ ๋ ธ์ด์ฆ๋ฅผ ์ถ๊ฐํ ์ ์๋ค:
- Ray (e.g., lasers)
- Camera
- IMU
Ray ์ผ์์ ๊ฒฝ์ฐ, ์ฐ๋ฆฌ๋ ๊ฐ ๋น์ ๋ฒ์์ Gaussian noise๋ฅผ ์ถ๊ฐํ ์ ์๋ค. ๋น์ ์ ๋ ธ์ด์ฆ ๊ฐ์ ์ํ๋งํ ๊ฐ์ฐ์ค ๋ถํฌ(Gaussian distribution)์ ํ๊ท ๊ฐ(the mean), ํ์คํธ์ฐจ(the standard deviation)๋ฅผ ์ค์ ํ ์ ์๋ค. ๋ ธ์ด์ฆ๊ฐ์ ๊ฐ ๋น๋ง๋ค ๋ ๋ฆฝ์ ์ผ๋ก ์ํ๋ง๋๋ค. ๋ ธ์ด์ฆ๋ฅผ ์ถ๊ฐํ ํ์, ๊ฒฐ๊ณผ ๋ฒ์๋ ์ผ์์ ์ต์ ๋ฐ ์ต๋ ๋ฒ์์ ๋์ฌ์ง๋ค? (ํฌํจ?)
Ray ๋ ธ์ด์ฆ ๋ชจ๋ธ์ ํ ์คํธ ํ๊ธฐ ์ํด์:
-
๋ชจ๋ธ ํด๋๋ฅผ ๋ง๋ ๋ค:
mkdir -p ~/.gazebo/models/noisy_laser -
๋ชจ๋ธ config file์ ์์ฑํ๋ค:
gedit ~/.gazebo/models/noisy_laser/model.config -
์๋ ๋ด์ฉ์ ๋ณต์ฌ, ๋ถ์ฌ๋ฃ๊ธฐํ๋ค:
<?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>
-
~/.gazebo/models/noisy_laser/model.sdfํ์ผ์ ์์ฑํ๋ค.gedit ~/.gazebo/models/noisy_laser/model.sdf -
์๋ ๋ด์ฉ์ ๋ณต์ฌ, ๋ถ์ฌ๋ฃ๊ธฐํ๋ค. ์ด ๋ด์ฉ์ ๋ถ๊ฐ์ ์ธ ๋ ธ์ด์ฆ๊ฐ ํฌํจ๋ ํ์ค 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>
-
Gazebo๋ฅผ ์คํํ๋ค:
gazebo -
noisy laser ๋ชจ๋ธ์ ์ฝ์ ํ๋ค: ์ผ์ชฝ ํจ๋์์,
Insertํญ์ ์ ํํ๊ณ , ์ด์ด์Noisy laser๋ฅผ ์ ํํ๋ค. laser๋ฅผ world ์ด๋๊ฐ์ ๋๊ณ , ๋ฐ์ค๋ฅผ ๊ทธ ์์ ์์น์ํจ๋ค. -
noisy laser๋ฅผ Visualize ํ๋ค: Topic selector๋ฅผ ๊ฐ์ ธ์ค๊ธฐ ์ํด, Window->Topic Visualization (or press Ctrl-T) ํด๋ฆญํ๋ค.
-
/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ํ ๊ฐ์ ๋ณผ ์ ์์ ๊ฒ์ด๋ค.
์นด๋ฉ๋ผ ์ผ์ ๊ฒฝ์ฐ, ์ฐ๋ฆฌ๋ ๊ฐ ํฝ์ ์ ๋ ๋ฆฝ์ ์ผ๋ก 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 ๋ ธ์ด์ฆ ๋ชจ๋ธ์ ํ ์คํธ ํ๊ธฐ ์ํด์:
-
๋ชจ๋ธ ํด๋๋ฅผ ๋ง๋ ๋ค:
mkdir -p ~/.gazebo/models/noisy_camera -
๋ชจ๋ธ config file์ ์์ฑํ๋ค:
gedit ~/.gazebo/models/noisy_camera/model.config -
์๋ ๋ด์ฉ์ ๋ณต์ฌ, ๋ถ์ฌ๋ฃ๊ธฐํ๋ค:
<?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>
-
~/.gazebo/models/noisy_camera/model.sdfํ์ผ์ ์์ฑํ๋ค.gedit ~/.gazebo/models/noisy_camera/model.sdf -
์๋ ๋ด์ฉ์ ๋ณต์ฌ, ๋ถ์ฌ๋ฃ๊ธฐํ๋ค. ์ด ๋ด์ฉ์ ๋ถ๊ฐ์ ์ธ ๋ ธ์ด์ฆ๊ฐ ํฌํจ๋ ํ์ค 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>
-
Gazebo๋ฅผ ์คํํ๋ค:
gazebo -
noisy camera ๋ชจ๋ธ์ ์ฝ์ ํ๋ค: ์ผ์ชฝ ํจ๋์์,
Insertํญ์ ์ ํํ๊ณ , ์ด์ด์Noisy laser๋ฅผ ์ ํํ๋ค. laser๋ฅผ world ์ด๋๊ฐ์ ๋๋๋ค. -
noisy camera๋ฅผ Visualize ํ๋ค: Topic selector๋ฅผ ๊ฐ์ ธ์ค๊ธฐ ์ํด, Window->Topic Visualization (or press Ctrl-T) ํด๋ฆญํ๋ค.
-
/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์ผ์์ ๊ฒฝ์ฐ, ์ฐ๋ฆฌ๋ 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 ๋ชจ๋ธ์ ํ ์คํธ ํ๊ธฐ ์ํด:
-
๋ชจ๋ธ ํด๋๋ฅผ ๋ง๋ ๋ค:
mkdir -p ~/.gazebo/models/noisy_imu -
๋ชจ๋ธ config file์ ์์ฑํ๋ค:
gedit ~/.gazebo/models/noisy_imu/model.config -
์๋ ๋ด์ฉ์ ๋ณต์ฌ, ๋ถ์ฌ๋ฃ๊ธฐํ๋ค:
<?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>
-
~/.gazebo/models/noisy_imu/model.sdfํ์ผ์ ์์ฑํ๋ค.gedit ~/.gazebo/models/noisy_imu/model.sdf -
์๋ ๋ด์ฉ์ ๋ณต์ฌ, ๋ถ์ฌ๋ฃ๊ธฐํ๋ค.
<?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>
-
Gazebo๋ฅผ ์คํํ๋ค:
gazebo -
noisy IMU ๋ชจ๋ธ์ ์ฝ์ ํ๋ค: ์ผ์ชฝ ํจ๋์์,
Insertํญ์ ์ ํํ๊ณ , ์ด์ด์Noisy IMU๋ฅผ ์ ํํ๋ค. IMU๋ฅผ world ์ด๋๊ฐ์ ๋๋๋ค. -
noisy IMU๋ฅผ Visualize ํ๋ค: Topic selector๋ฅผ ๊ฐ์ ธ์ค๊ธฐ ์ํด, Window->Topic Visualization (or press Ctrl-T) ํด๋ฆญํ๋ค.
-
/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ํ ๊ฐ์ ๋ณผ ์ ์์ ๊ฒ์ด๋ค.



