Skip to content

任意座標を原点とした横メルカトルへの対応 #16

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 8 commits into from
Mar 17, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
33 changes: 22 additions & 11 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# llh_converter

(Updated 2022/03/24)
(Updated 2025/03/17)

This repository has two class implementation.

Expand All @@ -17,6 +17,7 @@ Convert height between ellipsoid and orthometric library

* EGM2008-1
* GSIGEO2011 Ver2.1
* GSIGEO2024beta (Data file will be updated in 2025/04)

### Usage

Expand All @@ -27,7 +28,7 @@ hc.setGeoidType(height_converter::GeoidType::GSIGEO2011); // Select Geoid Model
// hc.setGeoidType(height_converter::GeoidType::EGM2008);

hc.setGSIGEOGeoidFile(path_to_gsigeo_asc_file); // Load geoid data file when you select GSIGEO
// hc.setGSIGEOGeoidFile(); // If called with void, it try to read /usr/share/GSIGEO/gsigeo2011_ver2_1.asc
// hc.setGSIGEOGeoidFile(); // If called with void, it try to read geoid data files under /usr/share/GSIGEO/

double geoid_heith = hc.getGeoid(lat, lon); // Get geoid heigth with latitude/longitude in decimal degree

Expand All @@ -46,19 +47,29 @@ Convert latitude/longitude/altitude into XYZ coordinate system.

* Millitary Grid Reference System (MGRS)
* Japan Plane Rectangular Coordinate System (JPRCS)
* Transverse Mercator with an arbitrary origin (TM)

### Usage

```
llh_converter::LLHConverter lc;
llh_converter::LLHParam param; // parameter for conversion
param.use_mgrs = true; // set true if you want to use MGRS
param.plane_num = 9; // set the plane number when you use JPRCS
param.mgrs_code = "53SPU"; // MGRS grid code is required when you revert MGRS x/y into lat/lon
llh_converter::LLHParam param; // parameter for conversion
param.projection_method = llh_converter::ProjectionMethod::TM;
// set the projection method TM/JPRCS/MGRS
param.plane_num = "9"; // set the grid code for JPRCS/MGRS
// for MGRS, it's required only when reverting to lat/lon
param.height_convert_type = llh_converter::ConvertType::ELLIPS2ORTHO;
// You can also convert height
// You can also convert height
param.geoid_type = llh_converter::GeoidType::EGM2008;
// Set geoid model
// Set geoid model
// The following tm_param is required only when the projection method is TM
param.tm_param.inv_flatten_ratio = 298.257222101;
// Set the inverse flattening ratio
param.tm_param.semi_mejor_axis = 6378137.0; // Set the semi-major axis
param.tm_param.scale_factor = 0.9996; // Set the scale factor
param.tm_param.origin_lat_rad = 35.0 * M_PI / 180.;
param.tm_param.origin_lon_rad = 139.0 * M_PI / 180.;
// Set the origin

double lat_deg, lon_deg, alt;
double lat_rad = lat_deg * M_PI / 180.;
Expand Down Expand Up @@ -87,8 +98,8 @@ The meridian convergence angle is calculated by the `getMeridianConvergence()` f
```
llh_converter::LLHConverter lc;
llh_converter::LLHParam param;
param.use_mgrs = false;
param.plane_num = 7;
param.projection_method = llh_converter::ProjectionMethod::JPRCS;
param.grid_code = "7";
param.height_convert_type = llh_converter::ConvertType::NONE;
param.geoid_type = llh_converter::GeoidType::EGM2008;

Expand Down Expand Up @@ -130,4 +141,4 @@ This package contains GSIGEO2011/GSIGEO2024 geoid data file which is provided by

## LICENSE

This package is provided under the [BSD 3-Clauses](LICENSE) License.
This package is provided under the [BSD 3-Clauses](LICENSE) License.
49 changes: 37 additions & 12 deletions include/llh_converter/llh_converter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,14 +53,30 @@ enum class MGRSPrecision
MICRO_METER_100 = 9,
};

enum class ProjectionMethod
{
TM = 0,
JPRCS = 1,
MGRS = 2,
};

struct TMParam
{
double inv_flatten_ratio;
double semi_major_axis;
double scale_factor;
double origin_lat_rad;
double origin_lon_rad;
};

struct LLHParam
{
bool use_mgrs;
int plane_num;
std::string mgrs_code;
ProjectionMethod projection_method;
std::string grid_code;
// MGRSPrecision precision;
ConvertType height_convert_type;
GeoidType geoid_type;
TMParam tm_param;
};

class LLHConverter
Expand All @@ -75,8 +91,11 @@ class LLHConverter
void revertXYZ2Deg(const double& x, const double& y, double& lat_deg, double& lon_deg, const LLHParam& param);
void revertXYZ2Rad(const double& x, const double& y, double& lat_rad, double& lon_rad, const LLHParam& param);

