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 #include "jsk_perception/project_image_point.h"
00037
00038 namespace jsk_perception
00039 {
00040 void ProjectImagePoint::onInit()
00041 {
00042 DiagnosticNodelet::onInit();
00043 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00044 dynamic_reconfigure::Server<Config>::CallbackType f =
00045 boost::bind (&ProjectImagePoint::configCallback, this, _1, _2);
00046 srv_->setCallback (f);
00047
00048 pub_ = advertise<geometry_msgs::PointStamped>(*pnh_, "output", 1);
00049 pub_vector_ = advertise<geometry_msgs::Vector3Stamped>(
00050 *pnh_, "output/ray", 1);
00051 }
00052
00053 void ProjectImagePoint::subscribe()
00054 {
00055 sub_ = pnh_->subscribe("input", 1, &ProjectImagePoint::project, this);
00056 sub_camera_info_ = pnh_->subscribe("input/camera_info", 1,
00057 &ProjectImagePoint::cameraInfoCallback,
00058 this);
00059 }
00060
00061 void ProjectImagePoint::unsubscribe()
00062 {
00063 sub_.shutdown();
00064 sub_camera_info_.shutdown();
00065 }
00066
00067 void ProjectImagePoint::configCallback(Config& config, uint32_t level)
00068 {
00069 boost::mutex::scoped_lock lock(mutex_);
00070 z_ = config.z;
00071 }
00072
00073 void ProjectImagePoint::cameraInfoCallback(
00074 const sensor_msgs::CameraInfo::ConstPtr& msg)
00075 {
00076 boost::mutex::scoped_lock lock(mutex_);
00077 camera_info_ = msg;
00078 }
00079
00080 void ProjectImagePoint::project(
00081 const geometry_msgs::PointStamped::ConstPtr& msg)
00082 {
00083 vital_checker_->poke();
00084 boost::mutex::scoped_lock lock(mutex_);
00085 if (!camera_info_) {
00086 JSK_NODELET_WARN(
00087 "[ProjectImagePoint::project] camera info is not yet available");
00088 return;
00089 }
00090 image_geometry::PinholeCameraModel model;
00091 model.fromCameraInfo(camera_info_);
00092 cv::Point3d ray = model.projectPixelTo3dRay(
00093 cv::Point2d(msg->point.x, msg->point.y));
00094 geometry_msgs::Vector3Stamped vector;
00095 vector.header.frame_id = camera_info_->header.frame_id;
00096 vector.header = msg->header;
00097 vector.vector.x = ray.x;
00098 vector.vector.y = ray.y;
00099 vector.vector.z = ray.z;
00100 pub_vector_.publish(vector);
00101 if (ray.z == 0.0) {
00102 JSK_NODELET_ERROR("Z value of projected ray is 0");
00103 return;
00104 }
00105 double alpha = z_ / ray.z;
00106 geometry_msgs::PointStamped point;
00107 point.header = msg->header;
00108 point.header.frame_id = camera_info_->header.frame_id;
00109 point.point.x = ray.x * alpha;
00110 point.point.y = ray.y * alpha;
00111 point.point.z = ray.z * alpha;
00112 pub_.publish(point);
00113
00114 }
00115
00116 }
00117
00118 #include <pluginlib/class_list_macros.h>
00119 PLUGINLIB_EXPORT_CLASS (jsk_perception::ProjectImagePoint, nodelet::Nodelet);