Skip to content

Instantly share code, notes, and snippets.

@ruffsl
Created August 16, 2019 01:52
Show Gist options
  • Save ruffsl/6925e4a15f978238414bbb910043e657 to your computer and use it in GitHub Desktop.
Save ruffsl/6925e4a15f978238414bbb910043e657 to your computer and use it in GitHub Desktop.
Small fiducial slam demo

Install

Install the fiducials package and perception packages

http://wiki.ros.org/fiducials https://github.com/UbiquityRobotics/fiducials

sudo apt install \
  ros-melodic-fiducials \
  ros-melodic-perception \
  ros-melodic-usb_cam

Setup

Calibrate camera by launching usb_cam with demo launch

roslaunch demo.launch

# and

rosrun camera_calibration cameracalibrator.py \
  --size 8x6 \
  --square 0.108 \
  image:=/camera/image_raw \
  camera:=/camera

Or just copy this calibration to your local folder, if using the little red web cam:

mkdir ~/.ros/camera_info/
cp head_camera.yaml ~/.ros/camera_info/

Use the demo.launch to start the demo. To clean/reset the map:

rosservice call /fiducial_slam/clear_map

# or

rm -rf ~/.ros/slam
<launch>
<node name="camera" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/video0" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="base_link" />
<param name="io_method" value="mmap"/>
</node>
<group ns="camera">
<node name="image_proc" pkg="image_proc" type="image_proc"
respawn="true" output="screen"/>
</group>
<include file="$(find aruco_detect)/launch/aruco_detect.launch">
<arg name="image" value="image_rect"/>
</include>
<include file="$(find fiducial_slam)/launch/fiducial_slam.launch"/>
<node pkg="rviz" type="rviz" name="$(anon rviz)"
args="-d $(find fiducial_slam)/fiducials.rviz"/>
</launch>
image_width: 640
image_height: 480
camera_name: head_camera
camera_matrix:
rows: 3
cols: 3
data: [1102.03443411021, 0, 294.9838235592765, 0, 1097.815474843589, 206.3316681283001, 0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [0.09248821808877597, -0.50850871469002, -0.0020237558553935, 0.01001186475337764, 0]
rectification_matrix:
rows: 3
cols: 3
data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
projection_matrix:
rows: 3
cols: 4
data: [1108.644409179688, 0, 297.9023053757373, 0, 0, 1107.520385742188, 205.7312279849648, 0, 0, 0, 1, 0]
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment