GeoUtilities.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2010, LABUST, UNIZG-FER
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 LABUST 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 #ifndef GEOUTILITIES_HPP_
00035 #define GEOUTILITIES_HPP_
00036 #define _USE_MATH_DEFINES
00037 #include <utility>
00038 #include <math.h>
00039 
00040 namespace labust
00041 {
00045         namespace tools
00046   {
00047     static const double deg2rad = M_PI/180;
00048     static const double rad2deg = 180/M_PI;
00049     static const double radius = 6378137;
00050     static const double ratio = 0.99664719;
00051 
00057     inline double mpdlat(double lat)
00058     {
00059       return (111132.954 - 559.822*cos(2*lat*deg2rad) + 1.175*cos(4*lat*deg2rad));
00060     };
00066     inline double mpdlon(double lat)
00067     {
00068       return (radius*cos(atan(ratio*tan(lat*deg2rad)))*deg2rad);
00069     };
00079     inline std::pair<double,double> deg2meter(double difflat, double difflon, double lat)
00080     {
00081       return std::pair<double,double>(difflat*mpdlat(lat),difflon*mpdlon(lat));
00082     }
00092     inline std::pair<double,double> meter2deg(double x, double y, double lat)
00093     {
00094       return std::pair<double,double>(x/mpdlat(lat),y/mpdlon(lat));
00095     };
00096   }
00097 }
00098 /* GEOUTILITIES_HPP_ */
00099 #endif


snippets
Author(s): Gyula Nagy
autogenerated on Mon Oct 6 2014 01:39:41