-
Notifications
You must be signed in to change notification settings - Fork 14
Camera Distortion
카메라 렌즈는 전형적으로 약 몇도 수준의 optical distortion를 보이는데, 이는 이미지에 반영되는 결과를 초래한다. 예를들면, object recognition or navigation task를 수행하기 위한 환경에서, 보다 넓은 각도를 얻기위해 로봇 분야에서 널리 사용되는 fishete camera
Matlab 또는 OpenCV와 같은 카메라 캘리브레이션 툴을 이용하면, 다른 카메라의 intrinsic parameters와 함께 distortion coefficients를 추출할 수 있다. 이제 유저는 Gazebo환경에서 distorted camera sensor의 이미지 데이터를 생성할 것이다.
Gazebo는 Brown's distortion model을 기반으로 한 카메라 시뮬레이션을 제공한다. 이것은 5개의 distortion coefficients k1
, k2
, k3
, p1
, p2
를 나타내는데, 당신은 camera calibration tools로부터 얻을 수 있다. k
coefficients는 radial components of the distortion model이고, p
coefficients는 the tangential components이다.
현재 이를 수행하기 위해, 설명이 필요한 몇가지 한계점들이 있다:
-
Gazebo 5, 6 버전에서는 오직 barrel distortion만 제공됩니다.즉,
k1
는 음의 값을 갖습니다. Pincushion 모델은 Gazebo 7.7 버전에 추가되어 있습니다. -
Distortion은 카메라 image texture(?)에 적용됩니다. 생성된 이미지를 얻고, 여기에 단지 씌우는 것을 의미합니다(?). 이것은 마지막 이미지 (특히, 가장자리 부분)가 barrel distortion을 갖는 실제 카메라 렌즈보다 좁은 field of view 을 가질 수 있음을 경고한다. 이를 보상하는 차선책은 gazebo 안에서 the field of view of camera sensor를 증가하는 것이다.
distortion을 반영한 camera 모델을 추가하기 위해:
-
모델 폴더를 만든다:
mkdir -p ~/.gazebo/models/distorted_camera
-
모델 config file을 생성한다:
gedit ~/.gazebo/models/distorted_camera/model.config
-
아래 내용을 복사, 붙여넣기한다:
<?xml version="1.0"?> <model> <name>Distorted Camera</name> <version>1.0</version> <sdf version='1.5'>model.sdf</sdf> <author> <name>My Name</name> <email>me@my.email</email> </author> <description> My distorted camera. </description> </model>
-
~/.gazebo/models/distorted_camera/model.sdf
파일을 생성한다.gedit ~/.gazebo/models/distorted_camera/model.sdf
-
아래 내용을 복사, 붙여넣기한다. 이 내용은 distortion이 부가된 표준 카메라 모델의 복사본이다:
<?xml version="1.0" ?> <sdf version="1.5"> <model name="distorted_camera"> <link name="link"> <pose>0.05 0.05 0.05 0 0 0</pose> <inertial> <mass>0.1</mass> <inertia> <ixx>0.000166667</ixx> <iyy>0.000166667</iyy> <izz>0.000166667</izz> </inertia> </inertial> <collision name="collision"> <geometry> <box> <size>0.1 0.1 0.1</size> </box> </geometry> </collision> <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>320</width> <height>240</height> </image> <clip> <near>0.1</near> <far>100</far> </clip> <distortion> <k1>-0.25</k1> <k2>0.12</k2> <k3>0.0</k3> <p1>-0.00028</p1> <p2>-0.00005</p2> <center>0.5 0.5</center> </distortion> </camera> <always_on>1</always_on> <update_rate>30</update_rate> <visualize>true</visualize> </sensor> </link> </model> </sdf>
-
Gazebo를 실행한다:
gazebo
-
distorted camera 모델을 삽입한다: 왼쪽 패널에서, Insert 탭을 선택하고, 이어서
Distorted Camera
를 선택한다. camera를 world 어딘가에 놓고, 박스를 그 앞에 위치시킨다. -
distorted camera images를 본다: Topic selector를 가져오기 위해, Window->Topic Visualization (or press Ctrl-T) 클릭한다.
-
/gazebo/default/distorted_camera/link/camera/image
이름을 가진 topic을 찾고 이를 클릭하고, 이어서Okay
를 클릭한다. 당신은 camera image data를 보여주는 Camera View window를 얻을 수 있을 것이다.
당신도 알다시피, box의 가장자리가 curve한 화면을 보이기에, 카메라 이미지는 distorted하다. distortion을 조정하기 위해, model.sdf
에 있는 k1
, k2
, k3
, p1
, p1
distortion coefficients을 가지고 간단히 놀면 된다:
-
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]