|
| 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 () |
| |
Definition at line 68 of file image_rotate_nodelet.cpp.
◆ connectCb()
◆ disconnectCb()
◆ do_work()
| void jsk_pcl_ros::ImageRotateNodelet::do_work |
( |
const sensor_msgs::ImageConstPtr & |
msg, |
|
|
const std::string |
input_frame_from_msg |
|
) |
| |
|
inlineprivate |
◆ frameWithDefault()
◆ imageCallback()
| void jsk_pcl_ros::ImageRotateNodelet::imageCallback |
( |
const sensor_msgs::ImageConstPtr & |
msg | ) |
|
|
inlineprivate |
◆ imageCallbackWithInfo()
| void jsk_pcl_ros::ImageRotateNodelet::imageCallbackWithInfo |
( |
const sensor_msgs::ImageConstPtr & |
msg, |
|
|
const sensor_msgs::CameraInfoConstPtr & |
cam_info |
|
) |
| |
|
inlineprivate |
◆ onInit()
| virtual void jsk_pcl_ros::ImageRotateNodelet::onInit |
( |
| ) |
|
|
inlinevirtual |
◆ reconfigureCallback()
| void jsk_pcl_ros::ImageRotateNodelet::reconfigureCallback |
( |
jsk_pcl_ros::ImageRotateConfig & |
new_config, |
|
|
uint32_t |
level |
|
) |
| |
|
inlineprivate |
◆ setupTFListener()
| void jsk_pcl_ros::ImageRotateNodelet::setupTFListener |
( |
| ) |
|
|
inlineprivate |
◆ subscribe()
| void jsk_pcl_ros::ImageRotateNodelet::subscribe |
( |
| ) |
|
|
inlineprivate |
◆ transformVector()
◆ unsubscribe()
| void jsk_pcl_ros::ImageRotateNodelet::unsubscribe |
( |
| ) |
|
|
inlineprivate |
◆ angle_
| double jsk_pcl_ros::ImageRotateNodelet::angle_ |
|
private |
◆ cam_sub_
◆ config_
| jsk_pcl_ros::ImageRotateConfig jsk_pcl_ros::ImageRotateNodelet::config_ |
|
private |
◆ img_pub_
◆ img_sub_
◆ it_
◆ nh_
◆ prev_stamp_
| ros::Time jsk_pcl_ros::ImageRotateNodelet::prev_stamp_ |
|
private |
◆ source_vector_
◆ srv
| dynamic_reconfigure::Server<jsk_pcl_ros::ImageRotateConfig> jsk_pcl_ros::ImageRotateNodelet::srv |
|
private |
◆ subscriber_count_
| int jsk_pcl_ros::ImageRotateNodelet::subscriber_count_ |
|
private |
◆ target_vector_
◆ tf2_client_
◆ tf_pub_
◆ tf_sub_
◆ use_tf2_
| bool jsk_pcl_ros::ImageRotateNodelet::use_tf2_ |
|
private |
The documentation for this class was generated from the following file: