This commit is contained in:
Your Name
2024-04-27 03:14:01 -05:00
parent f5ba304cd6
commit f23e5441b5
56 changed files with 3319 additions and 36416 deletions

2
common/transformations/.gitignore vendored Normal file
View File

@@ -0,0 +1,2 @@
transformations
transformations.cpp

View File

@@ -0,0 +1,70 @@
Reference Frames
------
Many reference frames are used throughout. This
folder contains all helper functions needed to
transform between them. Generally this is done
by generating a rotation matrix and multiplying.
| Name | [x, y, z] | Units | Notes |
| :-------------: |:-------------:| :-----:| :----: |
| Geodetic | [Latitude, Longitude, Altitude] | geodetic coordinates | Sometimes used as [lon, lat, alt], avoid this frame. |
| ECEF | [x, y, z] | meters | We use **ITRF14 (IGS14)**, NOT NAD83. <br> This is the global Mesh3D frame. |
| NED | [North, East, Down] | meters | Relative to earth's surface, useful for visualizing. |
| Device | [Forward, Right, Down] | meters | This is the Mesh3D local frame. <br> Relative to camera, **not imu.** <br> ![img](http://upload.wikimedia.org/wikipedia/commons/thumb/2/2f/RPY_angles_of_airplanes.png/440px-RPY_angles_of_airplanes.png)|
| Calibrated | [Forward, Right, Down] | meters | This is the frame the model outputs are in. <br> More details below. <br>|
| Car | [Forward, Right, Down] | meters | This is useful for estimating position of points on the road. <br> More details below. <br>|
| View | [Right, Down, Forward] | meters | Like device frame, but according to camera conventions. |
| Camera | [u, v, focal] | pixels | Like view frame, but 2d on the camera image.|
| Normalized Camera | [u / focal, v / focal, 1] | / | |
| Model | [u, v, focal] | pixels | The sampled rectangle of the full camera frame the model uses. |
| Normalized Model | [u / focal, v / focal, 1] | / | |
Orientation Conventions
------
Quaternions, rotation matrices and euler angles are three
equivalent representations of orientation and all three are
used throughout the code base.
For euler angles the preferred convention is [roll, pitch, yaw]
which corresponds to rotations around the [x, y, z] axes. All
euler angles should always be in radians or radians/s unless
for plotting or display purposes. For quaternions the hamilton
notations is preferred which is [q<sub>w</sub>, q<sub>x</sub>, q<sub>y</sub>, q<sub>z</sub>]. All quaternions
should always be normalized with a strictly positive q<sub>w</sub>. **These
quaternions are a unique representation of orientation whereas euler angles
or rotation matrices are not.**
To rotate from one frame into another with euler angles the
convention is to rotate around roll, then pitch and then yaw,
while rotating around the rotated axes, not the original axes.
Car frame
------
Device frame is aligned with the road-facing camera used by openpilot. However, when controlling the vehicle it is helpful to think in a reference frame aligned with the vehicle. These two reference frames can be different.
The orientation of car frame is defined to be aligned with the car's direction of travel and the road plane when the vehicle is driving on a flat road and not turning. The origin of car frame is defined to be directly below device frame (in car frame), such that it is on the road plane. The position and orientation of this frame is not necessarily always aligned with the direction of travel or the road plane due to suspension movements and other effects.
Calibrated frame
------
It is helpful for openpilot's driving model to take in images that look similar when mounted differently in different cars. To achieve this we "calibrate" the images by transforming it into calibrated frame. Calibrated frame is defined to be aligned with car frame in pitch and yaw, and aligned with device frame in roll. It also has the same origin as device frame.
Example
------
To transform global Mesh3D positions and orientations (positions_ecef, quats_ecef) into the local frame described by the
first position and orientation from Mesh3D one would do:
```
ecef_from_local = rot_from_quat(quats_ecef[0])
local_from_ecef = ecef_from_local.T
positions_local = np.einsum('ij,kj->ki', local_from_ecef, postions_ecef - positions_ecef[0])
rotations_global = rot_from_quat(quats_ecef)
rotations_local = np.einsum('ij,kjl->kil', local_from_ecef, rotations_global)
eulers_local = euler_from_rot(rotations_local)
```

View File

@@ -0,0 +1,5 @@
Import('env', 'envCython')
transformations = env.Library('transformations', ['orientation.cc', 'coordinates.cc'])
transformations_python = envCython.Program('transformations.so', 'transformations.pyx')
Export('transformations', 'transformations_python')

View File

@@ -1,55 +1,74 @@
import itertools
import numpy as np
from dataclasses import dataclass
import openpilot.common.transformations.orientation as orient
## -- hardcoded hardware params --
eon_f_focal_length = 910.0
eon_d_focal_length = 650.0
tici_f_focal_length = 2648.0
tici_e_focal_length = tici_d_focal_length = 567.0 # probably wrong? magnification is not consistent across frame
@dataclass(frozen=True)
class CameraConfig:
width: int
height: int
focal_length: float
eon_f_frame_size = (1164, 874)
eon_d_frame_size = (816, 612)
tici_f_frame_size = tici_e_frame_size = tici_d_frame_size = (1928, 1208)
@property
def size(self):
return (self.width, self.height)
# aka 'K' aka camera_frame_from_view_frame
eon_fcam_intrinsics = np.array([
[eon_f_focal_length, 0.0, float(eon_f_frame_size[0])/2],
[0.0, eon_f_focal_length, float(eon_f_frame_size[1])/2],
[0.0, 0.0, 1.0]])
eon_intrinsics = eon_fcam_intrinsics # xx
@property
def intrinsics(self):
# aka 'K' aka camera_frame_from_view_frame
return np.array([
[self.focal_length, 0.0, float(self.width)/2],
[0.0, self.focal_length, float(self.height)/2],
[0.0, 0.0, 1.0]
])
eon_dcam_intrinsics = np.array([
[eon_d_focal_length, 0.0, float(eon_d_frame_size[0])/2],
[0.0, eon_d_focal_length, float(eon_d_frame_size[1])/2],
[0.0, 0.0, 1.0]])
@property
def intrinsics_inv(self):
# aka 'K_inv' aka view_frame_from_camera_frame
return np.linalg.inv(self.intrinsics)
tici_fcam_intrinsics = np.array([
[tici_f_focal_length, 0.0, float(tici_f_frame_size[0])/2],
[0.0, tici_f_focal_length, float(tici_f_frame_size[1])/2],
[0.0, 0.0, 1.0]])
@dataclass(frozen=True)
class _NoneCameraConfig(CameraConfig):
width: int = 0
height: int = 0
focal_length: float = 0
tici_dcam_intrinsics = np.array([
[tici_d_focal_length, 0.0, float(tici_d_frame_size[0])/2],
[0.0, tici_d_focal_length, float(tici_d_frame_size[1])/2],
[0.0, 0.0, 1.0]])
@dataclass(frozen=True)
class DeviceCameraConfig:
fcam: CameraConfig
dcam: CameraConfig
ecam: CameraConfig
tici_ecam_intrinsics = tici_dcam_intrinsics
def all_cams(self):
for cam in ['fcam', 'dcam', 'ecam']:
if not isinstance(getattr(self, cam), _NoneCameraConfig):
yield cam, getattr(self, cam)
# aka 'K_inv' aka view_frame_from_camera_frame
eon_fcam_intrinsics_inv = np.linalg.inv(eon_fcam_intrinsics)
eon_intrinsics_inv = eon_fcam_intrinsics_inv # xx
_ar_ox_fisheye = CameraConfig(1928, 1208, 567.0) # focal length probably wrong? magnification is not consistent across frame
_os_fisheye = CameraConfig(2688, 1520, 567.0 / 2 * 3)
_ar_ox_config = DeviceCameraConfig(CameraConfig(1928, 1208, 2648.0), _ar_ox_fisheye, _ar_ox_fisheye)
_os_config = DeviceCameraConfig(CameraConfig(2688, 1520, 2648.0 * 2 / 3), _os_fisheye, _os_fisheye)
_neo_config = DeviceCameraConfig(CameraConfig(1164, 874, 910.0), CameraConfig(816, 612, 650.0), _NoneCameraConfig())
tici_fcam_intrinsics_inv = np.linalg.inv(tici_fcam_intrinsics)
tici_ecam_intrinsics_inv = np.linalg.inv(tici_ecam_intrinsics)
DEVICE_CAMERAS = {
# A "device camera" is defined by a device type and sensor
# sensor type was never set on eon/neo/two
("neo", "unknown"): _neo_config,
# unknown here is AR0231, field was added with OX03C10 support
("tici", "unknown"): _ar_ox_config,
FULL_FRAME_SIZE = tici_f_frame_size
FOCAL = tici_f_focal_length
fcam_intrinsics = tici_fcam_intrinsics
W, H = FULL_FRAME_SIZE[0], FULL_FRAME_SIZE[1]
# before deviceState.deviceType was set, assume tici AR config
("unknown", "ar0231"): _ar_ox_config,
("unknown", "ox03c10"): _ar_ox_config,
# simulator (emulates a tici)
("pc", "unknown"): _ar_ox_config,
}
prods = itertools.product(('tici', 'tizi', 'mici'), (('ar0231', _ar_ox_config), ('ox03c10', _ar_ox_config), ('os04c10', _os_config)))
DEVICE_CAMERAS.update({(d, c[0]): c[1] for d, c in prods})
# device/mesh : x->forward, y-> right, z->down
# view : x->right, y->down, z->forward
@@ -93,7 +112,7 @@ def roll_from_ke(m):
-(m[0, 0] - m[0, 1] * m[2, 0] / m[2, 1]))
def normalize(img_pts, intrinsics=fcam_intrinsics):
def normalize(img_pts, intrinsics):
# normalizes image coordinates
# accepts single pt or array of pts
intrinsics_inv = np.linalg.inv(intrinsics)
@@ -106,7 +125,7 @@ def normalize(img_pts, intrinsics=fcam_intrinsics):
return img_pts_normalized[:, :2].reshape(input_shape)
def denormalize(img_pts, intrinsics=fcam_intrinsics, width=np.inf, height=np.inf):
def denormalize(img_pts, intrinsics, width=np.inf, height=np.inf):
# denormalizes image coordinates
# accepts single pt or array of pts
img_pts = np.array(img_pts)
@@ -123,7 +142,7 @@ def denormalize(img_pts, intrinsics=fcam_intrinsics, width=np.inf, height=np.inf
return img_pts_denormalized[:, :2].reshape(input_shape)
def get_calib_from_vp(vp, intrinsics=fcam_intrinsics):
def get_calib_from_vp(vp, intrinsics):
vp_norm = normalize(vp, intrinsics)
yaw_calib = np.arctan(vp_norm[0])
pitch_calib = -np.arctan(vp_norm[1]*np.cos(yaw_calib))

View File

@@ -0,0 +1,100 @@
#define _USE_MATH_DEFINES
#include "common/transformations/coordinates.hpp"
#include <iostream>
#include <cmath>
#include <eigen3/Eigen/Dense>
double a = 6378137; // lgtm [cpp/short-global-name]
double b = 6356752.3142; // lgtm [cpp/short-global-name]
double esq = 6.69437999014 * 0.001; // lgtm [cpp/short-global-name]
double e1sq = 6.73949674228 * 0.001;
static Geodetic to_degrees(Geodetic geodetic){
geodetic.lat = RAD2DEG(geodetic.lat);
geodetic.lon = RAD2DEG(geodetic.lon);
return geodetic;
}
static Geodetic to_radians(Geodetic geodetic){
geodetic.lat = DEG2RAD(geodetic.lat);
geodetic.lon = DEG2RAD(geodetic.lon);
return geodetic;
}
ECEF geodetic2ecef(Geodetic g){
g = to_radians(g);
double xi = sqrt(1.0 - esq * pow(sin(g.lat), 2));
double x = (a / xi + g.alt) * cos(g.lat) * cos(g.lon);
double y = (a / xi + g.alt) * cos(g.lat) * sin(g.lon);
double z = (a / xi * (1.0 - esq) + g.alt) * sin(g.lat);
return {x, y, z};
}
Geodetic ecef2geodetic(ECEF e){
// Convert from ECEF to geodetic using Ferrari's methods
// https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#Ferrari.27s_solution
double x = e.x;
double y = e.y;
double z = e.z;
double r = sqrt(x * x + y * y);
double Esq = a * a - b * b;
double F = 54 * b * b * z * z;
double G = r * r + (1 - esq) * z * z - esq * Esq;
double C = (esq * esq * F * r * r) / (pow(G, 3));
double S = cbrt(1 + C + sqrt(C * C + 2 * C));
double P = F / (3 * pow((S + 1 / S + 1), 2) * G * G);
double Q = sqrt(1 + 2 * esq * esq * P);
double r_0 = -(P * esq * r) / (1 + Q) + sqrt(0.5 * a * a*(1 + 1.0 / Q) - P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r);
double U = sqrt(pow((r - esq * r_0), 2) + z * z);
double V = sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z);
double Z_0 = b * b * z / (a * V);
double h = U * (1 - b * b / (a * V));
double lat = atan((z + e1sq * Z_0) / r);
double lon = atan2(y, x);
return to_degrees({lat, lon, h});
}
LocalCoord::LocalCoord(Geodetic g, ECEF e){
init_ecef << e.x, e.y, e.z;
g = to_radians(g);
ned2ecef_matrix <<
-sin(g.lat)*cos(g.lon), -sin(g.lon), -cos(g.lat)*cos(g.lon),
-sin(g.lat)*sin(g.lon), cos(g.lon), -cos(g.lat)*sin(g.lon),
cos(g.lat), 0, -sin(g.lat);
ecef2ned_matrix = ned2ecef_matrix.transpose();
}
NED LocalCoord::ecef2ned(ECEF e) {
Eigen::Vector3d ecef;
ecef << e.x, e.y, e.z;
Eigen::Vector3d ned = (ecef2ned_matrix * (ecef - init_ecef));
return {ned[0], ned[1], ned[2]};
}
ECEF LocalCoord::ned2ecef(NED n) {
Eigen::Vector3d ned;
ned << n.n, n.e, n.d;
Eigen::Vector3d ecef = (ned2ecef_matrix * ned) + init_ecef;
return {ecef[0], ecef[1], ecef[2]};
}
NED LocalCoord::geodetic2ned(Geodetic g) {
ECEF e = ::geodetic2ecef(g);
return ecef2ned(e);
}
Geodetic LocalCoord::ned2geodetic(NED n){
ECEF e = ned2ecef(n);
return ::ecef2geodetic(e);
}

