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