Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef JSK_PERCEPTION_PROJECT_IMAGE_POINT_H_
00038 #define JSK_PERCEPTION_PROJECT_IMAGE_POINT_H_
00039
00040 #include <sensor_msgs/CameraInfo.h>
00041 #include <geometry_msgs/PointStamped.h>
00042 #include <geometry_msgs/Vector3Stamped.h>
00043
00044 #include <image_geometry/pinhole_camera_model.h>
00045
00046 #include <jsk_topic_tools/diagnostic_nodelet.h>
00047 #include <dynamic_reconfigure/server.h>
00048 #include <jsk_perception/ProjectImagePointConfig.h>
00049
00050 namespace jsk_perception
00051 {
00052 class ProjectImagePoint: public jsk_topic_tools::DiagnosticNodelet
00053 {
00054 public:
00055 typedef boost::shared_ptr<ProjectImagePoint> Ptr;
00056 typedef ProjectImagePointConfig Config;
00057 ProjectImagePoint(): DiagnosticNodelet("ProjectImagePoint") {}
00058
00059 protected:
00060 virtual void onInit();
00061 virtual void subscribe();
00062 virtual void unsubscribe();
00063 virtual void project(const geometry_msgs::PointStamped::ConstPtr& msg);
00064 virtual void cameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg);
00065 virtual void configCallback(Config& config, uint32_t level);
00066
00067 boost::mutex mutex_;
00068 ros::Subscriber sub_;
00069 ros::Subscriber sub_camera_info_;
00070 ros::Publisher pub_;
00071 ros::Publisher pub_vector_;
00072 sensor_msgs::CameraInfo::ConstPtr camera_info_;
00073 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00074 double z_;
00075
00076 private:
00077
00078 };
00079 }
00080
00081 #endif