Skip to content
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
4 changes: 1 addition & 3 deletions eagleye_core/coordinate/include/eagleye_coordinate/eagleye_coordinate.hpp
100755 → 100644
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,7 @@
#include <GeographicLib/MGRS.hpp>
#include <GeographicLib/UTMUPS.hpp>

class ConvertHeight
{
class ConvertHeight {
public:
ConvertHeight();

Expand Down Expand Up @@ -65,5 +64,4 @@ extern double geoid_per_degree(double, double);
extern double geoid_per_minute(double, double, double**);
extern double** read_geoid_map();


#endif /*COORDINATE_H */
53 changes: 22 additions & 31 deletions eagleye_core/coordinate/src/convertheight.cpp
100755 → 100644
Original file line number Diff line number Diff line change
Expand Up @@ -30,57 +30,48 @@

#include "eagleye_coordinate/eagleye_coordinate.hpp"

ConvertHeight::ConvertHeight()
{
}
ConvertHeight::ConvertHeight() {}

void ConvertHeight::setLLH(double latitude,double longitude,double height)
{
_latitude = latitude;
void ConvertHeight::setLLH(double latitude, double longitude, double height) {
_latitude = latitude;
_longitude = longitude;
_height = height;
_height = height;
}

double ConvertHeight::convert2altitude()
{
try
{
double ConvertHeight::convert2altitude() {
try {
GeographicLib::Geoid egm2008("egm2008-1");
converted_height = egm2008.ConvertHeight(_latitude, _longitude, _height, GeographicLib::Geoid::ELLIPSOIDTOGEOID);
}
catch (const GeographicLib::GeographicErr err)
{
std::cerr << "\033[31;1mError: Failed to convert height from Ellipsoid to Altitude. " << err.what() << std::endl;
converted_height =
egm2008.ConvertHeight(_latitude, _longitude, _height, GeographicLib::Geoid::ELLIPSOIDTOGEOID);
} catch (const GeographicLib::GeographicErr err) {
std::cerr << "\033[31;1mError: Failed to convert height from Ellipsoid to Altitude. "
<< err.what() << std::endl;
exit(4);
}

return converted_height;
}

double ConvertHeight::convert2ellipsoid()
{
try
{
double ConvertHeight::convert2ellipsoid() {
try {
GeographicLib::Geoid egm2008("egm2008-1");
converted_height = egm2008.ConvertHeight(_latitude, _longitude, _height, GeographicLib::Geoid::GEOIDTOELLIPSOID);
}
catch (const GeographicLib::GeographicErr err)
{
std::cerr << "\033[31;1mError: Failed to convert height from Ellipsoid to Altitude. " << err.what() << std::endl;
converted_height =
egm2008.ConvertHeight(_latitude, _longitude, _height, GeographicLib::Geoid::GEOIDTOELLIPSOID);
} catch (const GeographicLib::GeographicErr err) {
std::cerr << "\033[31;1mError: Failed to convert height from Ellipsoid to Altitude. "
<< err.what() << std::endl;
exit(4);
}

return converted_height;
}

double ConvertHeight::getGeoidPerDegree()
{
geoid = geoid_per_degree(_latitude,_longitude);
double ConvertHeight::getGeoidPerDegree() {
geoid = geoid_per_degree(_latitude, _longitude);
return geoid;
}

double ConvertHeight::getGeoidPerMinute()
{
geoid = geoid_per_minute(_latitude,_longitude,geoid_map_data);
double ConvertHeight::getGeoidPerMinute() {
geoid = geoid_per_minute(_latitude, _longitude, geoid_map_data);
return geoid;
}
33 changes: 16 additions & 17 deletions eagleye_core/coordinate/src/ecef2llh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,38 +26,37 @@
#include "eagleye_coordinate/eagleye_coordinate.hpp"
#include <math.h>


void ecef2llh(double ecef_pos[3], double llh_pos[3])
{
void ecef2llh(double ecef_pos[3], double llh_pos[3]) {
double semi_major_axis = 6378137.0000;
double semi_minor_axis = 6356752.3142;
double a1 = sqrt(1 - pow(semi_minor_axis / semi_major_axis, 2.0));
double a2 = sqrt((ecef_pos[0] * ecef_pos[0]) + (ecef_pos[1] * ecef_pos[1]));
double a3 = 54 * (semi_minor_axis * semi_minor_axis) * (ecef_pos[2] * ecef_pos[2]);
double a4 = (a2 * a2) + (1 - (a1 * a1)) * (ecef_pos[2] * ecef_pos[2]) - (a1 * a1) * (semi_major_axis * semi_major_axis - semi_minor_axis * semi_minor_axis);
double a4 = (a2 * a2) + (1 - (a1 * a1)) * (ecef_pos[2] * ecef_pos[2]) -
(a1 * a1) * (semi_major_axis * semi_major_axis - semi_minor_axis * semi_minor_axis);
double a5 = ((a1 * a1) * (a1 * a1) * a3 * (a2 * a2)) / (a4 * a4 * a4);
double a6 = pow((1 + a5 + sqrt(a5 * a5 + 2 * a5)), 1.0 / 3.0);
double a7 = a3 / (3 * pow((a6 + 1 / a6 + 1), 2.0) * a4 * a4);
double a8 = sqrt(1 + 2 * (a1 * a1) * (a1 * a1) * a7);
double a9 = -(a7 * (a1 * a1) * a2) / (1 + a8) + sqrt((semi_major_axis * semi_major_axis / 2) * (1 + 1 / a8) - (a7 * (1 - (a1 * a1)) * (ecef_pos[2] * ecef_pos[2])) / (a8 * (1 + a8)) - a7 * (a2 * a2) / 2);
double a9 = -(a7 * (a1 * a1) * a2) / (1 + a8) +
sqrt((semi_major_axis * semi_major_axis / 2) * (1 + 1 / a8) -
(a7 * (1 - (a1 * a1)) * (ecef_pos[2] * ecef_pos[2])) / (a8 * (1 + a8)) -
a7 * (a2 * a2) / 2);
double a10 = sqrt((pow((a2 - (a1 * a1) * a9), 2.0)) + (ecef_pos[2] * ecef_pos[2]));
double a11 = sqrt((pow((a2 - (a1 * a1) * a9), 2.0)) + (1 - (a1 * a1)) * (ecef_pos[2] * ecef_pos[2]));
double a11 =
sqrt((pow((a2 - (a1 * a1) * a9), 2.0)) + (1 - (a1 * a1)) * (ecef_pos[2] * ecef_pos[2]));
double a12 = ((semi_minor_axis * semi_minor_axis) * ecef_pos[2]) / (semi_major_axis * a11);
llh_pos[0] = atan((ecef_pos[2] + (a1 * (semi_major_axis / semi_minor_axis)) * (a1 * (semi_major_axis / semi_minor_axis)) * a12) / a2);
llh_pos[0] = atan((ecef_pos[2] + (a1 * (semi_major_axis / semi_minor_axis)) *
(a1 * (semi_major_axis / semi_minor_axis)) * a12) /
a2);
llh_pos[1] = 0;

if (ecef_pos[0] >= 0)
{
if (ecef_pos[0] >= 0) {
llh_pos[1] = (atan(ecef_pos[1] / ecef_pos[0]));
}
else
{
if (ecef_pos[0] < 0 && ecef_pos[1] >= 0)
{
} else {
if (ecef_pos[0] < 0 && ecef_pos[1] >= 0) {
llh_pos[1] = M_PI + (atan(ecef_pos[1] / ecef_pos[0]));
}
else
{
} else {
llh_pos[1] = (atan(ecef_pos[1] / ecef_pos[0])) - M_PI;
}
}
Expand Down
20 changes: 13 additions & 7 deletions eagleye_core/coordinate/src/enu2llh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,13 +26,19 @@
#include "eagleye_coordinate/eagleye_coordinate.hpp"
#include <math.h>

void enu2llh(double enu_pos[3], double ecef_base_pos[3], double llh_pos[3])
{
void enu2llh(double enu_pos[3], double ecef_base_pos[3], double llh_pos[3]) {
double llh_base_pos[3];
double ecef_pos[3];
ecef2llh(ecef_base_pos,llh_base_pos);
ecef_pos[0] = ecef_base_pos[0] + ((-(sin(llh_base_pos[1])) * enu_pos[0]) + (-(cos(llh_base_pos[1])) * (sin(llh_base_pos[0])) * enu_pos[1]) + ((cos(llh_base_pos[1])) * (cos(llh_base_pos[0])) * enu_pos[2]));
ecef_pos[1] = ecef_base_pos[1] + (((cos(llh_base_pos[1])) * enu_pos[0]) + (-(sin(llh_base_pos[1])) * (sin(llh_base_pos[0])) * enu_pos[1]) + ((sin(llh_base_pos[1])) * (cos(llh_base_pos[0])) * enu_pos[2]));
ecef_pos[2] = ecef_base_pos[2] + ((0 * enu_pos[0]) + ((cos(llh_base_pos[0])) * enu_pos[1]) + ((sin(llh_base_pos[0])) * enu_pos[2]));
ecef2llh(ecef_pos,llh_pos);
ecef2llh(ecef_base_pos, llh_base_pos);
ecef_pos[0] =
ecef_base_pos[0] + ((-(sin(llh_base_pos[1])) * enu_pos[0]) +
(-(cos(llh_base_pos[1])) * (sin(llh_base_pos[0])) * enu_pos[1]) +
((cos(llh_base_pos[1])) * (cos(llh_base_pos[0])) * enu_pos[2]));
ecef_pos[1] =
ecef_base_pos[1] + (((cos(llh_base_pos[1])) * enu_pos[0]) +
(-(sin(llh_base_pos[1])) * (sin(llh_base_pos[0])) * enu_pos[1]) +
((sin(llh_base_pos[1])) * (cos(llh_base_pos[0])) * enu_pos[2]));
ecef_pos[2] = ecef_base_pos[2] + ((0 * enu_pos[0]) + ((cos(llh_base_pos[0])) * enu_pos[1]) +
((sin(llh_base_pos[0])) * enu_pos[2]));
ecef2llh(ecef_pos, llh_pos);
}
6 changes: 3 additions & 3 deletions eagleye_core/coordinate/src/enu2xyz_vel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,14 +27,14 @@
#include <GeographicLib/Geocentric.hpp>
#include <eigen3/Eigen/StdVector>

void enu2xyz_vel(double enu_vel[3], double ecef_base_pos[3], double xyz_vel[3])
{
void enu2xyz_vel(double enu_vel[3], double ecef_base_pos[3], double xyz_vel[3]) {
using namespace GeographicLib;
Geocentric earth(Constants::WGS84_a(), Constants::WGS84_f());

std::vector<double> rotation(9);
double llh[3];
earth.Reverse(ecef_base_pos[0], ecef_base_pos[1], ecef_base_pos[2], llh[0], llh[1], llh[2], rotation);
earth.Reverse(ecef_base_pos[0], ecef_base_pos[1], ecef_base_pos[2], llh[0], llh[1], llh[2],
rotation);

Eigen::Matrix3d R(rotation.data());
Eigen::Vector3d v_enu(enu_vel);
Expand Down
Loading
Loading