monocam_settler.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2009, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00036 
00037 #include <monocam_settler/monocam_settler.h>
00038 #include <settlerlib/interval_calc.h>
00039 
00040 using namespace monocam_settler;
00041 
00042 
00043 MonocamSettler::MonocamSettler() : cache_(&DeflatedMsgCache::getPtrStamp)
00044 {
00045   configured_ = false;
00046 }
00047 
00048 bool MonocamSettler::configure(const monocam_settler::ConfigGoal& goal)
00049 {
00050   tol_ = goal.tolerance;
00051   max_step_ = goal.max_step;
00052   ignore_failures_ = goal.ignore_failures;
00053   cache_.clear();
00054   cache_.setMaxSize(goal.cache_size);
00055 
00056   ROS_DEBUG("Configuring MonocamSettler with tolerance of [%.3f]", tol_);
00057 
00058   configured_ = true;
00059   return true;
00060 }
00061 
00062 
00063 bool MonocamSettler::add(const calibration_msgs::CalibrationPatternConstPtr msg,
00064                          calibration_msgs::Interval& interval)
00065 {
00066   if (!configured_)
00067   {
00068     ROS_WARN("Not configured. Going to skip");
00069     return false;
00070   }
00071 
00072   // Check if detection failed
00073   if (!msg->success)
00074   {
00075     if(!ignore_failures_)   // If we care about failures then we should reset the cache
00076       cache_.clear();
00077     return false;
00078   }
00079 
00080   boost::shared_ptr<DeflatedCalibrationPattern> deflated(new DeflatedCalibrationPattern);
00081   deflate(msg, *deflated);
00082   cache_.add(deflated);
00083 
00084   DeflatedCache* bare_cache = (DeflatedCache*)(&cache_);
00085 
00086   std::vector<double> tol_vec(deflated->channels_.size(), tol_);
00087 
00088   interval = settlerlib::IntervalCalc::computeLatestInterval(*bare_cache, tol_vec, max_step_);
00089 
00090   return true;
00091 }
00092 
00093 void MonocamSettler::deflate(const calibration_msgs::CalibrationPatternConstPtr& msg,
00094                              DeflatedCalibrationPattern& deflated)
00095 {
00096   deflated.header.stamp = msg->header.stamp;
00097 
00098   const unsigned int N = msg->image_points.size();
00099   deflated.channels_.resize( 2 * N );
00100   for (unsigned int i=0; i<N; i++)
00101   {
00102     deflated.channels_[2*i+0] = msg->image_points[i].x;
00103     deflated.channels_[2*i+1] = msg->image_points[i].y; 
00104   }
00105   deflated.msg_ = msg;
00106 }


monocam_settler
Author(s): Vijay Pradeep
autogenerated on Sun Oct 5 2014 22:43:58