00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 00010 00011 * notice, this list of conditions and the following disclaimer. 00012 * * Redistributions in binary form must reproduce the above copyright 00013 * notice, this list of conditions and the following disclaimer in the 00014 * documentation and/or other materials provided with the distribution. 00015 * * Neither the name of the Willow Garage, Inc. nor the names of its 00016 * contributors may be used to endorse or promote products derived from 00017 * this software without specific prior written permission. 00018 * 00019 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00020 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00021 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00022 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00023 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00024 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00025 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00026 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00027 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00028 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00029 * POSSIBILITY OF SUCH DAMAGE. 00030 * 00031 */ 00032 00041 #include <semanticmodel/velocity.h> 00042 00043 namespace semanticmodel 00044 { 00045 00046 namespace gm=geometry_msgs; 00047 00048 using std::string; 00049 00050 // three point one-sided interpolation for first derivative 00051 inline 00052 double deriv (const double y0, const double y1, const double y2, 00053 const double inc) 00054 { 00055 return (3*y0 - 4*y1 + y2)/(2*inc); 00056 } 00057 00058 // Lookup tf transforms at times t, t-inc, t-2*inc, and interpolate 00059 gm::Vector3 VelocityCalc::velocity (const gm::PointStamped& p) const 00060 { 00061 tf::Point pts[3]; 00062 const tf::Point p0(p.point.x, p.point.y, p.point.z); 00063 const double t0 = p.header.stamp.toSec(); 00064 for (unsigned i=0; i<3; i++) 00065 { 00066 const double t = t0-i*inc_; 00067 const tf::StampedTransform trans = 00068 transforms_->lookupTransform(reference_frame_, p.header.frame_id, t); 00069 pts[i] = trans*p0; 00070 } 00071 gm::Vector3 v; 00072 v.x = deriv(pts[0].x(), pts[1].x(), pts[2].x(), inc_); 00073 v.y = deriv(pts[0].y(), pts[1].y(), pts[2].y(), inc_); 00074 v.z = deriv(pts[0].z(), pts[1].z(), pts[2].z(), inc_); 00075 return v; 00076 } 00077 00078 } // namespace