void convertMGRS2JPRCS(const double& m_x, const double& m_y, double& j_x, double& j_y, const LLHParam& param);
void convertJPRCS2MGRS(const double& j_x, const double& j_y, double& m_x, double& m_y, const LLHParam& param);
void convertMGRS2JPRCS(const double& m_x, const double& m_y, double& j_x, double& j_y, const std::string& mgrs_code,
const int jprcs_code);
void convertJPRCS2MGRS(const double& j_x, const double& j_y, double& m_x, double& m_y, const int jprcs_code);
void convertProj2Proj(const double& before_x, const double& before_y, const LLHParam& before_param, double& after_x,
double& after_y, const LLHParam& after_param);

void getMapOriginDeg(double& lat_rad, double& lon_rad, const LLHParam& param);
void getMapOriginRad(double& lat_rad, double& lon_rad, const LLHParam& param);
Expand All @@ -100,23 +119,29 @@ class LLHConverter
bool use_origin_zone_ = true;
bool is_origin_set_ = false;

// Constant param
const double F_ = 298.257222101;
const double a_ = 6378137;
const double m0_ = 0.9999;
// Constant param for MGRS
const int grid_code_size_ = 5;
MGRSPrecision precision_ = MGRSPrecision::MICRO_METER_100;

// origins for JPRCS
std::vector<double> jprcs_origin_lat_rads_;
std::vector<double> jprcs_origin_lon_rads_;
TMParam jprcs_tm_param_;

// Object
HeightConverter height_converter_;

// Functions
// TransverseMercator
void convRad2TM(const double& lat_rad, const double& lon_rad, const TMParam& param, double& x, double& y);
void revTM2Rad(const double& x, const double& y, const TMParam& param, double& lat_rad, double& lon_rad);
// Japan Plane Rectangular Coordinate System
void convRad2JPRCS(const double& lat_rad, const double& lon_rad, double& x, double& y);
void revJPRCS2Rad(const double& x, const double& y, double& lat_rad, double& lon_rad);
void initializeJPRCSOrigins();
void convRad2JPRCS(const double& lat_rad, const double& lon_rad, const int grid_code, double& x, double& y);
void revJPRCS2Rad(const double& x, const double& y, const int grid_code, double& lat_rad, double& lon_rad);
// MGRS
void convRad2MGRS(const double& lat_rad, const double& lon_rad, double& x, double& y);
void revMGRS2Rad(const double& x, const double& y, double& lat_rad, double& lon_rad);
void revMGRS2Rad(const double& x, const double& y, std::string mgrs_code, double& lat_rad, double& lon_rad);

std::pair<int, double> getCrossNum(const double& x);
std::string getOffsetZone(const std::string& zone, const int& offset);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ struct XYZ
double z;
};

