## repository: https://github.com/danielsnider/hugin_panorama <> <> == Overview == Create panoramas using image snapshots or multiple video streams. {{attachment:pano_by_senza_senso.JPG|Hugin Panorama|width="750"}} Panorama by [[https://www.flickr.com/photos/mesec/25814467750/|Senza Senso]] (cc). [[http://hugin.sourceforge.net/|Hugin photo stitching tool]] is used to automatically stitch panoramas. Specifically, the [[http://wiki.panotools.org/Panorama_scripting_in_a_nutshell|Hugin command line tools]]. == Quick Start == 1. Install: {{{ $ sudo apt-get install ros-kinetic-hugin-panorama hugin-tools enblend }}} 2. Launch node: {{{ $ roslaunch hugin_panorama hugin_panorama.launch image:=/image_topic }}} 3. Save individual images for input to the panorama: (order doesn't matter) {{{ $ rosservice call /hugin_panorama/image_saver/save # change angle of camera $ rosservice call /hugin_panorama/image_saver/save # repeat as many times as you like... }}} 4. Stitch the panorama: {{{ $ rosservice call /hugin_panorama/stitch }}} 5. View resulting panorama: {{{ $ rqt_image_view /hugin_panorama/panorama/compressed # or open the panorama file $ roscd hugin_panorama; eog ./images/output.png }}} 6. Start again: {{{ $ rosservice call /hugin_panorama/reset }}} This command will clear the images waiting to be stitched so you can start collecting images for an entirely new panorama. == Live Panorama Mode == If you have more than one camera on your robot and you want to stitch them together repetitively in a loop, then use `stitch_loop.launch`. However, expect a slow frame rate of less than 1 Hz because this package is not optimized for speed (pull requests welcome). 1. Launch the `stitch_loop` node: {{{ $ roslaunch hugin_panorama stitch_loop.launch image1:=/image_topic2 image2:=/image_topic2 }}} 2. View resulting live panorama: {{{ $ rqt_image_view /hugin_panorama/panorama/compressed }}} If you have more than two cameras then you'll have to edit the simple python script (`rosed hugin_panorama stitch_loop.py`) and the launch file (`rosed hugin_panorama stitch_loop.launch`). == Nodes == {{{ #!clearsilver CS/NodeAPI name = hugin_panorama pub { 0.name = panorama/compressed 0.type = sensor_msgs/CompressedImage 0.desc = The resulting panorama. } srv { 0.name = stitch 0.type = std_srvs/Empty 0.desc = Create the panorama. 1.name = reset 1.type = std_srvs/Empty 1.desc = Clear images waiting to be stitched. } param { 0.name = ~images_path 0.type = string 0.desc = This is the working directory where input and output images for the panorama are stored. 0.default = "`$(find hugin_panorama)/images`" } }}} {{{ #!clearsilver CS/NodeAPI name = image_saver }}} This node provided by the [[image_view]] package allows you to save images as jpg/png file from a <> topic. The saved images are used when stitching the panoramas. The `image_saver` node should save images to the same location that the `hugin_panorama` node will look in when stitching. See [[https://github.com/danielsnider/hugin_panorama/blob/master/launch/hugin_panorama.launch|hugin_panorama.launch]] for a proper usage example. See the [[http://wiki.ros.org/image_view#image_view.2BAC8-diamondback.image_saver|image_saver]] wiki for full node documentation.