-
Notifications
You must be signed in to change notification settings - Fork 14
Sensor Noise Model
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한 값을 볼 수 있을 것이다.
-
Robot Simulators
-
Build a Robot
- Model structure and requirements
- How to contribute a model
- Make a model
- Make a Mobile Robot
- The relationship among Link, Joint and Axis
- Import Meshes
- Attach Meshes
- Add a Sensor to a Robot
- Make a Simple Gripper
- Attach Gripper to Robot
- Nested model
- Model Editor
- Animated Box
- Make an animated model(actor)
- Inertial parameters of triangle meshes
- Visibility layers
-
Model Editor
-
Build a World
-
Tools and utilities
-
Write a plugin
-
Plugins
-
Sensors
-
User input
-
Transport Library
-
Rendering Library
-
Connect to ROS
-
Ros Control - Advanced
-
DRCSIM for ROS Kinetic (Ubuntu16.04)
-
DRCSIM
- DRC Simulator installation
- Launchfile options
- Spawn Atlas into a custom world
- Animate joints
- Atlas Keyboard Teleoperation over ROS
- Teleoperate atlas with a music mixer
- Visualization and logging
- Atlas MultiSense SL head
- How to use the Atlas Sim Interface
- Atlas fake walking
- Grasp with Sandia hands
- DRC vehicle tele-operation
- DRC vehicle tele operation with Atlas
- Sending joint commands with ROS
- Atlas control over ROS with python
- Modify environment
- Atlas switching control modes
- Atlas Controller Synchronization over ROS Topics
- Changing Viscous Damping Coefficients Over ROS Service
- Running BDI controller demo
- Using the RobotiQ 3 Finger Adaptive Robot Gripper
- BDI Atlas Robot Interface 3.0.0 Stand In Example
-
HAPTIX
- HAPTIX software install and update
- HAPTIX C API
- HAPTIX Matlab and Octave API
- HAPTIX Simulation World API
- HAPTIX Teleoperation
- HAPTIX environment setup
- HAPTIX Optitrack Control
- HAPTIX Tactor Glove
- HAPTIX Simulation World API with Custom World Example
- HAPTIX logging
- HAPTIX DEKA Luke hand installation
- HAPTIX Simulation Scoring Plugin Example
-
MoveIt!
-
Rviz & rqt & ROSBAG
- Control Theory
- TroubleShooting
- Solidworks model to URDF
- ROS-Gazebo with MATLab
- MATLab installation in Linux
- [Gazebo simulation with MATLab]