Skip to content

Commit

Permalink
Merge pull request jsk-ros-pkg#2745 from knorth55/dual-fisheye-image-…
Browse files Browse the repository at this point in the history
…transport

[jsk_perception] support image_transport in DualFisheyeToPanorama
  • Loading branch information
k-okada authored Dec 13, 2022
2 parents e8e5ac3 + 5eafa3f commit 9ac8536
Show file tree
Hide file tree
Showing 6 changed files with 25 additions and 8 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
# FisheyeStitcher
![](images/fisheye_stitcher.jpg)
# DualFisheyeToPanorama

![](images/dual_fisheye_to_panorama.jpg)

Generate panorama image by stitching dual-fisheye camera images.
This is ROS wrapper of [drNoob13/fisheyeStitcher](https://github.com/drNoob13/fisheyeStitcher)
Expand All @@ -14,7 +15,16 @@ This is ROS wrapper of [drNoob13/fisheyeStitcher](https://github.com/drNoob13/fi

Output panorama image.

Output topic is published by `image_transport` plugins, so `~output/compressed` topic is also available.

## Parameters

* `~image_transport` (String, default `raw`)

Image transport type for `~input` topic.

You can choose `compressed` and so on to subscribe `~input/compressed` compressed image.

* `~light_compen` (Bool, default: false)

Light Fall-off Compensation. The outer edge of the fisheye image has low brightness.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@
#include <jsk_perception/DualFisheyeConfig.h>

#include <opencv2/opencv.hpp>
#include <image_transport/image_transport.h>

#include "jsk_perception/fisheye_stitcher.hpp"

Expand All @@ -76,8 +77,8 @@ namespace jsk_perception

bool sticher_initialized_;
boost::shared_ptr<stitcher::FisheyeStitcher> stitcher_;
ros::Subscriber sub_image_;
ros::Publisher pub_panorama_image_;
image_transport::Subscriber sub_image_;
image_transport::Publisher pub_panorama_image_;
ros::Publisher pub_panorama_info_;

jsk_recognition_msgs::PanoramaInfo msg_panorama_info_;
Expand All @@ -96,7 +97,6 @@ namespace jsk_perception
int output_image_height_;
int output_image_width_;
std::string mls_map_path_;

private:
};
}
Expand Down
2 changes: 2 additions & 0 deletions jsk_perception/sample/sample_dual_fisheye_to_panorama.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
<arg name="fovd" default="185.0" doc="Camera's Field of View [degree]" />
<arg name="save_unwarped" default="false" doc="Save unwarped fisheye images. This is useful to create MLS grids." />
<arg name="resolution_mode" default="high" doc="Resolution mode, 'high' or 'low'" />
<arg name="image_transport" default="raw"/>

<node name="dual_fisheye_to_panorama"
pkg="nodelet" type="nodelet"
Expand All @@ -15,6 +16,7 @@
<param name="refine_align" value="$(arg refine_align)" />
<param name="fovd" value="$(arg fovd)" />
<param name="save_unwarped" value="$(arg save_unwarped)" />
<param name="image_transport" value="$(arg image_transport)"/>
<rosparam
command="load"
file="$(find jsk_perception)/config/dual_fisheye_to_panorama/$(arg resolution_mode)_resolution_config.yaml"
Expand Down
3 changes: 3 additions & 0 deletions jsk_perception/sample/sample_insta360_air.launch
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
<arg name="refine_align" default="false" />
<arg name="save_unwarped" default="false" />
<arg name="panorama_resolution_mode" default="high" />
<arg name="panorama_image_transport" default="raw"/>

<arg name="gui" default="true" />

<!-- Publish camera image -->
Expand Down Expand Up @@ -98,6 +100,7 @@
<arg name="refine_align" value="$(arg refine_align)" />
<arg name="save_unwarped" value="$(arg save_unwarped)" />
<arg name="resolution_mode" value="$(arg panorama_resolution_mode)" />
<arg name="image_transport" value="$(arg panorama_image_transport)" />
</include>

<group if="$(arg gui)">
Expand Down
8 changes: 5 additions & 3 deletions jsk_perception/src/dual_fisheye_to_panorama.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
#include "jsk_perception/dual_fisheye_to_panorama.h"
#include <jsk_topic_tools/log_utils.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/Image.h>
#include <image_transport/image_transport.h>
#include <sensor_msgs/image_encodings.h>
#include <jsk_recognition_msgs/PanoramaInfo.h>
#include <algorithm>
Expand Down Expand Up @@ -78,7 +78,7 @@ namespace jsk_perception
ROS_INFO("blend_param_row_end : %d", blend_param_row_end_);
ROS_INFO("output_image_height : %d", output_image_height_);
ROS_INFO("output_image_width : %d", output_image_width_);
pub_panorama_image_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
pub_panorama_image_ = advertiseImage(*pnh_, "output", 1);
pub_panorama_info_ = advertise<jsk_recognition_msgs::PanoramaInfo>(*pnh_, "panorama_info", 1);

sticher_initialized_ = false;
Expand All @@ -103,7 +103,9 @@ namespace jsk_perception

void DualFisheyeToPanorama::subscribe()
{
sub_image_ = pnh_->subscribe("input", 1, &DualFisheyeToPanorama::rectify, this);
image_transport::ImageTransport it(*pnh_);
image_transport::TransportHints hints("raw", ros::TransportHints(), *pnh_, "image_transport");
sub_image_ = it.subscribe(pnh_->resolveName("input"), 1, &DualFisheyeToPanorama::rectify, this, hints);
ros::V_string names = boost::assign::list_of("~input");
jsk_topic_tools::warnNoRemap(names);
}
Expand Down

0 comments on commit 9ac8536

Please sign in to comment.