project_image_point.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
37 #include <boost/assign.hpp>
39 
40 namespace jsk_perception
41 {
43  {
44  DiagnosticNodelet::onInit();
45  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
46  dynamic_reconfigure::Server<Config>::CallbackType f =
47  boost::bind (&ProjectImagePoint::configCallback, this, _1, _2);
48  srv_->setCallback (f);
49 
50  pub_ = advertise<geometry_msgs::PointStamped>(*pnh_, "output", 1);
51  pub_vector_ = advertise<geometry_msgs::Vector3Stamped>(
52  *pnh_, "output/ray", 1);
54  }
55 
57  {
58  sub_ = pnh_->subscribe("input", 1, &ProjectImagePoint::project, this);
59  sub_camera_info_ = pnh_->subscribe("input/camera_info", 1,
61  this);
62  ros::V_string names = boost::assign::list_of("~input")("~input/camera_info");
64  }
65 
67  {
68  sub_.shutdown();
70  }
71 
72  void ProjectImagePoint::configCallback(Config& config, uint32_t level)
73  {
74  boost::mutex::scoped_lock lock(mutex_);
75  z_ = config.z;
76  }
77 
79  const sensor_msgs::CameraInfo::ConstPtr& msg)
80  {
81  boost::mutex::scoped_lock lock(mutex_);
82  camera_info_ = msg;
83  }
84 
86  const geometry_msgs::PointStamped::ConstPtr& msg)
87  {
88  vital_checker_->poke();
89  boost::mutex::scoped_lock lock(mutex_);
90  if (!camera_info_) {
92  "[ProjectImagePoint::project] camera info is not yet available");
93  return;
94  }
97  cv::Point3d ray = model.projectPixelTo3dRay(
98  cv::Point2d(msg->point.x, msg->point.y));
99  geometry_msgs::Vector3Stamped vector;
100  vector.header.frame_id = camera_info_->header.frame_id;
101  vector.header = msg->header;
102  vector.vector.x = ray.x;
103  vector.vector.y = ray.y;
104  vector.vector.z = ray.z;
105  pub_vector_.publish(vector);
106  if (ray.z == 0.0) {
107  NODELET_ERROR("Z value of projected ray is 0");
108  return;
109  }
110  double alpha = z_ / ray.z;
111  geometry_msgs::PointStamped point;
112  point.header = msg->header;
113  point.header.frame_id = camera_info_->header.frame_id;
114  point.point.x = ray.x * alpha;
115  point.point.y = ray.y * alpha;
116  point.point.z = ray.z * alpha;
117  pub_.publish(point);
118 
119  }
120 
121 }
122 
f
virtual void project(const geometry_msgs::PointStamped::ConstPtr &msg)
sensor_msgs::CameraInfo::ConstPtr camera_info_
virtual void cameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
cv::Point3d projectPixelTo3dRay(const cv::Point2d &uv_rect) const
virtual void configCallback(Config &config, uint32_t level)
PLUGINLIB_EXPORT_CLASS(jsk_perception::ProjectImagePoint, nodelet::Nodelet)
std::vector< std::string > V_string
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
boost::shared_ptr< ros::NodeHandle > pnh_
bool warnNoRemap(const std::vector< std::string > names)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
mutex_t * lock


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27