height_map.cc
Go to the documentation of this file.
00001 /******************************************************************************
00002 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
00003 
00004 Redistribution and use in source and binary forms, with or without
00005 modification, are permitted provided that the following conditions are met:
00006 
00007 * Redistributions of source code must retain the above copyright notice, this
00008   list of conditions and the following disclaimer.
00009 
00010 * Redistributions in binary form must reproduce the above copyright notice,
00011   this list of conditions and the following disclaimer in the documentation
00012   and/or other materials provided with the distribution.
00013 
00014 * Neither the name of the copyright holder nor the names of its
00015   contributors may be used to endorse or promote products derived from
00016   this software without specific prior written permission.
00017 
00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00022 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00023 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00024 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00025 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00026 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00027 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 ******************************************************************************/
00029 
00030 #include <towr/terrain/height_map.h>
00031 #include <towr/terrain/examples/height_map_examples.h>
00032 
00033 #include <cmath>
00034 
00035 namespace towr {
00036 
00037 HeightMap::Ptr
00038 HeightMap::MakeTerrain (TerrainID type)
00039 {
00040   switch (type) {
00041     case FlatID:      return std::make_shared<FlatGround>(); break;
00042     case BlockID:     return std::make_shared<Block>(); break;
00043     case StairsID:    return std::make_shared<Stairs>(); break;
00044     case GapID:       return std::make_shared<Gap>(); break;
00045     case SlopeID:     return std::make_shared<Slope>(); break;
00046     case ChimneyID:   return std::make_shared<Chimney>(); break;
00047     case ChimneyLRID: return std::make_shared<ChimneyLR>(); break;
00048     default: assert(false); break;
00049   }
00050 }
00051 
00052 double
00053 HeightMap::GetDerivativeOfHeightWrt (Dim2D dim, double x, double y) const
00054 {
00055   switch (dim) {
00056     case X: return GetHeightDerivWrtX(x,y);
00057     case Y: return GetHeightDerivWrtY(x,y);
00058     default: assert(false); // derivative dimension not implemented
00059   }
00060 }
00061 
00062 HeightMap::Vector3d
00063 HeightMap::GetNormalizedBasis (Direction basis, double x, double y) const
00064 {
00065   return GetBasis(basis, x, y).normalized();
00066 }
00067 
00068 HeightMap::Vector3d
00069 HeightMap::GetBasis (Direction basis, double x, double y,
00070                                   const DimDerivs& deriv) const
00071 {
00072   switch (basis) {
00073     case Normal:   return GetNormal(x,y, deriv);
00074     case Tangent1: return GetTangent1(x,y, deriv);
00075     case Tangent2: return GetTangent2(x,y, deriv);
00076     default: assert(false); // basis does not exist
00077   }
00078 }
00079 
00080 HeightMap::Vector3d
00081 HeightMap::GetDerivativeOfNormalizedBasisWrt (Direction basis, Dim2D dim,
00082                                               double x, double y) const
00083 {
00084   // inner derivative
00085   Vector3d dv_wrt_dim = GetBasis(basis, x, y, {dim});
00086 
00087   // outer derivative
00088   Vector3d v = GetBasis(basis, x,y, {});
00089   Vector3d dn_norm_wrt_n = GetDerivativeOfNormalizedVectorWrtNonNormalizedIndex(v, dim);
00090   return dn_norm_wrt_n.cwiseProduct(dv_wrt_dim);
00091 }
00092 
00093 HeightMap::Vector3d
00094 HeightMap::GetNormal(double x, double y, const DimDerivs& deriv) const
00095 {
00096   Vector3d n;
00097 
00098   bool basis_requested = deriv.empty();
00099 
00100   for (auto dim : {X_,Y_}) {
00101     if (basis_requested)
00102       n(dim) = -GetDerivativeOfHeightWrt(dim, x, y);
00103     else
00104       n(dim) = -GetSecondDerivativeOfHeightWrt(dim, deriv.front(), x, y);
00105   }
00106 
00107   n(Z) = basis_requested? 1.0 : 0.0;
00108 
00109   return n;
00110 }
00111 
00112 HeightMap::Vector3d
00113 HeightMap::GetTangent1 (double x, double y, const DimDerivs& deriv) const
00114 {
00115   Vector3d tx;
00116 
00117   bool basis_requested = deriv.empty();
00118 
00119   tx(X) = basis_requested? 1.0 : 0.0;
00120   tx(Y) = 0.0;
00121   tx(Z) = basis_requested? GetDerivativeOfHeightWrt(X_, x, y)
00122                          : GetSecondDerivativeOfHeightWrt(X_, deriv.front(), x, y);
00123 
00124   return tx;
00125 }
00126 
00127 HeightMap::Vector3d
00128 HeightMap::GetTangent2 (double x, double y, const DimDerivs& deriv) const
00129 {
00130   Vector3d ty;
00131 
00132   bool basis_requested = deriv.empty();
00133 
00134   ty(X) = 0.0;
00135   ty(Y) = basis_requested? 1.0 : 0.0;
00136   ty(Z) = basis_requested? GetDerivativeOfHeightWrt(Y_, x,y)
00137                          : GetSecondDerivativeOfHeightWrt(Y_, deriv.front(), x, y);
00138   return ty;
00139 }
00140 
00141 HeightMap::Vector3d
00142 HeightMap::GetDerivativeOfNormalizedVectorWrtNonNormalizedIndex (
00143     const Vector3d& v, int idx) const
00144 {
00145   // see notebook or
00146   // http://blog.mmacklin.com/2012/05/
00147   return 1/v.squaredNorm()*(v.norm() * Vector3d::Unit(idx) - v(idx)*v.normalized());
00148 }
00149 
00150 double
00151 HeightMap::GetSecondDerivativeOfHeightWrt (Dim2D dim1, Dim2D dim2,
00152                                            double x, double y) const
00153 {
00154   if (dim1 == X_) {
00155     if (dim2 == X_) return GetHeightDerivWrtXX(x,y);
00156     if (dim2 == Y_) return GetHeightDerivWrtXY(x,y);
00157   } else {
00158     if (dim2 == X_) return GetHeightDerivWrtYX(x,y);
00159     if (dim2 == Y_) return GetHeightDerivWrtYY(x,y);
00160   }
00161 
00162   assert(false); // second derivative not specified.
00163 }
00164 
00165 } /* namespace towr */


towr
Author(s): Alexander W. Winkler
autogenerated on Mon Apr 15 2019 02:42:32