View File

@@ -1,19 +1,11 @@
import numpy as np
from openpilot.common.transformations.orientation import rot_from_euler
from openpilot.common.transformations.camera import (
FULL_FRAME_SIZE, get_view_frame_from_calib_frame, view_frame_from_device_frame,
eon_fcam_intrinsics, tici_ecam_intrinsics, tici_fcam_intrinsics)
from openpilot.common.transformations.camera import get_view_frame_from_calib_frame, view_frame_from_device_frame
# segnet
SEGNET_SIZE = (512, 384)
def get_segnet_frame_from_camera_frame(segnet_size=SEGNET_SIZE, full_frame_size=FULL_FRAME_SIZE):
return np.array([[float(segnet_size[0]) / full_frame_size[0], 0.0],
[0.0, float(segnet_size[1]) / full_frame_size[1]]])
segnet_frame_from_camera_frame = get_segnet_frame_from_camera_frame() # xx
# MED model
MEDMODEL_INPUT_SIZE = (512, 256)
MEDMODEL_YUV_SIZE = (MEDMODEL_INPUT_SIZE[0], MEDMODEL_INPUT_SIZE[1] * 3 // 2)
@@ -63,16 +55,9 @@ calib_from_medmodel = np.linalg.inv(medmodel_frame_from_calib_frame[:, :3])
calib_from_sbigmodel = np.linalg.inv(sbigmodel_frame_from_calib_frame[:, :3])
# This function is verified to give similar results to xx.uncommon.utils.transform_img
def get_warp_matrix(device_from_calib_euler: np.ndarray, wide_camera: bool = False, bigmodel_frame: bool = False, tici: bool = True) -> np.ndarray:
if tici and wide_camera:
cam_intrinsics = tici_ecam_intrinsics
elif tici:
cam_intrinsics = tici_fcam_intrinsics
else:
cam_intrinsics = eon_fcam_intrinsics
def get_warp_matrix(device_from_calib_euler: np.ndarray, intrinsics: np.ndarray, bigmodel_frame: bool = False) -> np.ndarray:
calib_from_model = calib_from_sbigmodel if bigmodel_frame else calib_from_medmodel
device_from_calib = rot_from_euler(device_from_calib_euler)
camera_from_calib = cam_intrinsics @ view_frame_from_device_frame @ device_from_calib
camera_from_calib = intrinsics @ view_frame_from_device_frame @ device_from_calib
warp_matrix: np.ndarray = camera_from_calib @ calib_from_model
return warp_matrix

View File

@@ -0,0 +1,144 @@
#define _USE_MATH_DEFINES
#include <iostream>
#include <cmath>
#include <eigen3/Eigen/Dense>
#include "common/transformations/orientation.hpp"
#include "common/transformations/coordinates.hpp"
Eigen::Quaterniond ensure_unique(Eigen::Quaterniond quat){
if (quat.w() > 0){
return quat;
} else {
return Eigen::Quaterniond(-quat.w(), -quat.x(), -quat.y(), -quat.z());
}
}
Eigen::Quaterniond euler2quat(Eigen::Vector3d euler){
Eigen::Quaterniond q;
q = Eigen::AngleAxisd(euler(2), Eigen::Vector3d::UnitZ())
* Eigen::AngleAxisd(euler(1), Eigen::Vector3d::UnitY())
* Eigen::AngleAxisd(euler(0), Eigen::Vector3d::UnitX());
return ensure_unique(q);
}
Eigen::Vector3d quat2euler(Eigen::Quaterniond quat){
// TODO: switch to eigen implementation if the range of the Euler angles doesn't matter anymore
// Eigen::Vector3d euler = quat.toRotationMatrix().eulerAngles(2, 1, 0);
// return {euler(2), euler(1), euler(0)};
double gamma = atan2(2 * (quat.w() * quat.x() + quat.y() * quat.z()), 1 - 2 * (quat.x()*quat.x() + quat.y()*quat.y()));
double asin_arg_clipped = std::clamp(2 * (quat.w() * quat.y() - quat.z() * quat.x()), -1.0, 1.0);
double theta = asin(asin_arg_clipped);
double psi = atan2(2 * (quat.w() * quat.z() + quat.x() * quat.y()), 1 - 2 * (quat.y()*quat.y() + quat.z()*quat.z()));
return {gamma, theta, psi};
}
Eigen::Matrix3d quat2rot(Eigen::Quaterniond quat){
return quat.toRotationMatrix();
}
Eigen::Quaterniond rot2quat(const Eigen::Matrix3d &rot){
return ensure_unique(Eigen::Quaterniond(rot));
}
Eigen::Matrix3d euler2rot(Eigen::Vector3d euler){
return quat2rot(euler2quat(euler));
}
Eigen::Vector3d rot2euler(const Eigen::Matrix3d &rot){
return quat2euler(rot2quat(rot));
}
Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw){
return euler2rot({roll, pitch, yaw});
}
Eigen::Matrix3d rot(Eigen::Vector3d axis, double angle){
Eigen::Quaterniond q;
q = Eigen::AngleAxisd(angle, axis);
return q.toRotationMatrix();
}
Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose) {
/*
Using Rotations to Build Aerospace Coordinate Systems
Don Koks
https://apps.dtic.mil/dtic/tr/fulltext/u2/a484864.pdf
*/
LocalCoord converter = LocalCoord(ecef_init);
Eigen::Vector3d zero = ecef_init.to_vector();
Eigen::Vector3d x0 = converter.ned2ecef({1, 0, 0}).to_vector() - zero;
Eigen::Vector3d y0 = converter.ned2ecef({0, 1, 0}).to_vector() - zero;
Eigen::Vector3d z0 = converter.ned2ecef({0, 0, 1}).to_vector() - zero;
Eigen::Vector3d x1 = rot(z0, ned_pose(2)) * x0;
Eigen::Vector3d y1 = rot(z0, ned_pose(2)) * y0;
Eigen::Vector3d z1 = rot(z0, ned_pose(2)) * z0;
Eigen::Vector3d x2 = rot(y1, ned_pose(1)) * x1;
Eigen::Vector3d y2 = rot(y1, ned_pose(1)) * y1;
Eigen::Vector3d z2 = rot(y1, ned_pose(1)) * z1;
Eigen::Vector3d x3 = rot(x2, ned_pose(0)) * x2;
Eigen::Vector3d y3 = rot(x2, ned_pose(0)) * y2;
x0 = Eigen::Vector3d(1, 0, 0);
y0 = Eigen::Vector3d(0, 1, 0);
z0 = Eigen::Vector3d(0, 0, 1);
double psi = atan2(x3.dot(y0), x3.dot(x0));
double theta = atan2(-x3.dot(z0), sqrt(pow(x3.dot(x0), 2) + pow(x3.dot(y0), 2)));
y2 = rot(z0, psi) * y0;
z2 = rot(y2, theta) * z0;
double phi = atan2(y3.dot(z2), y3.dot(y2));
return {phi, theta, psi};
}
Eigen::Vector3d ned_euler_from_ecef(ECEF ecef_init, Eigen::Vector3d ecef_pose){
/*
Using Rotations to Build Aerospace Coordinate Systems
Don Koks
https://apps.dtic.mil/dtic/tr/fulltext/u2/a484864.pdf
*/
LocalCoord converter = LocalCoord(ecef_init);
Eigen::Vector3d x0 = Eigen::Vector3d(1, 0, 0);
Eigen::Vector3d y0 = Eigen::Vector3d(0, 1, 0);
Eigen::Vector3d z0 = Eigen::Vector3d(0, 0, 1);
Eigen::Vector3d x1 = rot(z0, ecef_pose(2)) * x0;
Eigen::Vector3d y1 = rot(z0, ecef_pose(2)) * y0;
Eigen::Vector3d z1 = rot(z0, ecef_pose(2)) * z0;
Eigen::Vector3d x2 = rot(y1, ecef_pose(1)) * x1;
Eigen::Vector3d y2 = rot(y1, ecef_pose(1)) * y1;
Eigen::Vector3d z2 = rot(y1, ecef_pose(1)) * z1;
Eigen::Vector3d x3 = rot(x2, ecef_pose(0)) * x2;
Eigen::Vector3d y3 = rot(x2, ecef_pose(0)) * y2;
Eigen::Vector3d zero = ecef_init.to_vector();
x0 = converter.ned2ecef({1, 0, 0}).to_vector() - zero;
y0 = converter.ned2ecef({0, 1, 0}).to_vector() - zero;
z0 = converter.ned2ecef({0, 0, 1}).to_vector() - zero;
double psi = atan2(x3.dot(y0), x3.dot(x0));
double theta = atan2(-x3.dot(z0), sqrt(pow(x3.dot(x0), 2) + pow(x3.dot(y0), 2)));
y2 = rot(z0, psi) * y0;
z2 = rot(y2, theta) * z0;
double phi = atan2(y3.dot(z2), y3.dot(y2));
return {phi, theta, psi};
}

