37 #include <boost/assign.hpp> 
   38 #include <jsk_topic_tools/log_utils.h> 
   44     DiagnosticNodelet::onInit();
 
   45     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
   46     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   48     srv_->setCallback (f);
 
   50     pub_ = advertise<geometry_msgs::PointStamped>(*pnh_, 
"output", 1);
 
   51     pub_vector_ = advertise<geometry_msgs::Vector3Stamped>(
 
   52       *pnh_, 
"output/ray", 1);
 
   62     ros::V_string names = boost::assign::list_of(
"~input")(
"~input/camera_info");
 
   63     jsk_topic_tools::warnNoRemap(names);
 
   79     const sensor_msgs::CameraInfo::ConstPtr& msg)
 
   86     const geometry_msgs::PointStamped::ConstPtr& msg)
 
   88     vital_checker_->poke();
 
   92         "[ProjectImagePoint::project] camera info is not yet available");
 
   97     cv::Point3d ray = 
model.projectPixelTo3dRay(
 
   98       cv::Point2d(
msg->point.x, 
msg->point.y));
 
   99     geometry_msgs::Vector3Stamped 
vector;
 
  110     double alpha = 
z_ / ray.z;
 
  111     geometry_msgs::PointStamped 
point;
 
  114     point.point.x = ray.x * alpha;
 
  115     point.point.y = ray.y * alpha;
 
  116     point.point.z = ray.z * alpha;