Go to the documentation of this file. 1 #ifndef JSK_PERCEPTION_VIRTUAL_CAMERA_MONO_H_
2 #define JSK_PERCEPTION_VIRTUAL_CAMERA_MONO_H_
4 #include <jsk_topic_tools/diagnostic_nodelet.h>
5 #include <jsk_perception/VirtualCameraMonoConfig.h>
7 #include <dynamic_reconfigure/server.h>
12 #include <boost/assign.hpp>
13 #include <boost/thread.hpp>
14 #include <geometry_msgs/PolygonStamped.h>
15 #if ( CV_MAJOR_VERSION >= 4)
17 #include <opencv/cv.hpp>
18 #include <opencv/highgui.h>
26 typedef VirtualCameraMonoConfig
Config;
35 virtual void imageCb (
const sensor_msgs::ImageConstPtr& image_msg,
36 const sensor_msgs::CameraInfoConstPtr& info_msg);
37 virtual void polyCb (
const geometry_msgs::PolygonStampedConstPtr& poly);
38 virtual void transCb (
const geometry_msgs::TransformStampedConstPtr&
tf);
54 geometry_msgs::PolygonStamped
poly_;
tf::TransformBroadcaster tf_broadcaster_
ros::Subscriber sub_poly_
ros::Subscriber sub_trans_
virtual void unsubscribe()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
int interpolation_method_
boost::shared_ptr< image_transport::ImageTransport > it_
tf::TransformListener tf_listener_
geometry_msgs::PolygonStamped poly_
image_transport::CameraSubscriber sub_
virtual bool TransformImage(cv::Mat src, cv::Mat dest, tf::StampedTransform &trans, geometry_msgs::PolygonStamped &poly, image_geometry::PinholeCameraModel &cam_model_)
image_transport::CameraPublisher pub_
virtual void transCb(const geometry_msgs::TransformStampedConstPtr &tf)
image_geometry::PinholeCameraModel cam_model_
virtual void imageCb(const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
virtual void configCb(Config &config, uint32_t level)
VirtualCameraMonoConfig Config
tf::StampedTransform trans_
virtual void polyCb(const geometry_msgs::PolygonStampedConstPtr &poly)
jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17