rgbd_cb_detector_action.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
36 
37 #include <boost/thread.hpp>
38 #include <ros/console.h>
39 #include <ros/ros.h>
43 #include <opencv2/core/core.hpp>
44 #include <opencv2/core/core_c.h>
45 
46 #include <sensor_msgs/Image.h>
47 #include <sensor_msgs/CameraInfo.h>
48 #include <image_cb_detector/ConfigAction.h>
49 #include <calibration_msgs/Interval.h>
50 
54 
56 
58 
60 {
61 public:
63  as_("cb_detector_config", false),
64  image_sub_ (nh_, "image", 3),
65  depth_sub_(nh_, "depth", 3),
66  caminfo_sub_(nh_, "camera_info", 3),
68  {
71 
72  pub_ = nh_.advertise<calibration_msgs::CalibrationPattern>("features",1);
73  sync_.registerCallback(boost::bind(&RgbdCbDetectorAction::cameraCallback, this, _1, _2, _3));
74 
75  as_.start();
76 
77  last_sample_invalid_ = false;
78  }
79 
80  void goalCallback()
81  {
82  boost::mutex::scoped_lock lock(run_mutex_);
83 
84  // Stop the previously running goal (if it exists)
85  if (as_.isActive())
86  as_.setPreempted();
87 
88  // Get the new goal from the action server
89  image_cb_detector::ConfigGoalConstPtr goal = as_.acceptNewGoal();
90  assert(goal);
91 
92  // Try to reconfigure the settler object
93  bool success = detector_.configure(*goal);
94 
95  // Detect possible failure
96  if (!success)
97  as_.setAborted();
98  }
99 
101  {
102  boost::mutex::scoped_lock lock(run_mutex_);
103 
104  // Don't need to do any cleanup. Immeadiately turn it off
105  as_.setPreempted();
106  }
107 
108  void cameraCallback ( const sensor_msgs::ImageConstPtr& image_msg,
109  const sensor_msgs::ImageConstPtr& depth_msg,
110  const sensor_msgs::CameraInfoConstPtr& caminfo_msg)
111  {
112  boost::mutex::scoped_lock lock(run_mutex_);
113 
114  std::ostringstream s;
115  s << image_sub_.getTopic() << ": ";
116 
117  if (as_.isActive())
118  {
119  // detect checkerboard corners
120  calibration_msgs::CalibrationPattern features;
121  bool success;
122  success = detector_.detect(image_msg, features);
123  if (!success)
124  {
125  ROS_ERROR_STREAM(s.str()<<"Error trying to detect checkerboard, not going to publish CalibrationPattern");
126  last_sample_invalid_ = true;
127  return;
128  }
129  if (depth_msg->encoding != sensor_msgs::image_encodings::TYPE_32FC1) {
130  ROS_ERROR_STREAM("Depth image must be 32-bit floating point (encoding '32FC1'), but has encoding '" << depth_msg->encoding << "'");
131  last_sample_invalid_ = true;
132  return;
133  }
134 
135  // prepare data
136  cloud_converter_.initialize( image_msg, caminfo_msg );
137  const float* depth_ptr = reinterpret_cast<const float*>(&depth_msg->data[0]);
138  std::size_t width = depth_msg->width;
139  std::size_t height = depth_msg->height;
140 
141  // make a pointcloud from the checkerboard corners
142  std::vector<cv::Point3f> corner_cloud;
143  for(size_t i = 0; i< features.image_points.size(); i++){
144  geometry_msgs::Point pixel = features.image_points[i];
145  float depth = *(depth_ptr+width*(unsigned int)pixel.y+(unsigned int)pixel.x);
146  if ( isnan(depth) )
147  {
148  continue;
149  }
150 
151  cv::Point3f point;
152  cloud_converter_.depthTo3DPoint( pixel, depth, point );
153  corner_cloud.push_back( point );
154  }
155 
156  if( corner_cloud.size() < features.image_points.size()/2 ) {
157  ROS_ERROR_STREAM(s.str() << "More than 50% missing 3d points in checkerboard, not going to publish CalibrationPattern");
158  last_sample_invalid_ = true;
159  return;
160  }
161 
162  // estimate plane
163  cv::Vec3f n;
164  float d;
165  float best_ratio = 0;
166  cv::RNG rng;
167  for(size_t i = 0; i < 100; ++i) {
168  // Get 3 random points
169  for(int i=0;i<3;++i) {
170  std::swap(corner_cloud[i], corner_cloud[rng.uniform(i+1, int(corner_cloud.size()))]);
171  }
172  // Compute the plane from those
173  cv::Vec3f nrm = cv::Vec3f(corner_cloud[2]-corner_cloud[0]).cross(cv::Vec3f(corner_cloud[1])-cv::Vec3f(corner_cloud[0]));
174  nrm = nrm / cv::norm(nrm);
175  cv::Vec3f x0(corner_cloud[0]);
176 
177  float p_to_plane_thresh = 0.01;
178  int num_inliers = 0;
179 
180  // Check the number of inliers
181  for (size_t i=0; i<corner_cloud.size(); ++i) {
182  cv::Vec3f w = cv::Vec3f(corner_cloud[i]) - x0;
183  float D = std::fabs(nrm.dot(w));
184  if(D < p_to_plane_thresh)
185  ++num_inliers;
186  }
187  float ratio = float(num_inliers) / float(corner_cloud.size());
188  if (ratio > best_ratio) {
189  best_ratio = ratio;
190  n = nrm;
191  d = -x0.dot(nrm);
192  }
193  }
194 
195  if(best_ratio < 0.9)
196  {
197  ROS_ERROR ("Could not estimate a planar model from the checkboard corners.");
198  last_sample_invalid_ = true;
199  return;
200  }
201 
202  ROS_DEBUG_STREAM( "Model coefficients: " << n[0] << " "
203  << n[1] << " "
204  << n[2] << " "
205  << d );
206 
207  unsigned vi=0;
208  for(size_t i = 0; i< features.image_points.size(); i++)
209  {
210  // intersect pixel ray with plane
211  geometry_msgs::Point& pixel = features.image_points[i];
212 
213  cv::Point3f ray_pt;
214  cloud_converter_.depthTo3DPoint( pixel, 1.0, ray_pt );
215  cv::Vec3f ray(ray_pt);
216  ray = ray / cv::norm(ray);
217 
218  float d1 = ray.dot(n);
219  float lambda = d / d1;
220 
221  ray = ray * lambda;
222 
223  if ( ray[2] < 0 )
224  {
225  ray = -ray;
226  }
227 
229  /*
230  float depth = *(depth_ptr+width*(unsigned int)pixel.y+(unsigned int)pixel.x);
231  if ( !isnan(depth) )
232  {
233  pcl::PointXYZ point;
234  cloud_converter_.depthTo3DPoint( pixel, depth, point );
235  std::cout << "3d point: " << point.x << ", " << point.y << ", " << point.z << std::endl;
236  }
237  std::cout << "ray-plane intersection: " << ray.x << ", " << ray.y << ", " << ray.z << std::endl;
238  */
240 
241  pixel.z = ray[2];
242  }
243 
244  // print 'back to normal' message once
245  if ( last_sample_invalid_ )
246  {
247  ROS_INFO_STREAM(s.str() << "Successfuly detected checkerboard.");
248  }
249 
250  last_sample_invalid_ = false;
251  pub_.publish(features);
252  }
253  }
254 
255 private:
256  boost::mutex run_mutex_;
260 
265 
267 
270 };
271 
272 int main(int argc, char** argv)
273 {
274  ros::init(argc, argv, "rgbd_cb_detector_action");
275  ros::NodeHandle n;
276  RgbdCbDetectorAction detector_action(n);
277  ros::spin();
278  return 0;
279 }
280 
d
Definition: setup.py:6
std::string getTopic() const
boost::shared_ptr< const Goal > acceptNewGoal()
image_cb_detector::ImageCbDetector detector_
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber< sensor_msgs::Image > image_sub_
message_filters::Subscriber< sensor_msgs::Image > depth_sub_
XmlRpcServer s
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
RgbdCbDetectorAction(ros::NodeHandle &n)
void cameraCallback(const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &caminfo_msg)
ROSCPP_DECL void spin(Spinner &spinner)
actionlib::SimpleActionServer< image_cb_detector::ConfigAction > as_
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
bool detect(const sensor_msgs::ImageConstPtr &image, calibration_msgs::CalibrationPattern &result)
void depthTo3DPoint(Point2D_T &image_pos, float depth, Point3D_T &point)
const std::string TYPE_32FC1
DepthToPointCloud cloud_converter_
void initialize(sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::CameraInfoConstPtr camera_info_msg)
void registerPreemptCallback(boost::function< void()> cb)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > CameraSyncPolicy
#define ROS_DEBUG_STREAM(args)
int main(int argc, char **argv)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
bool configure(const ConfigGoal &config)
#define ROS_INFO_STREAM(args)
message_filters::Synchronizer< CameraSyncPolicy > sync_
message_filters::Subscriber< sensor_msgs::CameraInfo > caminfo_sub_
#define ROS_ERROR_STREAM(args)
void registerGoalCallback(boost::function< void()> cb)
#define ROS_ERROR(...)


image_cb_detector
Author(s): Vijay Pradeep, Eitan Marder-Eppstein
autogenerated on Fri Apr 2 2021 02:12:56