Skip to content

Commit

Permalink
Add ros files
Browse files Browse the repository at this point in the history
  • Loading branch information
Iñigo Cirauqui Viloria authored Jul 7, 2017
1 parent a0bf429 commit 4c4dfb7
Show file tree
Hide file tree
Showing 4 changed files with 182 additions and 0 deletions.
6 changes: 6 additions & 0 deletions roslaunch/Hamlyn02.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<launch>

<node pkg="ORB_SLAM2" type="Mono" name="ORB_SLAM2" args="../../../Vocabulary/ORBvoc.txt ../../../rossettings/Settings_Hamlyn02.yaml" cwd="node" output="screen">
</node>

</launch>
16 changes: 16 additions & 0 deletions roslaunch/cam_ORB2.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<launch>

<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/video1" />
<param name="image_width" value="1024" />
<param name="image_height" value="768" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="camera" />
<param name="io_method" value="mmap"/>
<remap from="/usb_cam/image_raw" to="/camera/image_raw" />
</node>

<node pkg="ORB_SLAM2" type="Mono" name="ORB_SLAM2" args="../../../Vocabulary/ORBvoc.txt ../../../rossettings/Settings_Cam.yaml" cwd="node" output="screen">
</node>

</launch>
79 changes: 79 additions & 0 deletions rossettings/Settings_Cam.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
%YAML:1.0

#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 1271.2646
Camera.fy: 1276.0352
Camera.cx: 330.3848
Camera.cy: 245.6502

Camera.k1: -0.50344
Camera.k2: 1.81448
Camera.p1: 0.0
Camera.p2: 0.0
Camera.k3: 0.0

# Camera frames per second
Camera.fps: 30.0

# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1

# Display output in color (1) or grayscale (0)
Camera.colorPub: 1

#--------------------------------------------------------------------------------------------
### Output data to save

# Statistics from the Tracking (Window 1)
Output.StatsW1: 1

# Statistics from the Mapping (Window 2)
Output.StatsW2: 1

# Statistics from the MapPoint creation (Window 3)
Output.StatsW3: 1

# Statistics from the PnP
Output.StatsPnP: 0

# Statistics from the Non-Linear Optimization
Output.StatsNLOpt: 1

#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------

# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1000

# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2

# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8

# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7

#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500

81 changes: 81 additions & 0 deletions rossettings/Settings_Hamlyn02.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
%YAML:1.0

#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

# Camera calibration and distortion parameters (OpenCV)

Camera.fx: 381.914307
Camera.fy: 383.797882
Camera.cx: 168.108963
Camera.cy: 126.979446

Camera.k1: -0.333236
Camera.k2: 0.925076
Camera.p1: 0.003847
Camera.p2: 0.000916
Camera.k3: 0.0

# Camera frames per second
Camera.fps: 30.0

# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1

# Display output in color (1) or grayscale (0)
Camera.colorPub: 1

#--------------------------------------------------------------------------------------------
### Output data to save

# Statistics from the Tracking (Window 1)
Output.StatsW1: 1

# Statistics from the Mapping (Window 2)
Output.StatsW2: 1

# Statistics from the MapPoint creation (Window 3)
Output.StatsW3: 1

# Statistics from the PnP
Output.StatsPnP: 0

# Statistics from the Non-Linear Optimization
Output.StatsNLOpt: 1



#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------

# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1200

# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.1

# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 6

# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 24
ORBextractor.minThFAST: 7

#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500

0 comments on commit 4c4dfb7

Please sign in to comment.