double getMeridianConvergence(const LLA &lla, const XYZ &xyz, LLHConverter &llhc, const LLHParam &llhc_param);
double getMeridianConvergence(const LLA& lla, const XYZ& xyz, LLHConverter& llhc, const LLHParam& llhc_param);
double getMeridianConvergence(const LLA& lla, LLHConverter& llhc, const LLHParam& llhc_param);
double getMeridianConvergence(const XYZ& xyz, LLHConverter& llhc, const LLHParam& llhc_param);
} // namespace llh_converter
Expand Down
187 changes: 93 additions & 94 deletions src/gsigeo2024.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,113 +39,112 @@
#include <boost/algorithm/string.hpp>
namespace llh_converter
{

GSIGEO2024::GSIGEO2024() {}

GSIGEO2024::~GSIGEO2024() {}

void GSIGEO2024::loadGeoidMap(const std::string &geoid_file)
GSIGEO2024::GSIGEO2024()
{
std::ifstream infile(geoid_file);
if (!infile)
{
std::cerr << "Error opening file: " << geoid_file << std::endl;
return;
}

std::string line;
bool header_end = false;
while (std::getline(infile, line))
{
if (line.find("end_of_head") != std::string::npos)
{
header_end = true;
break;
}
}

if (!header_end)
{
std::cerr << "Header not properly formatted in file." << std::endl;
return;
}

geoid_map_.resize(row_size_, std::vector<double>(column_size_, -9999.0));

for (int i = 0; i < row_size_; ++i)
{
for (int j = 0; j < column_size_; ++j)
{
if (!(infile >> geoid_map_[i][j]))
{
std::cerr << "Error reading geoid data at row " << i << ", col " << j << std::endl;
return;
}
}
}

is_geoid_loaded_ = true;
}

double GSIGEO2024::getGeoid(const double &lat, const double &lon)
GSIGEO2024::~GSIGEO2024()
{
if (!is_geoid_loaded_)
{
std::cerr << "Geoid map not loaded." << std::endl;
return std::numeric_limits<double>::quiet_NaN();
}
}

if (lat < 15.0 || lat > 50.0 || lon < 120.0 || lon > 160.0)
void GSIGEO2024::loadGeoidMap(const std::string& geoid_file)
{
std::ifstream infile(geoid_file);
if (!infile)
{
std::cerr << "Error opening file: " << geoid_file << std::endl;
return;
}

std::string line;
bool header_end = false;
while (std::getline(infile, line))
{
if (line.find("end_of_head") != std::string::npos)
{
std::cerr << "Input coordinates out of range." << std::endl;
return std::numeric_limits<double>::quiet_NaN();
header_end = true;
break;
}
}

// Grid step (latitude 1 minute = 0.0166667 degrees, longitude 1.5 minutes = 0.025 degrees)
const double lat_step = 1.0 / 60.0;
const double lon_step = 1.5 / 60.0;

// The index calculation from the reference point (latitude 50 degrees, longitude 120 degrees)
int i1 = static_cast<int>((50.0 - lat) / lat_step);
int j1 = static_cast<int>((lon - 120.0) / lon_step);

int i2 = i1 + 1;
int j2 = j1 + 1;
if (!header_end)
{
std::cerr << "Header not properly formatted in file." << std::endl;
return;
}

if (i1 < 0 || i2 >= row_size_ || j1 < 0 || j2 >= column_size_)
{
return std::numeric_limits<double>::quiet_NaN();
}
geoid_map_.resize(row_size_, std::vector<double>(column_size_, -9999.0));

// Geoid height at the four corners
double f00 = geoid_map_[i1][j1];
double f10 = geoid_map_[i1][j2];
double f01 = geoid_map_[i2][j1];
double f11 = geoid_map_[i2][j2];

if (f00 == -9999.0 || f10 == -9999.0 || f01 == -9999.0 || f11 == -9999.0)
for (int i = 0; i < row_size_; ++i)
{
for (int j = 0; j < column_size_; ++j)
{
return std::numeric_limits<double>::quiet_NaN();
if (!(infile >> geoid_map_[i][j]))
{
std::cerr << "Error reading geoid data at row " << i << ", col " << j << std::endl;
return;
}
}
}

// Coordinates of the four corners
double lat1 = 50.0 - i1 * lat_step;
double lat2 = lat1 - lat_step;
double lon1 = 120.0 + j1 * lon_step;
double lon2 = lon1 + lon_step;

// Calculate interpolation coefficients correctly
double t = (lat1 - lat) / (lat1 - lat2);
double u = (lon - lon1) / (lon2 - lon1);

// Bilinear interpolation
double interpolated_value =
(1 - t) * (1 - u) * f00 +
(1 - t) * u * f10 +
t * (1 - u) * f01 +
t * u * f11;
is_geoid_loaded_ = true;
}

return interpolated_value;
double GSIGEO2024::getGeoid(const double& lat, const double& lon)
{
if (!is_geoid_loaded_)
{
std::cerr << "Geoid map not loaded." << std::endl;
return std::numeric_limits<double>::quiet_NaN();
}

if (lat < 15.0 || lat > 50.0 || lon < 120.0 || lon > 160.0)
{
std::cerr << "Input coordinates out of range." << std::endl;
return std::numeric_limits<double>::quiet_NaN();
}

// Grid step (latitude 1 minute = 0.0166667 degrees, longitude 1.5 minutes = 0.025 degrees)
const double lat_step = 1.0 / 60.0;
const double lon_step = 1.5 / 60.0;

// The index calculation from the reference point (latitude 50 degrees, longitude 120 degrees)
int i1 = static_cast<int>((50.0 - lat) / lat_step);
int j1 = static_cast<int>((lon - 120.0) / lon_step);

int i2 = i1 + 1;
int j2 = j1 + 1;

if (i1 < 0 || i2 >= row_size_ || j1 < 0 || j2 >= column_size_)
{
return std::numeric_limits<double>::quiet_NaN();
}

// Geoid height at the four corners
double f00 = geoid_map_[i1][j1];
double f10 = geoid_map_[i1][j2];
double f01 = geoid_map_[i2][j1];
double f11 = geoid_map_[i2][j2];

if (f00 == -9999.0 || f10 == -9999.0 || f01 == -9999.0 || f11 == -9999.0)
{
return std::numeric_limits<double>::quiet_NaN();
}

// Coordinates of the four corners
double lat1 = 50.0 - i1 * lat_step;
double lat2 = lat1 - lat_step;
double lon1 = 120.0 + j1 * lon_step;
double lon2 = lon1 + lon_step;

// Calculate interpolation coefficients correctly
double t = (lat1 - lat) / (lat1 - lat2);
double u = (lon - lon1) / (lon2 - lon1);

// Bilinear interpolation
double interpolated_value = (1 - t) * (1 - u) * f00 + (1 - t) * u * f10 + t * (1 - u) * f01 + t * u * f11;

return interpolated_value;
}

} // namespace llh_converter
} // namespace llh_converter
Loading