Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_perception::DualFisheyeToPanorama Class Reference

#include <dual_fisheye_to_panorama.h>

Inheritance diagram for jsk_perception::DualFisheyeToPanorama:
Inheritance graph
[legend]

Public Types

typedef jsk_perception::DualFisheyeConfig Config
 
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
 

Public Member Functions

 DualFisheyeToPanorama ()
 

Protected Member Functions

void configCallback (Config &new_config, uint32_t level)
 
virtual void onInit ()
 
virtual void rectify (const sensor_msgs::Image::ConstPtr &image_msg)
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 

Protected Attributes

int blend_image_height_
 
int blend_image_width_
 
int blend_param_p_wid_
 
int blend_param_p_x1_
 
int blend_param_p_x2_
 
int blend_param_row_end_
 
int blend_param_row_start_
 
bool enb_lc_
 
bool enb_ra_
 
float fovd_
 
std::string mls_map_path_
 
jsk_recognition_msgs::PanoramaInfo msg_panorama_info_
 
int output_image_height_
 
int output_image_width_
 
image_transport::Publisher pub_panorama_image_
 
ros::Publisher pub_panorama_info_
 
bool save_unwarped_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
bool sticher_initialized_
 
boost::shared_ptr< stitcher::FisheyeStitcherstitcher_
 
image_transport::Subscriber sub_image_
 

Detailed Description

Definition at line 92 of file dual_fisheye_to_panorama.h.

Member Typedef Documentation

◆ Config

typedef jsk_perception::DualFisheyeConfig jsk_perception::DualFisheyeToPanorama::Config

Definition at line 131 of file dual_fisheye_to_panorama.h.

◆ SyncPolicy

Definition at line 130 of file dual_fisheye_to_panorama.h.

Constructor & Destructor Documentation

◆ DualFisheyeToPanorama()

jsk_perception::DualFisheyeToPanorama::DualFisheyeToPanorama ( )
inline

Definition at line 133 of file dual_fisheye_to_panorama.h.

Member Function Documentation

◆ configCallback()

void jsk_perception::DualFisheyeToPanorama::configCallback ( Config new_config,
uint32_t  level 
)
protected

Definition at line 133 of file dual_fisheye_to_panorama.cpp.

◆ onInit()

void jsk_perception::DualFisheyeToPanorama::onInit ( )
protectedvirtual

Definition at line 82 of file dual_fisheye_to_panorama.cpp.

◆ rectify()

void jsk_perception::DualFisheyeToPanorama::rectify ( const sensor_msgs::Image::ConstPtr &  image_msg)
protectedvirtual

Definition at line 153 of file dual_fisheye_to_panorama.cpp.

◆ subscribe()

void jsk_perception::DualFisheyeToPanorama::subscribe ( )
protectedvirtual

Definition at line 138 of file dual_fisheye_to_panorama.cpp.

◆ unsubscribe()

void jsk_perception::DualFisheyeToPanorama::unsubscribe ( )
protectedvirtual

Definition at line 147 of file dual_fisheye_to_panorama.cpp.

Member Data Documentation

◆ blend_image_height_

int jsk_perception::DualFisheyeToPanorama::blend_image_height_
protected

Definition at line 154 of file dual_fisheye_to_panorama.h.

◆ blend_image_width_

int jsk_perception::DualFisheyeToPanorama::blend_image_width_
protected

Definition at line 155 of file dual_fisheye_to_panorama.h.

◆ blend_param_p_wid_

int jsk_perception::DualFisheyeToPanorama::blend_param_p_wid_
protected

Definition at line 156 of file dual_fisheye_to_panorama.h.

◆ blend_param_p_x1_

int jsk_perception::DualFisheyeToPanorama::blend_param_p_x1_
protected

Definition at line 157 of file dual_fisheye_to_panorama.h.

◆ blend_param_p_x2_

int jsk_perception::DualFisheyeToPanorama::blend_param_p_x2_
protected

Definition at line 158 of file dual_fisheye_to_panorama.h.

◆ blend_param_row_end_

int jsk_perception::DualFisheyeToPanorama::blend_param_row_end_
protected

Definition at line 160 of file dual_fisheye_to_panorama.h.

◆ blend_param_row_start_

int jsk_perception::DualFisheyeToPanorama::blend_param_row_start_
protected

Definition at line 159 of file dual_fisheye_to_panorama.h.

◆ enb_lc_

bool jsk_perception::DualFisheyeToPanorama::enb_lc_
protected

Definition at line 150 of file dual_fisheye_to_panorama.h.

◆ enb_ra_

bool jsk_perception::DualFisheyeToPanorama::enb_ra_
protected

Definition at line 151 of file dual_fisheye_to_panorama.h.

◆ fovd_

float jsk_perception::DualFisheyeToPanorama::fovd_
protected

Definition at line 153 of file dual_fisheye_to_panorama.h.

◆ mls_map_path_

std::string jsk_perception::DualFisheyeToPanorama::mls_map_path_
protected

Definition at line 163 of file dual_fisheye_to_panorama.h.

◆ msg_panorama_info_

jsk_recognition_msgs::PanoramaInfo jsk_perception::DualFisheyeToPanorama::msg_panorama_info_
protected

Definition at line 148 of file dual_fisheye_to_panorama.h.

◆ output_image_height_

int jsk_perception::DualFisheyeToPanorama::output_image_height_
protected

Definition at line 161 of file dual_fisheye_to_panorama.h.

◆ output_image_width_

int jsk_perception::DualFisheyeToPanorama::output_image_width_
protected

Definition at line 162 of file dual_fisheye_to_panorama.h.

◆ pub_panorama_image_

image_transport::Publisher jsk_perception::DualFisheyeToPanorama::pub_panorama_image_
protected

Definition at line 145 of file dual_fisheye_to_panorama.h.

◆ pub_panorama_info_

ros::Publisher jsk_perception::DualFisheyeToPanorama::pub_panorama_info_
protected

Definition at line 146 of file dual_fisheye_to_panorama.h.

◆ save_unwarped_

bool jsk_perception::DualFisheyeToPanorama::save_unwarped_
protected

Definition at line 152 of file dual_fisheye_to_panorama.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_perception::DualFisheyeToPanorama::srv_
protected

Definition at line 135 of file dual_fisheye_to_panorama.h.

◆ sticher_initialized_

bool jsk_perception::DualFisheyeToPanorama::sticher_initialized_
protected

Definition at line 142 of file dual_fisheye_to_panorama.h.

◆ stitcher_

boost::shared_ptr<stitcher::FisheyeStitcher> jsk_perception::DualFisheyeToPanorama::stitcher_
protected

Definition at line 143 of file dual_fisheye_to_panorama.h.

◆ sub_image_

image_transport::Subscriber jsk_perception::DualFisheyeToPanorama::sub_image_
protected

Definition at line 144 of file dual_fisheye_to_panorama.h.


The documentation for this class was generated from the following files:


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17