
| Public Member Functions | |
| virtual void | onInit () | 
| Private Member Functions | |
| void | connectCb (const image_transport::SingleSubscriberPublisher &ssp) | 
| void | disconnectCb (const image_transport::SingleSubscriberPublisher &) | 
| void | do_work (const sensor_msgs::ImageConstPtr &msg, const std::string input_frame_from_msg) | 
| const std::string & | frameWithDefault (const std::string &frame, const std::string &image_frame) | 
| void | imageCallback (const sensor_msgs::ImageConstPtr &msg) | 
| void | imageCallbackWithInfo (const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info) | 
| void | reconfigureCallback (jsk_pcl_ros::ImageRotateConfig &new_config, uint32_t level) | 
| void | setupTFListener () | 
| void | subscribe () | 
| void | transformVector (const std::string &input_frame_id, const ros::Time &target_time, const std::string &source_frame_id, const ros::Time &time, const std::string &fixed_frame_id, const tf::Stamped< tf::Vector3 > &input_vector, tf::Stamped< tf::Vector3 > &target_vector, const ros::Duration &duration) | 
| void | unsubscribe () | 
| Private Attributes | |
| double | angle_ | 
| image_transport::CameraSubscriber | cam_sub_ | 
| jsk_pcl_ros::ImageRotateConfig | config_ | 
| image_transport::Publisher | img_pub_ | 
| image_transport::Subscriber | img_sub_ | 
| boost::shared_ptr < image_transport::ImageTransport > | it_ | 
| ros::NodeHandle | nh_ | 
| ros::Time | prev_stamp_ | 
| tf::Stamped< tf::Vector3 > | source_vector_ | 
| dynamic_reconfigure::Server < jsk_pcl_ros::ImageRotateConfig > | srv | 
| int | subscriber_count_ | 
| tf::Stamped< tf::Vector3 > | target_vector_ | 
| boost::shared_ptr < tf2_ros::BufferClient > | tf2_client_ | 
| tf::TransformBroadcaster | tf_pub_ | 
| boost::shared_ptr < tf::TransformListener > | tf_sub_ | 
| bool | use_tf2_ | 
Definition at line 68 of file image_rotate_nodelet.cpp.
| void jsk_pcl_ros::ImageRotateNodelet::connectCb | ( | const image_transport::SingleSubscriberPublisher & | ssp | ) |  [inline, private] | 
Definition at line 310 of file image_rotate_nodelet.cpp.
| void jsk_pcl_ros::ImageRotateNodelet::disconnectCb | ( | const image_transport::SingleSubscriberPublisher & | ) |  [inline, private] | 
Definition at line 317 of file image_rotate_nodelet.cpp.
| void jsk_pcl_ros::ImageRotateNodelet::do_work | ( | const sensor_msgs::ImageConstPtr & | msg, | 
| const std::string | input_frame_from_msg | ||
| ) |  [inline, private] | 
Definition at line 173 of file image_rotate_nodelet.cpp.
| const std::string& jsk_pcl_ros::ImageRotateNodelet::frameWithDefault | ( | const std::string & | frame, | 
| const std::string & | image_frame | ||
| ) |  [inline, private] | 
Definition at line 122 of file image_rotate_nodelet.cpp.
| void jsk_pcl_ros::ImageRotateNodelet::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg | ) |  [inline, private] | 
Definition at line 134 of file image_rotate_nodelet.cpp.
| void jsk_pcl_ros::ImageRotateNodelet::imageCallbackWithInfo | ( | const sensor_msgs::ImageConstPtr & | msg, | 
| const sensor_msgs::CameraInfoConstPtr & | cam_info | ||
| ) |  [inline, private] | 
Definition at line 129 of file image_rotate_nodelet.cpp.
| virtual void jsk_pcl_ros::ImageRotateNodelet::onInit | ( | void | ) |  [inline, virtual] | 
Implements nodelet::Nodelet.
Definition at line 326 of file image_rotate_nodelet.cpp.
| void jsk_pcl_ros::ImageRotateNodelet::reconfigureCallback | ( | jsk_pcl_ros::ImageRotateConfig & | new_config, | 
| uint32_t | level | ||
| ) |  [inline, private] | 
Definition at line 106 of file image_rotate_nodelet.cpp.
| void jsk_pcl_ros::ImageRotateNodelet::setupTFListener | ( | ) |  [inline, private] | 
Definition at line 91 of file image_rotate_nodelet.cpp.
| void jsk_pcl_ros::ImageRotateNodelet::subscribe | ( | ) |  [inline, private] | 
Definition at line 294 of file image_rotate_nodelet.cpp.
| void jsk_pcl_ros::ImageRotateNodelet::transformVector | ( | const std::string & | input_frame_id, | 
| const ros::Time & | target_time, | ||
| const std::string & | source_frame_id, | ||
| const ros::Time & | time, | ||
| const std::string & | fixed_frame_id, | ||
| const tf::Stamped< tf::Vector3 > & | input_vector, | ||
| tf::Stamped< tf::Vector3 > & | target_vector, | ||
| const ros::Duration & | duration | ||
| ) |  [inline, private] | 
Definition at line 139 of file image_rotate_nodelet.cpp.
| void jsk_pcl_ros::ImageRotateNodelet::unsubscribe | ( | ) |  [inline, private] | 
Definition at line 303 of file image_rotate_nodelet.cpp.
| double jsk_pcl_ros::ImageRotateNodelet::angle_  [private] | 
Definition at line 88 of file image_rotate_nodelet.cpp.
Definition at line 79 of file image_rotate_nodelet.cpp.
| jsk_pcl_ros::ImageRotateConfig jsk_pcl_ros::ImageRotateNodelet::config_  [private] | 
Definition at line 74 of file image_rotate_nodelet.cpp.
Definition at line 77 of file image_rotate_nodelet.cpp.
Definition at line 78 of file image_rotate_nodelet.cpp.
| boost::shared_ptr<image_transport::ImageTransport> jsk_pcl_ros::ImageRotateNodelet::it_  [private] | 
Definition at line 84 of file image_rotate_nodelet.cpp.
Reimplemented from nodelet::Nodelet.
Definition at line 85 of file image_rotate_nodelet.cpp.
Definition at line 89 of file image_rotate_nodelet.cpp.
Definition at line 82 of file image_rotate_nodelet.cpp.
| dynamic_reconfigure::Server<jsk_pcl_ros::ImageRotateConfig> jsk_pcl_ros::ImageRotateNodelet::srv  [private] | 
Definition at line 75 of file image_rotate_nodelet.cpp.
| int jsk_pcl_ros::ImageRotateNodelet::subscriber_count_  [private] | 
Definition at line 87 of file image_rotate_nodelet.cpp.
Definition at line 81 of file image_rotate_nodelet.cpp.
| boost::shared_ptr<tf2_ros::BufferClient> jsk_pcl_ros::ImageRotateNodelet::tf2_client_  [private] | 
Definition at line 73 of file image_rotate_nodelet.cpp.
Definition at line 72 of file image_rotate_nodelet.cpp.
| boost::shared_ptr<tf::TransformListener> jsk_pcl_ros::ImageRotateNodelet::tf_sub_  [private] | 
Definition at line 71 of file image_rotate_nodelet.cpp.
| bool jsk_pcl_ros::ImageRotateNodelet::use_tf2_  [private] | 
Definition at line 70 of file image_rotate_nodelet.cpp.