joint_states_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 <sstream>
00038 #include <joint_states_settler/joint_states_settler.h>
00039 #include <settlerlib/interval_calc.h>
00040 #include <ros/console.h>
00041 
00042 using namespace joint_states_settler;
00043 
00044 JointStatesSettler::JointStatesSettler() : cache_(&DeflatedMsgCache::getPtrStamp)
00045 {
00046   configured_ = false;
00047 }
00048 
00049 bool JointStatesSettler::configure(const joint_states_settler::ConfigGoal& goal)
00050 {
00051   const unsigned int N = goal.joint_names.size();
00052 
00053   if (N != goal.tolerances.size())
00054   {
00055     ROS_ERROR("Invalid configuration for JointStatesSettler:\n"
00056               "  [joint_names.size() == %u] should equal [tolerances.size() == %u]",
00057               goal.joint_names.size(), goal.tolerances.size());
00058     return false;
00059   }
00060 
00061   deflater_.setDeflationJointNames(goal.joint_names);
00062   tol_ = goal.tolerances;
00063   max_step_ = goal.max_step;
00064   cache_.clear();
00065   cache_.setMaxSize(goal.cache_size);
00066 
00067   std::ostringstream info;
00068   ROS_DEBUG("Configuring JointStatesSettler with the following joints:");
00069   for (unsigned int i=0; i<N; i++)
00070     ROS_DEBUG_STREAM("   " << goal.joint_names[i] << ": " << goal.tolerances[i]);
00071 
00072   configured_ = true;
00073   return true;
00074 }
00075 
00076 calibration_msgs::Interval JointStatesSettler::add(const sensor_msgs::JointStateConstPtr msg)
00077 {
00078   if (!configured_)
00079   {
00080     ROS_WARN("Not yet configured. Going to skip");
00081     return calibration_msgs::Interval();
00082   }
00083 
00084   boost::shared_ptr<DeflatedJointStates> deflated(new DeflatedJointStates);
00085   deflater_.deflate(msg, *deflated);
00086   cache_.add(deflated);
00087 
00088   DeflatedCache* bare_cache = (DeflatedCache*)(&cache_);
00089 
00090   calibration_msgs::Interval interval = settlerlib::IntervalCalc::computeLatestInterval(*bare_cache, tol_, max_step_);
00091 
00092   return interval;
00093 }
00094 
00095 sensor_msgs::JointState JointStatesSettler::pruneJointState(const sensor_msgs::JointStateConstPtr msg)
00096 {
00097   sensor_msgs::JointState pruned;
00098   deflater_.prune(*msg, pruned);
00099   return pruned;
00100 }


joint_states_settler
Author(s): Vijay Pradeep, Eitan Marder-Eppstein
autogenerated on Wed Aug 26 2015 10:56:10