View File

@@ -1,5 +1,5 @@
import numpy as np
from typing import Callable
from collections.abc import Callable
from openpilot.common.transformations.transformations import (ecef_euler_from_ned_single,
euler2quat_single,

View File

View File

@@ -0,0 +1,109 @@
#!/usr/bin/env python3
import numpy as np
import unittest
import openpilot.common.transformations.coordinates as coord
geodetic_positions = np.array([[37.7610403, -122.4778699, 115],
[27.4840915, -68.5867592, 2380],
[32.4916858, -113.652821, -6],
[15.1392514, 103.6976037, 24],
[24.2302229, 44.2835412, 1650]])
ecef_positions = np.array([[-2711076.55270557, -4259167.14692758, 3884579.87669935],
[ 2068042.69652729, -5273435.40316622, 2927004.89190746],
[-2160412.60461669, -4932588.89873832, 3406542.29652851],
[-1458247.92550567, 5983060.87496612, 1654984.6099885 ],
[ 4167239.10867871, 4064301.90363223, 2602234.6065749 ]])
ecef_positions_offset = np.array([[-2711004.46961115, -4259099.33540613, 3884605.16002147],
[ 2068074.30639499, -5273413.78835412, 2927012.48741131],
[-2160344.53748176, -4932586.20092211, 3406636.2962545 ],
[-1458211.98517094, 5983151.11161276, 1655077.02698447],
[ 4167271.20055269, 4064398.22619263, 2602238.95265847]])
ned_offsets = np.array([[78.722153649976391, 24.396208657446344, 60.343017506838436],
[10.699003365155221, 37.319278617604269, 4.1084100025050407],
[95.282646251726959, 61.266689955574428, -25.376506058505054],
[68.535769283630003, -56.285970011848889, -100.54840137956515],
[-33.066609321880179, 46.549821994306861, -84.062540548335591]])
ecef_init_batch = np.array([2068042.69652729, -5273435.40316622, 2927004.89190746])
ecef_positions_offset_batch = np.array([[ 2068089.41454771, -5273434.46829148, 2927074.04783672],
[ 2068103.31628647, -5273393.92275431, 2927102.08725987],
[ 2068108.49939636, -5273359.27047121, 2927045.07091581],
[ 2068075.12395611, -5273381.69432566, 2927041.08207992],
[ 2068060.72033399, -5273430.6061505, 2927094.54928305]])
ned_offsets_batch = np.array([[ 53.88103168, 43.83445935, -46.27488057],
[ 93.83378995, 71.57943024, -30.23113187],
[ 57.26725796, 89.05602684, 23.02265814],
[ 49.71775195, 49.79767572, 17.15351015],
[ 78.56272609, 18.53100158, -43.25290759]])
class TestNED(unittest.TestCase):
def test_small_distances(self):
start_geodetic = np.array([33.8042184, -117.888593, 0.0])
local_coord = coord.LocalCoord.from_geodetic(start_geodetic)
start_ned = local_coord.geodetic2ned(start_geodetic)
np.testing.assert_array_equal(start_ned, np.zeros(3,))
west_geodetic = start_geodetic + [0, -0.0005, 0]
west_ned = local_coord.geodetic2ned(west_geodetic)
self.assertLess(np.abs(west_ned[0]), 1e-3)
self.assertLess(west_ned[1], 0)
southwest_geodetic = start_geodetic + [-0.0005, -0.002, 0]
southwest_ned = local_coord.geodetic2ned(southwest_geodetic)
self.assertLess(southwest_ned[0], 0)
self.assertLess(southwest_ned[1], 0)
def test_ecef_geodetic(self):
# testing single
np.testing.assert_allclose(ecef_positions[0], coord.geodetic2ecef(geodetic_positions[0]), rtol=1e-9)
np.testing.assert_allclose(geodetic_positions[0, :2], coord.ecef2geodetic(ecef_positions[0])[:2], rtol=1e-9)
np.testing.assert_allclose(geodetic_positions[0, 2], coord.ecef2geodetic(ecef_positions[0])[2], rtol=1e-9, atol=1e-4)
np.testing.assert_allclose(geodetic_positions[:, :2], coord.ecef2geodetic(ecef_positions)[:, :2], rtol=1e-9)
np.testing.assert_allclose(geodetic_positions[:, 2], coord.ecef2geodetic(ecef_positions)[:, 2], rtol=1e-9, atol=1e-4)
np.testing.assert_allclose(ecef_positions, coord.geodetic2ecef(geodetic_positions), rtol=1e-9)
def test_ned(self):
for ecef_pos in ecef_positions:
converter = coord.LocalCoord.from_ecef(ecef_pos)
ecef_pos_moved = ecef_pos + [25, -25, 25]
ecef_pos_moved_double_converted = converter.ned2ecef(converter.ecef2ned(ecef_pos_moved))
np.testing.assert_allclose(ecef_pos_moved, ecef_pos_moved_double_converted, rtol=1e-9)
for geo_pos in geodetic_positions:
converter = coord.LocalCoord.from_geodetic(geo_pos)
geo_pos_moved = geo_pos + np.array([0, 0, 10])
geo_pos_double_converted_moved = converter.ned2geodetic(converter.geodetic2ned(geo_pos) + np.array([0, 0, -10]))
np.testing.assert_allclose(geo_pos_moved[:2], geo_pos_double_converted_moved[:2], rtol=1e-9, atol=1e-6)
np.testing.assert_allclose(geo_pos_moved[2], geo_pos_double_converted_moved[2], rtol=1e-9, atol=1e-4)
def test_ned_saved_results(self):
for i, ecef_pos in enumerate(ecef_positions):
converter = coord.LocalCoord.from_ecef(ecef_pos)
np.testing.assert_allclose(converter.ned2ecef(ned_offsets[i]),
ecef_positions_offset[i],
rtol=1e-9, atol=1e-4)
np.testing.assert_allclose(converter.ecef2ned(ecef_positions_offset[i]),
ned_offsets[i],
rtol=1e-9, atol=1e-4)
def test_ned_batch(self):
converter = coord.LocalCoord.from_ecef(ecef_init_batch)
np.testing.assert_allclose(converter.ecef2ned(ecef_positions_offset_batch),
ned_offsets_batch,
rtol=1e-9, atol=1e-7)
np.testing.assert_allclose(converter.ned2ecef(ned_offsets_batch),
ecef_positions_offset_batch,
rtol=1e-9, atol=1e-7)
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,68 @@
#!/usr/bin/env python3
import numpy as np
import unittest
from openpilot.common.transformations.orientation import euler2quat, quat2euler, euler2rot, rot2euler, \
rot2quat, quat2rot, \
ned_euler_from_ecef
eulers = np.array([[ 1.46520501, 2.78688383, 2.92780854],
[ 4.86909526, 3.60618161, 4.30648981],
[ 3.72175965, 2.68763705, 5.43895988],
[ 5.92306687, 5.69573614, 0.81100357],
[ 0.67838374, 5.02402037, 2.47106426]])
quats = np.array([[ 0.66855182, -0.71500939, 0.19539353, 0.06017818],
[ 0.43163717, 0.70013301, 0.28209145, 0.49389021],
[ 0.44121991, -0.08252646, 0.34257534, 0.82532207],
[ 0.88578382, -0.04515356, -0.32936046, 0.32383617],
[ 0.06578165, 0.61282835, 0.07126891, 0.78424163]])
ecef_positions = np.array([[-2711076.55270557, -4259167.14692758, 3884579.87669935],
[ 2068042.69652729, -5273435.40316622, 2927004.89190746],
[-2160412.60461669, -4932588.89873832, 3406542.29652851],
[-1458247.92550567, 5983060.87496612, 1654984.6099885 ],
[ 4167239.10867871, 4064301.90363223, 2602234.6065749 ]])
ned_eulers = np.array([[ 0.46806039, -0.4881889 , 1.65697808],
[-2.14525969, -0.36533066, 0.73813479],
[-1.39523364, -0.58540761, -1.77376356],
[-1.84220435, 0.61828016, -1.03310421],
[ 2.50450101, 0.36304151, 0.33136365]])
class TestOrientation(unittest.TestCase):
def test_quat_euler(self):
for i, eul in enumerate(eulers):
np.testing.assert_allclose(quats[i], euler2quat(eul), rtol=1e-7)
np.testing.assert_allclose(quats[i], euler2quat(quat2euler(quats[i])), rtol=1e-6)
for i, eul in enumerate(eulers):
np.testing.assert_allclose(quats[i], euler2quat(list(eul)), rtol=1e-7)
np.testing.assert_allclose(quats[i], euler2quat(quat2euler(list(quats[i]))), rtol=1e-6)
np.testing.assert_allclose(quats, euler2quat(eulers), rtol=1e-7)
np.testing.assert_allclose(quats, euler2quat(quat2euler(quats)), rtol=1e-6)
def test_rot_euler(self):
for eul in eulers:
np.testing.assert_allclose(euler2quat(eul), euler2quat(rot2euler(euler2rot(eul))), rtol=1e-7)
for eul in eulers:
np.testing.assert_allclose(euler2quat(eul), euler2quat(rot2euler(euler2rot(list(eul)))), rtol=1e-7)
np.testing.assert_allclose(euler2quat(eulers), euler2quat(rot2euler(euler2rot(eulers))), rtol=1e-7)
def test_rot_quat(self):
for quat in quats:
np.testing.assert_allclose(quat, rot2quat(quat2rot(quat)), rtol=1e-7)
for quat in quats:
np.testing.assert_allclose(quat, rot2quat(quat2rot(list(quat))), rtol=1e-7)
np.testing.assert_allclose(quats, rot2quat(quat2rot(quats)), rtol=1e-7)
def test_euler_ned(self):
for i in range(len(eulers)):
np.testing.assert_allclose(ned_eulers[i], ned_euler_from_ecef(ecef_positions[i], eulers[i]), rtol=1e-7)
#np.testing.assert_allclose(eulers[i], ecef_euler_from_ned(ecef_positions[i], ned_eulers[i]), rtol=1e-7)
# np.testing.assert_allclose(ned_eulers, ned_euler_from_ecef(ecef_positions, eulers), rtol=1e-7)
if __name__ == "__main__":
unittest.main()

File diff suppressed because it is too large Load Diff