openpilot v0.9.6 release
date: 2024-01-12T10:13:37 master commit: ba792d576a49a0899b88a753fa1c52956bedf9e6
This commit is contained in:
5
common/transformations/SConscript
Normal file
5
common/transformations/SConscript
Normal 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')
|
||||
0
common/transformations/__init__.py
Normal file
0
common/transformations/__init__.py
Normal file
160
common/transformations/camera.py
Normal file
160
common/transformations/camera.py
Normal file
@@ -0,0 +1,160 @@
|
||||
import numpy as np
|
||||
|
||||
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
|
||||
|
||||
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)
|
||||
|
||||
# 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
|
||||
|
||||
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]])
|
||||
|
||||
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]])
|
||||
|
||||
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]])
|
||||
|
||||
tici_ecam_intrinsics = tici_dcam_intrinsics
|
||||
|
||||
# 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
|
||||
|
||||
tici_fcam_intrinsics_inv = np.linalg.inv(tici_fcam_intrinsics)
|
||||
tici_ecam_intrinsics_inv = np.linalg.inv(tici_ecam_intrinsics)
|
||||
|
||||
|
||||
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]
|
||||
|
||||
|
||||
# device/mesh : x->forward, y-> right, z->down
|
||||
# view : x->right, y->down, z->forward
|
||||
device_frame_from_view_frame = np.array([
|
||||
[ 0., 0., 1.],
|
||||
[ 1., 0., 0.],
|
||||
[ 0., 1., 0.]
|
||||
])
|
||||
view_frame_from_device_frame = device_frame_from_view_frame.T
|
||||
|
||||
|
||||
# aka 'extrinsic_matrix'
|
||||
# road : x->forward, y -> left, z->up
|
||||
def get_view_frame_from_road_frame(roll, pitch, yaw, height):
|
||||
device_from_road = orient.rot_from_euler([roll, pitch, yaw]).dot(np.diag([1, -1, -1]))
|
||||
view_from_road = view_frame_from_device_frame.dot(device_from_road)
|
||||
return np.hstack((view_from_road, [[0], [height], [0]]))
|
||||
|
||||
|
||||
|
||||
# aka 'extrinsic_matrix'
|
||||
def get_view_frame_from_calib_frame(roll, pitch, yaw, height):
|
||||
device_from_calib= orient.rot_from_euler([roll, pitch, yaw])
|
||||
view_from_calib = view_frame_from_device_frame.dot(device_from_calib)
|
||||
return np.hstack((view_from_calib, [[0], [height], [0]]))
|
||||
|
||||
|
||||
def vp_from_ke(m):
|
||||
"""
|
||||
Computes the vanishing point from the product of the intrinsic and extrinsic
|
||||
matrices C = KE.
|
||||
|
||||
The vanishing point is defined as lim x->infinity C (x, 0, 0, 1).T
|
||||
"""
|
||||
return (m[0, 0]/m[2, 0], m[1, 0]/m[2, 0])
|
||||
|
||||
|
||||
def roll_from_ke(m):
|
||||
# note: different from calibration.h/RollAnglefromKE: i think that one's just wrong
|
||||
return np.arctan2(-(m[1, 0] - m[1, 1] * m[2, 0] / m[2, 1]),
|
||||
-(m[0, 0] - m[0, 1] * m[2, 0] / m[2, 1]))
|
||||
|
||||
|
||||
def normalize(img_pts, intrinsics=fcam_intrinsics):
|
||||
# normalizes image coordinates
|
||||
# accepts single pt or array of pts
|
||||
intrinsics_inv = np.linalg.inv(intrinsics)
|
||||
img_pts = np.array(img_pts)
|
||||
input_shape = img_pts.shape
|
||||
img_pts = np.atleast_2d(img_pts)
|
||||
img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0], 1))))
|
||||
img_pts_normalized = img_pts.dot(intrinsics_inv.T)
|
||||
img_pts_normalized[(img_pts < 0).any(axis=1)] = np.nan
|
||||
return img_pts_normalized[:, :2].reshape(input_shape)
|
||||
|
||||
|
||||
def denormalize(img_pts, intrinsics=fcam_intrinsics, width=np.inf, height=np.inf):
|
||||
# denormalizes image coordinates
|
||||
# accepts single pt or array of pts
|
||||
img_pts = np.array(img_pts)
|
||||
input_shape = img_pts.shape
|
||||
img_pts = np.atleast_2d(img_pts)
|
||||
img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0], 1), dtype=img_pts.dtype)))
|
||||
img_pts_denormalized = img_pts.dot(intrinsics.T)
|
||||
if np.isfinite(width):
|
||||
img_pts_denormalized[img_pts_denormalized[:, 0] > width] = np.nan
|
||||
img_pts_denormalized[img_pts_denormalized[:, 0] < 0] = np.nan
|
||||
if np.isfinite(height):
|
||||
img_pts_denormalized[img_pts_denormalized[:, 1] > height] = np.nan
|
||||
img_pts_denormalized[img_pts_denormalized[:, 1] < 0] = np.nan
|
||||
return img_pts_denormalized[:, :2].reshape(input_shape)
|
||||
|
||||
|
||||
def get_calib_from_vp(vp, intrinsics=fcam_intrinsics):
|
||||
vp_norm = normalize(vp, intrinsics)
|
||||
yaw_calib = np.arctan(vp_norm[0])
|
||||
pitch_calib = -np.arctan(vp_norm[1]*np.cos(yaw_calib))
|
||||
roll_calib = 0
|
||||
return roll_calib, pitch_calib, yaw_calib
|
||||
|
||||
|
||||
def device_from_ecef(pos_ecef, orientation_ecef, pt_ecef):
|
||||
# device from ecef frame
|
||||
# device frame is x -> forward, y-> right, z -> down
|
||||
# accepts single pt or array of pts
|
||||
input_shape = pt_ecef.shape
|
||||
pt_ecef = np.atleast_2d(pt_ecef)
|
||||
ecef_from_device_rot = orient.rotations_from_quats(orientation_ecef)
|
||||
device_from_ecef_rot = ecef_from_device_rot.T
|
||||
pt_ecef_rel = pt_ecef - pos_ecef
|
||||
pt_device = np.einsum('jk,ik->ij', device_from_ecef_rot, pt_ecef_rel)
|
||||
return pt_device.reshape(input_shape)
|
||||
|
||||
|
||||
def img_from_device(pt_device):
|
||||
# img coordinates from pts in device frame
|
||||
# first transforms to view frame, then to img coords
|
||||
# accepts single pt or array of pts
|
||||
input_shape = pt_device.shape
|
||||
pt_device = np.atleast_2d(pt_device)
|
||||
pt_view = np.einsum('jk,ik->ij', view_frame_from_device_frame, pt_device)
|
||||
|
||||
# This function should never return negative depths
|
||||
pt_view[pt_view[:, 2] < 0] = np.nan
|
||||
|
||||
pt_img = pt_view/pt_view[:, 2:3]
|
||||
return pt_img.reshape(input_shape)[:, :2]
|
||||
|
||||
100
common/transformations/coordinates.cc
Normal file
100
common/transformations/coordinates.cc
Normal 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);
|
||||
}
|
||||
43
common/transformations/coordinates.hpp
Normal file
43
common/transformations/coordinates.hpp
Normal file
@@ -0,0 +1,43 @@
|
||||
#pragma once
|
||||
|
||||
#include <eigen3/Eigen/Dense>
|
||||
|
||||
#define DEG2RAD(x) ((x) * M_PI / 180.0)
|
||||
#define RAD2DEG(x) ((x) * 180.0 / M_PI)
|
||||
|
||||
struct ECEF {
|
||||
double x, y, z;
|
||||
Eigen::Vector3d to_vector(){
|
||||
return Eigen::Vector3d(x, y, z);
|
||||
}
|
||||
};
|
||||
|
||||
struct NED {
|
||||
double n, e, d;
|
||||
Eigen::Vector3d to_vector(){
|
||||
return Eigen::Vector3d(n, e, d);
|
||||
}
|
||||
};
|
||||
|
||||
struct Geodetic {
|
||||
double lat, lon, alt;
|
||||
bool radians=false;
|
||||
};
|
||||
|
||||
ECEF geodetic2ecef(Geodetic g);
|
||||
Geodetic ecef2geodetic(ECEF e);
|
||||
|
||||
class LocalCoord {
|
||||
public:
|
||||
Eigen::Matrix3d ned2ecef_matrix;
|
||||
Eigen::Matrix3d ecef2ned_matrix;
|
||||
Eigen::Vector3d init_ecef;
|
||||
LocalCoord(Geodetic g, ECEF e);
|
||||
LocalCoord(Geodetic g) : LocalCoord(g, ::geodetic2ecef(g)) {}
|
||||
LocalCoord(ECEF e) : LocalCoord(::ecef2geodetic(e), e) {}
|
||||
|
||||
NED ecef2ned(ECEF e);
|
||||
ECEF ned2ecef(NED n);
|
||||
NED geodetic2ned(Geodetic g);
|
||||
Geodetic ned2geodetic(NED n);
|
||||
};
|
||||
18
common/transformations/coordinates.py
Normal file
18
common/transformations/coordinates.py
Normal file
@@ -0,0 +1,18 @@
|
||||
from openpilot.common.transformations.orientation import numpy_wrap
|
||||
from openpilot.common.transformations.transformations import (ecef2geodetic_single,
|
||||
geodetic2ecef_single)
|
||||
from openpilot.common.transformations.transformations import LocalCoord as LocalCoord_single
|
||||
|
||||
|
||||
class LocalCoord(LocalCoord_single):
|
||||
ecef2ned = numpy_wrap(LocalCoord_single.ecef2ned_single, (3,), (3,))
|
||||
ned2ecef = numpy_wrap(LocalCoord_single.ned2ecef_single, (3,), (3,))
|
||||
geodetic2ned = numpy_wrap(LocalCoord_single.geodetic2ned_single, (3,), (3,))
|
||||
ned2geodetic = numpy_wrap(LocalCoord_single.ned2geodetic_single, (3,), (3,))
|
||||
|
||||
|
||||
geodetic2ecef = numpy_wrap(geodetic2ecef_single, (3,), (3,))
|
||||
ecef2geodetic = numpy_wrap(ecef2geodetic_single, (3,), (3,))
|
||||
|
||||
geodetic_from_ecef = ecef2geodetic
|
||||
ecef_from_geodetic = geodetic2ecef
|
||||
78
common/transformations/model.py
Normal file
78
common/transformations/model.py
Normal file
@@ -0,0 +1,78 @@
|
||||
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)
|
||||
|
||||
# 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)
|
||||
MEDMODEL_CY = 47.6
|
||||
|
||||
medmodel_fl = 910.0
|
||||
medmodel_intrinsics = np.array([
|
||||
[medmodel_fl, 0.0, 0.5 * MEDMODEL_INPUT_SIZE[0]],
|
||||
[0.0, medmodel_fl, MEDMODEL_CY],
|
||||
[0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
# BIG model
|
||||
BIGMODEL_INPUT_SIZE = (1024, 512)
|
||||
BIGMODEL_YUV_SIZE = (BIGMODEL_INPUT_SIZE[0], BIGMODEL_INPUT_SIZE[1] * 3 // 2)
|
||||
|
||||
bigmodel_fl = 910.0
|
||||
bigmodel_intrinsics = np.array([
|
||||
[bigmodel_fl, 0.0, 0.5 * BIGMODEL_INPUT_SIZE[0]],
|
||||
[0.0, bigmodel_fl, 256 + MEDMODEL_CY],
|
||||
[0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
# SBIG model (big model with the size of small model)
|
||||
SBIGMODEL_INPUT_SIZE = (512, 256)
|
||||
SBIGMODEL_YUV_SIZE = (SBIGMODEL_INPUT_SIZE[0], SBIGMODEL_INPUT_SIZE[1] * 3 // 2)
|
||||
|
||||
sbigmodel_fl = 455.0
|
||||
sbigmodel_intrinsics = np.array([
|
||||
[sbigmodel_fl, 0.0, 0.5 * SBIGMODEL_INPUT_SIZE[0]],
|
||||
[0.0, sbigmodel_fl, 0.5 * (256 + MEDMODEL_CY)],
|
||||
[0.0, 0.0, 1.0]])
|
||||
|
||||
bigmodel_frame_from_calib_frame = np.dot(bigmodel_intrinsics,
|
||||
get_view_frame_from_calib_frame(0, 0, 0, 0))
|
||||
|
||||
|
||||
sbigmodel_frame_from_calib_frame = np.dot(sbigmodel_intrinsics,
|
||||
get_view_frame_from_calib_frame(0, 0, 0, 0))
|
||||
|
||||
medmodel_frame_from_calib_frame = np.dot(medmodel_intrinsics,
|
||||
get_view_frame_from_calib_frame(0, 0, 0, 0))
|
||||
|
||||
medmodel_frame_from_bigmodel_frame = np.dot(medmodel_intrinsics, np.linalg.inv(bigmodel_intrinsics))
|
||||
|
||||
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
|
||||
|
||||
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
|
||||
warp_matrix: np.ndarray = camera_from_calib @ calib_from_model
|
||||
return warp_matrix
|
||||
144
common/transformations/orientation.cc
Normal file
144
common/transformations/orientation.cc
Normal 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};
|
||||
}
|
||||
|
||||
17
common/transformations/orientation.hpp
Normal file
17
common/transformations/orientation.hpp
Normal file
@@ -0,0 +1,17 @@
|
||||
#pragma once
|
||||
#include <eigen3/Eigen/Dense>
|
||||
#include "common/transformations/coordinates.hpp"
|
||||
|
||||
|
||||
Eigen::Quaterniond ensure_unique(Eigen::Quaterniond quat);
|
||||
|
||||
Eigen::Quaterniond euler2quat(Eigen::Vector3d euler);
|
||||
Eigen::Vector3d quat2euler(Eigen::Quaterniond quat);
|
||||
Eigen::Matrix3d quat2rot(Eigen::Quaterniond quat);
|
||||
Eigen::Quaterniond rot2quat(const Eigen::Matrix3d &rot);
|
||||
Eigen::Matrix3d euler2rot(Eigen::Vector3d euler);
|
||||
Eigen::Vector3d rot2euler(const Eigen::Matrix3d &rot);
|
||||
Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw);
|
||||
Eigen::Matrix3d rot(Eigen::Vector3d axis, double angle);
|
||||
Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose);
|
||||
Eigen::Vector3d ned_euler_from_ecef(ECEF ecef_init, Eigen::Vector3d ecef_pose);
|
||||
52
common/transformations/orientation.py
Normal file
52
common/transformations/orientation.py
Normal file
@@ -0,0 +1,52 @@
|
||||
import numpy as np
|
||||
from typing import Callable
|
||||
|
||||
from openpilot.common.transformations.transformations import (ecef_euler_from_ned_single,
|
||||
euler2quat_single,
|
||||
euler2rot_single,
|
||||
ned_euler_from_ecef_single,
|
||||
quat2euler_single,
|
||||
quat2rot_single,
|
||||
rot2euler_single,
|
||||
rot2quat_single)
|
||||
|
||||
|
||||
def numpy_wrap(function, input_shape, output_shape) -> Callable[..., np.ndarray]:
|
||||
"""Wrap a function to take either an input or list of inputs and return the correct shape"""
|
||||
def f(*inps):
|
||||
*args, inp = inps
|
||||
inp = np.array(inp)
|
||||
shape = inp.shape
|
||||
|
||||
if len(shape) == len(input_shape):
|
||||
out_shape = output_shape
|
||||
else:
|
||||
out_shape = (shape[0],) + output_shape
|
||||
|
||||
# Add empty dimension if inputs is not a list
|
||||
if len(shape) == len(input_shape):
|
||||
inp.shape = (1, ) + inp.shape
|
||||
|
||||
result = np.asarray([function(*args, i) for i in inp])
|
||||
result.shape = out_shape
|
||||
return result
|
||||
return f
|
||||
|
||||
|
||||
euler2quat = numpy_wrap(euler2quat_single, (3,), (4,))
|
||||
quat2euler = numpy_wrap(quat2euler_single, (4,), (3,))
|
||||
quat2rot = numpy_wrap(quat2rot_single, (4,), (3, 3))
|
||||
rot2quat = numpy_wrap(rot2quat_single, (3, 3), (4,))
|
||||
euler2rot = numpy_wrap(euler2rot_single, (3,), (3, 3))
|
||||
rot2euler = numpy_wrap(rot2euler_single, (3, 3), (3,))
|
||||
ecef_euler_from_ned = numpy_wrap(ecef_euler_from_ned_single, (3,), (3,))
|
||||
ned_euler_from_ecef = numpy_wrap(ned_euler_from_ecef_single, (3,), (3,))
|
||||
|
||||
quats_from_rotations = rot2quat
|
||||
quat_from_rot = rot2quat
|
||||
rotations_from_quats = quat2rot
|
||||
rot_from_quat = quat2rot
|
||||
euler_from_rot = rot2euler
|
||||
euler_from_quat = quat2euler
|
||||
rot_from_euler = euler2rot
|
||||
quat_from_euler = euler2quat
|
||||
72
common/transformations/transformations.pxd
Normal file
72
common/transformations/transformations.pxd
Normal file
@@ -0,0 +1,72 @@
|
||||
#cython: language_level=3
|
||||
from libcpp cimport bool
|
||||
|
||||
cdef extern from "orientation.cc":
|
||||
pass
|
||||
|
||||
cdef extern from "orientation.hpp":
|
||||
cdef cppclass Quaternion "Eigen::Quaterniond":
|
||||
Quaternion()
|
||||
Quaternion(double, double, double, double)
|
||||
double w()
|
||||
double x()
|
||||
double y()
|
||||
double z()
|
||||
|
||||
cdef cppclass Vector3 "Eigen::Vector3d":
|
||||
Vector3()
|
||||
Vector3(double, double, double)
|
||||
double operator()(int)
|
||||
|
||||
cdef cppclass Matrix3 "Eigen::Matrix3d":
|
||||
Matrix3()
|
||||
Matrix3(double*)
|
||||
|
||||
double operator()(int, int)
|
||||
|
||||
Quaternion euler2quat(Vector3)
|
||||
Vector3 quat2euler(Quaternion)
|
||||
Matrix3 quat2rot(Quaternion)
|
||||
Quaternion rot2quat(Matrix3)
|
||||
Vector3 rot2euler(Matrix3)
|
||||
Matrix3 euler2rot(Vector3)
|
||||
Matrix3 rot_matrix(double, double, double)
|
||||
Vector3 ecef_euler_from_ned(ECEF, Vector3)
|
||||
Vector3 ned_euler_from_ecef(ECEF, Vector3)
|
||||
|
||||
|
||||
cdef extern from "coordinates.cc":
|
||||
cdef struct ECEF:
|
||||
double x
|
||||
double y
|
||||
double z
|
||||
|
||||
cdef struct NED:
|
||||
double n
|
||||
double e
|
||||
double d
|
||||
|
||||
cdef struct Geodetic:
|
||||
double lat
|
||||
double lon
|
||||
double alt
|
||||
bool radians
|
||||
|
||||
ECEF geodetic2ecef(Geodetic)
|
||||
Geodetic ecef2geodetic(ECEF)
|
||||
|
||||
cdef cppclass LocalCoord_c "LocalCoord":
|
||||
Matrix3 ned2ecef_matrix
|
||||
Matrix3 ecef2ned_matrix
|
||||
|
||||
LocalCoord_c(Geodetic, ECEF)
|
||||
LocalCoord_c(Geodetic)
|
||||
LocalCoord_c(ECEF)
|
||||
|
||||
NED ecef2ned(ECEF)
|
||||
ECEF ned2ecef(NED)
|
||||
NED geodetic2ned(Geodetic)
|
||||
Geodetic ned2geodetic(NED)
|
||||
|
||||
cdef extern from "coordinates.hpp":
|
||||
pass
|
||||
174
common/transformations/transformations.pyx
Normal file
174
common/transformations/transformations.pyx
Normal file
@@ -0,0 +1,174 @@
|
||||
# distutils: language = c++
|
||||
# cython: language_level = 3
|
||||
from openpilot.common.transformations.transformations cimport Matrix3, Vector3, Quaternion
|
||||
from openpilot.common.transformations.transformations cimport ECEF, NED, Geodetic
|
||||
|
||||
from openpilot.common.transformations.transformations cimport euler2quat as euler2quat_c
|
||||
from openpilot.common.transformations.transformations cimport quat2euler as quat2euler_c
|
||||
from openpilot.common.transformations.transformations cimport quat2rot as quat2rot_c
|
||||
from openpilot.common.transformations.transformations cimport rot2quat as rot2quat_c
|
||||
from openpilot.common.transformations.transformations cimport euler2rot as euler2rot_c
|
||||
from openpilot.common.transformations.transformations cimport rot2euler as rot2euler_c
|
||||
from openpilot.common.transformations.transformations cimport rot_matrix as rot_matrix_c
|
||||
from openpilot.common.transformations.transformations cimport ecef_euler_from_ned as ecef_euler_from_ned_c
|
||||
from openpilot.common.transformations.transformations cimport ned_euler_from_ecef as ned_euler_from_ecef_c
|
||||
from openpilot.common.transformations.transformations cimport geodetic2ecef as geodetic2ecef_c
|
||||
from openpilot.common.transformations.transformations cimport ecef2geodetic as ecef2geodetic_c
|
||||
from openpilot.common.transformations.transformations cimport LocalCoord_c
|
||||
|
||||
|
||||
import cython
|
||||
import numpy as np
|
||||
cimport numpy as np
|
||||
|
||||
cdef np.ndarray[double, ndim=2] matrix2numpy(Matrix3 m):
|
||||
return np.array([
|
||||
[m(0, 0), m(0, 1), m(0, 2)],
|
||||
[m(1, 0), m(1, 1), m(1, 2)],
|
||||
[m(2, 0), m(2, 1), m(2, 2)],
|
||||
])
|
||||
|
||||
cdef Matrix3 numpy2matrix(np.ndarray[double, ndim=2, mode="fortran"] m):
|
||||
assert m.shape[0] == 3
|
||||
assert m.shape[1] == 3
|
||||
return Matrix3(<double*>m.data)
|
||||
|
||||
cdef ECEF list2ecef(ecef):
|
||||
cdef ECEF e;
|
||||
e.x = ecef[0]
|
||||
e.y = ecef[1]
|
||||
e.z = ecef[2]
|
||||
return e
|
||||
|
||||
cdef NED list2ned(ned):
|
||||
cdef NED n;
|
||||
n.n = ned[0]
|
||||
n.e = ned[1]
|
||||
n.d = ned[2]
|
||||
return n
|
||||
|
||||
cdef Geodetic list2geodetic(geodetic):
|
||||
cdef Geodetic g
|
||||
g.lat = geodetic[0]
|
||||
g.lon = geodetic[1]
|
||||
g.alt = geodetic[2]
|
||||
return g
|
||||
|
||||
def euler2quat_single(euler):
|
||||
cdef Vector3 e = Vector3(euler[0], euler[1], euler[2])
|
||||
cdef Quaternion q = euler2quat_c(e)
|
||||
return [q.w(), q.x(), q.y(), q.z()]
|
||||
|
||||
def quat2euler_single(quat):
|
||||
cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3])
|
||||
cdef Vector3 e = quat2euler_c(q);
|
||||
return [e(0), e(1), e(2)]
|
||||
|
||||
def quat2rot_single(quat):
|
||||
cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3])
|
||||
cdef Matrix3 r = quat2rot_c(q)
|
||||
return matrix2numpy(r)
|
||||
|
||||
def rot2quat_single(rot):
|
||||
cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double))
|
||||
cdef Quaternion q = rot2quat_c(r)
|
||||
return [q.w(), q.x(), q.y(), q.z()]
|
||||
|
||||
def euler2rot_single(euler):
|
||||
cdef Vector3 e = Vector3(euler[0], euler[1], euler[2])
|
||||
cdef Matrix3 r = euler2rot_c(e)
|
||||
return matrix2numpy(r)
|
||||
|
||||
def rot2euler_single(rot):
|
||||
cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double))
|
||||
cdef Vector3 e = rot2euler_c(r)
|
||||
return [e(0), e(1), e(2)]
|
||||
|
||||
def rot_matrix(roll, pitch, yaw):
|
||||
return matrix2numpy(rot_matrix_c(roll, pitch, yaw))
|
||||
|
||||
def ecef_euler_from_ned_single(ecef_init, ned_pose):
|
||||
cdef ECEF init = list2ecef(ecef_init)
|
||||
cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2])
|
||||
|
||||
cdef Vector3 e = ecef_euler_from_ned_c(init, pose)
|
||||
return [e(0), e(1), e(2)]
|
||||
|
||||
def ned_euler_from_ecef_single(ecef_init, ecef_pose):
|
||||
cdef ECEF init = list2ecef(ecef_init)
|
||||
cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2])
|
||||
|
||||
cdef Vector3 e = ned_euler_from_ecef_c(init, pose)
|
||||
return [e(0), e(1), e(2)]
|
||||
|
||||
def geodetic2ecef_single(geodetic):
|
||||
cdef Geodetic g = list2geodetic(geodetic)
|
||||
cdef ECEF e = geodetic2ecef_c(g)
|
||||
return [e.x, e.y, e.z]
|
||||
|
||||
def ecef2geodetic_single(ecef):
|
||||
cdef ECEF e = list2ecef(ecef)
|
||||
cdef Geodetic g = ecef2geodetic_c(e)
|
||||
return [g.lat, g.lon, g.alt]
|
||||
|
||||
|
||||
cdef class LocalCoord:
|
||||
cdef LocalCoord_c * lc
|
||||
|
||||
def __init__(self, geodetic=None, ecef=None):
|
||||
assert (geodetic is not None) or (ecef is not None)
|
||||
if geodetic is not None:
|
||||
self.lc = new LocalCoord_c(list2geodetic(geodetic))
|
||||
elif ecef is not None:
|
||||
self.lc = new LocalCoord_c(list2ecef(ecef))
|
||||
|
||||
@property
|
||||
def ned2ecef_matrix(self):
|
||||
return matrix2numpy(self.lc.ned2ecef_matrix)
|
||||
|
||||
@property
|
||||
def ecef2ned_matrix(self):
|
||||
return matrix2numpy(self.lc.ecef2ned_matrix)
|
||||
|
||||
@property
|
||||
def ned_from_ecef_matrix(self):
|
||||
return self.ecef2ned_matrix
|
||||
|
||||
@property
|
||||
def ecef_from_ned_matrix(self):
|
||||
return self.ned2ecef_matrix
|
||||
|
||||
@classmethod
|
||||
def from_geodetic(cls, geodetic):
|
||||
return cls(geodetic=geodetic)
|
||||
|
||||
@classmethod
|
||||
def from_ecef(cls, ecef):
|
||||
return cls(ecef=ecef)
|
||||
|
||||
def ecef2ned_single(self, ecef):
|
||||
assert self.lc
|
||||
cdef ECEF e = list2ecef(ecef)
|
||||
cdef NED n = self.lc.ecef2ned(e)
|
||||
return [n.n, n.e, n.d]
|
||||
|
||||
def ned2ecef_single(self, ned):
|
||||
assert self.lc
|
||||
cdef NED n = list2ned(ned)
|
||||
cdef ECEF e = self.lc.ned2ecef(n)
|
||||
return [e.x, e.y, e.z]
|
||||
|
||||
def geodetic2ned_single(self, geodetic):
|
||||
assert self.lc
|
||||
cdef Geodetic g = list2geodetic(geodetic)
|
||||
cdef NED n = self.lc.geodetic2ned(g)
|
||||
return [n.n, n.e, n.d]
|
||||
|
||||
def ned2geodetic_single(self, ned):
|
||||
assert self.lc
|
||||
cdef NED n = list2ned(ned)
|
||||
cdef Geodetic g = self.lc.ned2geodetic(n)
|
||||
return [g.lat, g.lon, g.alt]
|
||||
|
||||
def __dealloc__(self):
|
||||
del self.lc
|
||||
Reference in New Issue
Block a user