#include <fisheye_to_panorama.h>
Public Types | |
typedef jsk_perception::FisheyeConfig | Config |
typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::Image, sensor_msgs::CameraInfo > | SyncPolicy |
Public Member Functions | |
FisheyeToPanorama () | |
Protected Member Functions | |
void | configCallback (Config &new_config, uint32_t level) |
double | interpolate (double rate, double first, double second) |
virtual void | onInit () |
virtual void | rectify (const sensor_msgs::Image::ConstPtr &image_msg) |
virtual void | subscribe () |
virtual void | unsubscribe () |
Protected Attributes | |
float | max_degree_ |
double | offset_degree_ |
ros::Publisher | pub_undistorted_bilinear_image_ |
ros::Publisher | pub_undistorted_image_ |
float | scale_ |
bool | simple_panorama_ |
boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ |
ros::Subscriber | sub_image_ |
boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ |
float | upside_down_ |
bool | use_panorama_ |
Definition at line 55 of file fisheye_to_panorama.h.
typedef jsk_perception::FisheyeConfig jsk_perception::FisheyeToPanorama::Config |
Definition at line 62 of file fisheye_to_panorama.h.
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo > jsk_perception::FisheyeToPanorama::SyncPolicy |
Definition at line 61 of file fisheye_to_panorama.h.
jsk_perception::FisheyeToPanorama::FisheyeToPanorama | ( | ) | [inline] |
Definition at line 64 of file fisheye_to_panorama.h.
void jsk_perception::FisheyeToPanorama::configCallback | ( | Config & | new_config, |
uint32_t | level | ||
) | [protected] |
Definition at line 67 of file fisheye_to_panorama.cpp.
double jsk_perception::FisheyeToPanorama::interpolate | ( | double | rate, |
double | first, | ||
double | second | ||
) | [inline, protected] |
Definition at line 71 of file fisheye_to_panorama.h.
void jsk_perception::FisheyeToPanorama::onInit | ( | ) | [protected, virtual] |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 47 of file fisheye_to_panorama.cpp.
void jsk_perception::FisheyeToPanorama::rectify | ( | const sensor_msgs::Image::ConstPtr & | image_msg | ) | [protected, virtual] |
Definition at line 87 of file fisheye_to_panorama.cpp.
void jsk_perception::FisheyeToPanorama::subscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 76 of file fisheye_to_panorama.cpp.
void jsk_perception::FisheyeToPanorama::unsubscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 81 of file fisheye_to_panorama.cpp.
float jsk_perception::FisheyeToPanorama::max_degree_ [protected] |
Definition at line 80 of file fisheye_to_panorama.h.
double jsk_perception::FisheyeToPanorama::offset_degree_ [protected] |
Definition at line 83 of file fisheye_to_panorama.h.
Definition at line 77 of file fisheye_to_panorama.h.
Definition at line 76 of file fisheye_to_panorama.h.
float jsk_perception::FisheyeToPanorama::scale_ [protected] |
Definition at line 81 of file fisheye_to_panorama.h.
bool jsk_perception::FisheyeToPanorama::simple_panorama_ [protected] |
Definition at line 79 of file fisheye_to_panorama.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_perception::FisheyeToPanorama::srv_ [protected] |
Definition at line 66 of file fisheye_to_panorama.h.
Definition at line 75 of file fisheye_to_panorama.h.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_perception::FisheyeToPanorama::sync_ [protected] |
Definition at line 74 of file fisheye_to_panorama.h.
float jsk_perception::FisheyeToPanorama::upside_down_ [protected] |
Definition at line 82 of file fisheye_to_panorama.h.
bool jsk_perception::FisheyeToPanorama::use_panorama_ [protected] |
Definition at line 78 of file fisheye_to_panorama.h.