height_map.h
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 #ifndef TOWR_HEIGHT_MAP_H_
00031 #define TOWR_HEIGHT_MAP_H_
00032 
00033 #include <memory>
00034 #include <vector>
00035 #include <map>
00036 #include <string>
00037 
00038 #include <Eigen/Dense>
00039 
00040 #include <towr/variables/cartesian_dimensions.h>
00041 
00042 namespace towr {
00043 
00071 class HeightMap {
00072 public:
00073   using Ptr      = std::shared_ptr<HeightMap>;
00074   using Vector3d = Eigen::Vector3d;
00075 
00079   enum TerrainID { FlatID,
00080                    BlockID,
00081                    StairsID,
00082                    GapID,
00083                    SlopeID,
00084                    ChimneyID,
00085                    ChimneyLRID,
00086                    TERRAIN_COUNT };
00087 
00088   static HeightMap::Ptr MakeTerrain(TerrainID type);
00089 
00090   enum Direction { Normal, Tangent1, Tangent2 };
00091 
00092   HeightMap() = default;
00093   virtual ~HeightMap () = default;
00094 
00100   virtual double GetHeight(double x, double y) const = 0;
00101 
00109   double GetDerivativeOfHeightWrt(Dim2D dim, double x, double y) const;
00110 
00118   Vector3d GetNormalizedBasis(Direction direction, double x, double y) const;
00119 
00128   Vector3d GetDerivativeOfNormalizedBasisWrt(Direction direction, Dim2D dim,
00129                                              double x, double y) const;
00133   double GetFrictionCoeff() const { return friction_coeff_; };
00134 
00135 protected:
00136   double friction_coeff_ = 0.5;
00137 
00138 private:
00139   using DimDerivs = std::vector<Dim2D>; 
00140 
00149   Vector3d GetBasis(Direction direction, double x, double y,
00150                     const DimDerivs& dim_deriv= {}) const;
00151 
00152   Vector3d GetNormal(double x,   double y, const DimDerivs& = {}) const;
00153   Vector3d GetTangent1(double x, double y, const DimDerivs& = {}) const;
00154   Vector3d GetTangent2(double x, double y, const DimDerivs& = {}) const;
00155 
00156   double GetSecondDerivativeOfHeightWrt(Dim2D dim1, Dim2D dim2,
00157                                         double x, double y) const;
00158 
00159   Vector3d GetDerivativeOfNormalizedVectorWrtNonNormalizedIndex(
00160       const Vector3d& non_normalized, int index) const;
00161 
00162   // first derivatives that must be implemented by the user
00163   virtual double GetHeightDerivWrtX(double x, double y) const { return 0.0; };
00164   virtual double GetHeightDerivWrtY(double x, double y) const { return 0.0; };
00165 
00166   // second derivatives with respect to first letter, then second
00167   virtual double GetHeightDerivWrtXX(double x, double y) const { return 0.0; };
00168   virtual double GetHeightDerivWrtXY(double x, double y) const { return 0.0; };
00169   virtual double GetHeightDerivWrtYX(double x, double y) const { return 0.0; };
00170   virtual double GetHeightDerivWrtYY(double x, double y) const { return 0.0; };
00171 };
00172 
00173 
00174 const static std::map<HeightMap::TerrainID, std::string> terrain_names =
00175 {
00176   {HeightMap::FlatID,        "Flat"       },
00177   {HeightMap::BlockID,       "Block"      },
00178   {HeightMap::StairsID,      "Stairs"     },
00179   {HeightMap::GapID,         "Gap"        },
00180   {HeightMap::SlopeID,       "Slope"      },
00181   {HeightMap::ChimneyID,     "Chimney"    },
00182   {HeightMap::ChimneyLRID,   "ChimenyLR"  }
00183 };
00184 
00185 } /* namespace towr */
00186 
00187 #endif /* TOWR_HEIGHT_MAP_H_ */


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