virtual_camera_mono.h
Go to the documentation of this file.
1 #ifndef JSK_PERCEPTION_VIRTUAL_CAMERA_MONO_H_
2 #define JSK_PERCEPTION_VIRTUAL_CAMERA_MONO_H_
3 
4 #include <jsk_topic_tools/diagnostic_nodelet.h>
5 #include <jsk_perception/VirtualCameraMonoConfig.h>
6 
7 #include <dynamic_reconfigure/server.h>
10 #include <tf/transform_listener.h>
12 #include <boost/assign.hpp>
13 #include <boost/thread.hpp>
14 #include <geometry_msgs/PolygonStamped.h>
15 #if ( CV_MAJOR_VERSION >= 4)
16 #else
17 #include <opencv/cv.hpp>
18 #include <opencv/highgui.h>
19 #endif
20 
21 namespace jsk_perception
22 {
23  class VirtualCameraMono: public jsk_topic_tools::DiagnosticNodelet
24  {
25  public:
26  typedef VirtualCameraMonoConfig Config;
27  VirtualCameraMono() : DiagnosticNodelet("VirtualCameraMono") {}
28 
29  protected:
30 
31  virtual void onInit();
32  virtual void configCb (Config &config, uint32_t level);
33  virtual void subscribe();
34  virtual void unsubscribe();
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);
39  virtual bool TransformImage(cv::Mat src, cv::Mat dest,
40  tf::StampedTransform& trans, geometry_msgs::PolygonStamped& poly,
42 
46 
52 
53  tf::StampedTransform trans_; // transform to virtual camera
54  geometry_msgs::PolygonStamped poly_; // target polygon to transform image
57 
58  private:
59 
60  };
61 }
62 
63 #endif
jsk_perception::VirtualCameraMono::tf_broadcaster_
tf::TransformBroadcaster tf_broadcaster_
Definition: virtual_camera_mono.h:51
jsk_perception::VirtualCameraMono
Definition: virtual_camera_mono.h:23
jsk_perception::VirtualCameraMono::sub_poly_
ros::Subscriber sub_poly_
Definition: virtual_camera_mono.h:45
jsk_perception::VirtualCameraMono::sub_trans_
ros::Subscriber sub_trans_
Definition: virtual_camera_mono.h:45
jsk_perception::VirtualCameraMono::unsubscribe
virtual void unsubscribe()
Definition: virtual_camera_mono.cpp:88
boost::shared_ptr
pinhole_camera_model.h
jsk_perception::VirtualCameraMono::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: virtual_camera_mono.h:47
jsk_perception::VirtualCameraMono::interpolation_method_
int interpolation_method_
Definition: virtual_camera_mono.h:55
jsk_perception::VirtualCameraMono::it_
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: virtual_camera_mono.h:48
jsk_perception::VirtualCameraMono::tf_listener_
tf::TransformListener tf_listener_
Definition: virtual_camera_mono.h:49
tf::StampedTransform
transform_broadcaster.h
jsk_perception::VirtualCameraMono::poly_
geometry_msgs::PolygonStamped poly_
Definition: virtual_camera_mono.h:54
jsk_perception
Definition: add_mask_image.h:48
jsk_perception::VirtualCameraMono::sub_
image_transport::CameraSubscriber sub_
Definition: virtual_camera_mono.h:43
jsk_perception::VirtualCameraMono::TransformImage
virtual bool TransformImage(cv::Mat src, cv::Mat dest, tf::StampedTransform &trans, geometry_msgs::PolygonStamped &poly, image_geometry::PinholeCameraModel &cam_model_)
Definition: virtual_camera_mono.cpp:146
jsk_perception::VirtualCameraMono::queue_size_
int queue_size_
Definition: virtual_camera_mono.h:56
jsk_perception::VirtualCameraMono::pub_
image_transport::CameraPublisher pub_
Definition: virtual_camera_mono.h:44
image_transport::CameraSubscriber
tf::TransformBroadcaster
jsk_perception::VirtualCameraMono::transCb
virtual void transCb(const geometry_msgs::TransformStampedConstPtr &tf)
Definition: virtual_camera_mono.cpp:134
jsk_perception::VirtualCameraMono::cam_model_
image_geometry::PinholeCameraModel cam_model_
Definition: virtual_camera_mono.h:50
image_transport::CameraPublisher
jsk_perception::VirtualCameraMono::imageCb
virtual void imageCb(const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
Definition: virtual_camera_mono.cpp:94
jsk_perception::VirtualCameraMono::onInit
virtual void onInit()
Definition: virtual_camera_mono.cpp:10
image_transport.h
transform_listener.h
jsk_perception::VirtualCameraMono::configCb
virtual void configCb(Config &config, uint32_t level)
Definition: virtual_camera_mono.cpp:54
image_geometry::PinholeCameraModel
jsk_perception::VirtualCameraMono::Config
VirtualCameraMonoConfig Config
Definition: virtual_camera_mono.h:26
tf::TransformListener
jsk_perception::VirtualCameraMono::subscribe
virtual void subscribe()
Definition: virtual_camera_mono.cpp:79
jsk_perception::VirtualCameraMono::trans_
tf::StampedTransform trans_
Definition: virtual_camera_mono.h:53
tf
jsk_perception::VirtualCameraMono::polyCb
virtual void polyCb(const geometry_msgs::PolygonStampedConstPtr &poly)
Definition: virtual_camera_mono.cpp:131
jsk_perception::VirtualCameraMono::VirtualCameraMono
VirtualCameraMono()
Definition: virtual_camera_mono.h:27
ros::Subscriber


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