From 17a7660a5ff6899e29362faf772e88d6f5cd95dc Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Sun, 9 Feb 2025 19:47:52 +0100 Subject: [PATCH 01/30] feat: added the math and setup of the ESKF, need some changes --- navigation/eskf_python/CMakeLists.txt | 33 ++ navigation/eskf_python/README.md | 0 .../eskf_python/config/eskf_python.yaml | 3 + .../eskf_python/eskf_python/__init__.py | 0 .../eskf_python/eskf_python_filter.py | 511 ++++++++++++++++++ .../eskf_python/eskf_python_node.py | 103 ++++ navigation/eskf_python/launch/eskf.launch.py | 22 + navigation/eskf_python/package.xml | 23 + 8 files changed, 695 insertions(+) create mode 100644 navigation/eskf_python/CMakeLists.txt create mode 100644 navigation/eskf_python/README.md create mode 100644 navigation/eskf_python/config/eskf_python.yaml create mode 100644 navigation/eskf_python/eskf_python/__init__.py create mode 100644 navigation/eskf_python/eskf_python/eskf_python_filter.py create mode 100644 navigation/eskf_python/eskf_python/eskf_python_node.py create mode 100644 navigation/eskf_python/launch/eskf.launch.py create mode 100644 navigation/eskf_python/package.xml diff --git a/navigation/eskf_python/CMakeLists.txt b/navigation/eskf_python/CMakeLists.txt new file mode 100644 index 000000000..b4fc9118c --- /dev/null +++ b/navigation/eskf_python/CMakeLists.txt @@ -0,0 +1,33 @@ +cmake_minimum_required(VERSION 3.8) +project(eskf_python) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake_python REQUIRED) +find_package(rclpy REQUIRED) +find_package(vortex_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) + +ament_python_install_package(${PROJECT_NAME}) + +install(DIRECTORY + launch + config + DESTINATION share/${PROJECT_NAME} +) + +install(PROGRAMS + eskf_python/eskf_python_node.py + DESTINATION lib/${PROJECT_NAME} +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + find_package(ament_cmake_pytest REQUIRED) + set(ament_cmake_copyright_FOUND TRUE) + set(ament_cmake_cpplint_FOUND TRUE) +endif() + +ament_package() diff --git a/navigation/eskf_python/README.md b/navigation/eskf_python/README.md new file mode 100644 index 000000000..e69de29bb diff --git a/navigation/eskf_python/config/eskf_python.yaml b/navigation/eskf_python/config/eskf_python.yaml new file mode 100644 index 000000000..0d80b90df --- /dev/null +++ b/navigation/eskf_python/config/eskf_python.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + eskf_python_node: diff --git a/navigation/eskf_python/eskf_python/__init__.py b/navigation/eskf_python/eskf_python/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/navigation/eskf_python/eskf_python/eskf_python_filter.py b/navigation/eskf_python/eskf_python/eskf_python_filter.py new file mode 100644 index 000000000..286747467 --- /dev/null +++ b/navigation/eskf_python/eskf_python/eskf_python_filter.py @@ -0,0 +1,511 @@ +from dataclasses import dataclass, field +from typing import tuple + +import numpy as np + + +@dataclass +class StateVector_quaternion: + position: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Position vector (x, y, z) + velocity: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Velocity vector (u, v, w) + orientation: np.ndarray = field( + default_factory=lambda: np.zeros(4) + ) # Orientation quaternion (w, x, y, z) + acceleration_bias: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Acceleration bias vector (b_ax, b_ay, b_az) + gyro_bias: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Gyro bias vector (b_gx, b_gy, b_gz) + + def R_q(self) -> np.ndarray: + """Calculates the rotation matrix from the orientation quaternion. + + Returns: + np.ndarray: The rotation matrix. + """ + q0, q1, q2, q3 = self.orientation + R = np.array( + [ + [ + 1 - 2 * q2**2 - 2 * q3**2, + 2 * (q1 * q2 - q0 * q3), + 2 * (q0 * q2 + q1 * q3), + ], + [ + 2 * (q1 * q2 + q0 * q3), + 1 - 2 * q1**2 - 2 * q3**2, + 2 * (q2 * q3 - q0 * q1), + ], + [ + 2 * (q1 * q3 - q0 * q2), + 2 * (q0 * q1 + q2 * q3), + 1 - 2 * q1**2 - 2 * q2**2, + ], + ] + ) + + return R + + def euler_forward( + self, current_state: 'StateVector_quaternion', dt: float + ) -> 'StateVector_quaternion': + # Define the new state + new_state = StateVector_quaternion() + + # Define the state derivatives + new_state.position = current_state.position + self.position * dt + new_state.velocity = current_state.velocity + self.velocity * dt + new_state.orientation = current_state.orientation + self.orientation * dt + new_state.acceleration_bias = ( + current_state.acceleration_bias + self.acceleration_bias * dt + ) + new_state.gyro_bias = current_state.gyro_bias + self.gyro_bias * dt + + # Normalize the orientation quaternion + new_state.orientation /= np.linalg.norm(new_state.orientation) + + return new_state + + +@dataclass +class StateVector_euler: + position: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Position vector (x, y, z) + velocity: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Velocity vector (u, v, w) + orientation: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Orientation angles (roll, pitch, yaw) + acceleration_bias: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Acceleration bias vector (b_ax, b_ay, b_az) + gyro_bias: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Gyro bias vector (b_gx, b_gy, b_gz) + covariance: np.ndarray = field( + default_factory=lambda: np.zeros((15, 15)) + ) # Covariance matrix + + def fill_states(self, state: np.ndarray) -> None: + """Fills the state vector with the values from a numpy array. + + Args: + state (np.ndarray): The state vector. + """ + self.position = state[0:3] + self.velocity = state[3:6] + self.orientation = state[6:9] + self.acceleration_bias = state[9:12] + self.gyro_bias = state[12:15] + + def copy_state(self, wanted_state: 'StateVector_euler') -> None: + """Copies the state from a StateVector object into the current StateVector object. + + Args: + wanted_state (StateVector_euler): The quaternion state to copy from. + """ + self.position = wanted_state.position + self.velocity = wanted_state.velocity + self.orientation = wanted_state.orientation + self.acceleration_bias = wanted_state.acceleration_bias + self.gyro_bias = wanted_state.gyro_bias + + +@dataclass +class MeasurementModel: + measurement: np.ndarray = field( + default_factory=lambda: np.zeros(6) + ) # Measurement vector + measurement_matrix: np.ndarray = field( + default_factory=lambda: np.zeros((6, 15)) + ) # Measurement matrix + measurement_covariance: np.ndarray = field( + default_factory=lambda: np.zeros((6, 6)) + ) # Measurement noise matrix + + +class ErrorStateKalmanFilter: + def __init__( + self, + P_ab: np.ndarray, + P_wb: np.ndarray, + Q: np.ndarray, + lever_arm: np.array, + R: np.ndarray, + g: float, + dt: float, + ) -> None: + self.P_ab = P_ab + self.P_wb = P_wb + self.Q_process_noise = Q + self.lever_arm = lever_arm + self.R = R + self.g = np.array([0, 0, g]) + self.dt = dt + + def skew_symmetric(self, vector: np.ndarray) -> np.ndarray: + """Calculates the skew symmetric matrix of a vector. + + Args: + vector (np.ndarray): The vector. + + Returns: + np.ndarray: The skew symmetric matrix. + """ + return np.array( + [ + [0, -vector[2], vector[1]], + [vector[2], 0, -vector[0]], + [-vector[1], vector[0], 0], + ] + ) + + def quaternion_super_product(self, q1: np.ndarray, q2: np.ndarray) -> np.ndarray: + """Calculates the quaternion super product of two quaternions. + + Args: + q1 (np.ndarray): The first quaternion. + q2 (np.ndarray): The second quaternion. + + Returns: + np.ndarray: The quaternion super product. + """ + nu_0, eta_0_x, eta_0_y, eta_0_z = q1 + nu_1, eta_1_x, eta_1_y, eta_1_z = q2 + + eta_0 = np.array([[eta_1_x, eta_1_y, eta_1_z]]).T + eta_1 = np.array([[eta_0_x, eta_0_y, eta_0_z]]).T + + eta_new = ( + nu_1 * eta_0 + nu_0 * eta_1 + np.dot(self.skew_symmetric(eta_0), eta_1) + ) + nu_new = nu_0 * nu_1 - np.dot(eta_0.T, eta_1) + + q_new = np.array([nu_new, eta_new[0], eta_new[1], eta_new[2]]) + q_new /= np.linalg.norm(q_new) + + return q_new + + def van_loan_discretization( + self, A_c: np.ndarray, G_c: np.ndarray + ) -> tuple[np.ndarray, np.ndarray]: + """Calculates the Van Loan discretization of a continuous-time system. + + Args: + A_c (np.ndarray): The A matrix. + G_c (np.ndarray): The G matrix. + + Returns: + tuple: The A_d and GQG_d matrices. + """ + GQG_T = np.dot(np.dot(G_c, self.Q_process_noise), G_c.T) * self.dt + + matrix_exp = ( + np.block([[A_c, GQG_T], [np.zeros((A_c.shape[0], A_c.shape[0])), A_c.T]]) + * self.dt + ) + + van_loan_matrix = np.linalg.expm(matrix_exp) + + V1 = van_loan_matrix[A_c.shape[0] :, A_c.shape[0] :] + V2 = van_loan_matrix[: A_c.shape[0], A_c.shape[0] :] + + A_d = V1.T + GQG_d = A_d @ V2 + + return A_d, GQG_d + + def nominal_state_update( + self, current_state: StateVector_quaternion, imu_reading: np.ndarray + ) -> StateVector_quaternion: + """Updates the nominal state of the system. + + Args: + current_state (np.ndarray): The current state of the system. + imu_reading (np.ndarray): The IMU reading. + + Returns: + np.ndarray: The updated nominal state. + """ + # Defining the IMU readings + imu_acceleration = imu_reading[0:3] + imu_gyro = imu_reading[3:6] + + # Define the derivative of the state + current_state_dot = StateVector_quaternion() + + # Define the state derivates + current_state_dot.position = current_state.velocity + current_state_dot.velocity = ( + np.dot( + current_state.R_q(), + (imu_acceleration - current_state.acceleration_bias), + ) + + self.g + ) + + # Define the quaternion derivatives + current_state_dot.orientation = 0.5 * self.quaternion_super_product( + current_state.orientation, + np.array([0, imu_gyro[0], imu_gyro[1], imu_gyro[2]]), + ) + + # Define the bias + current_state_dot.acceleration_bias = ( + -np.dot(self.P_ab, np.eye(3)) @ current_state.acceleration_bias + ) + current_state_dot.gyro_bias = ( + -np.dot(self.P_wb, np.eye(3)) @ current_state.gyro_bias + ) + + return current_state_dot.euler_forward(current_state, self.dt) + + def error_state_update( + self, + current_error_state: StateVector_euler, + current_state: StateVector_quaternion, + imu_reading: np.ndarray, + ) -> StateVector_euler: + """Updates the error state of the system. + + Args: + current_error_state (np.ndarray): The current error state of the system. + current_state (np.ndarray): The current state of the system. + imu_reading (np.ndarray): The IMU reading. + + Returns: + np.ndarray: The updated error state. + """ + # Define the derivative of the state + next_error_state = StateVector_euler() + + # Defining the IMU readings + imu_acceleration = imu_reading[0:3] + imu_gyro = imu_reading[3:6] + + A_c = np.zeros((15, 15)) + A_c[0:3, 3:6] = np.eye(3) + A_c[3:6, 6:9] = -np.dot( + current_state.R_q(), + self.skew_symmetric(imu_acceleration - current_state.acceleration_bias), + ) + A_c[6:9, 6:9] = -self.skew_symmetric(imu_gyro - current_state.gyro_bias) + A_c[3:6, 9:12] = -current_state.R_q() + A_c[6:9, 12:15] = -np.eye(3) + A_c[9:12, 9:12] = -self.P_ab * np.eye(3) + A_c[12:15, 12:15] = -self.P_wb * np.eye(3) + + G_c = np.zeros((15, 12)) + G_c[3:6, 0:3] = -current_state.R_q() + G_c[6:9, 3:6] = -np.eye(3) + G_c[9:12, 6:9] = np.eye(3) + G_c[12:15, 9:12] = np.eye(3) + + # Van loan discretization + A_d, GQG_d = self.van_loan_discretization(A_c, G_c, self.dt) + + # Inserting the new state and covariance + next_error_state.copy_state(current_error_state) + next_error_state.covariance = ( + np.dot(np.dot(A_d, current_error_state.covariance), A_d.T) + GQG_d + ) + + return next_error_state + + def H(self) -> np.ndarray: + """Calculates the measurement matrix. + + Returns: + np.ndarray: The measurement matrix. + """ + # Define the measurement matrix + H = np.zeros((3, 15)) + + # For now assume only velocity is measured + H[0:3, 3:6] = np.eye(3) + + return H + + def prediction_from_estimates( + self, + current_state: StateVector_quaternion, + current_error_state: StateVector_euler, + imu_reading: np.ndarray, + ) -> StateVector_euler: + """Predicts the measurement from the current state and error state. + + Args: + current_state (StateVector_quaternion): The current state of the system. + current_error_state (StateVector_euler): The current error state of the system. + imu_reading (np.ndarray): The IMU reading. + + Returns: + StateVector_euler: The predicted measurement. + """ + # Define the z_pred matrix + z_pred = MeasurementModel() + + # Define the z_pred values separately + z_pred_1 = np.hstack((current_state.position, current_state.velocity)) + z_pred_2 = np.hstack( + np.dot(current_state.R_q(), self.lever_arm), + np.dot( + current_state.R_q, + np.dot( + self.skew_symmetric(current_state.angular_velocity), self.lever_arm + ), + ), + ) + + # Combine the z_pred values + z_pred.measurement = z_pred_1 + z_pred_2 + + # Define the H matrix + z_pred.measurement_matrix = self.H() + R = self.R + z_pred.measurement_covariance = ( + np.dot( + np.dot(z_pred.measurement_matrix, current_error_state.covariance), + z_pred.measurement_matrix.T, + ) + + R + ) + + return z_pred + + def measurement_update( + self, + error_state_pred: StateVector_euler, + z_pred: MeasurementModel, + dvl_measure: np.array, + ) -> StateVector_euler: + """Updates the error state of the system. + + Args: + current_error_state (np.ndarray): The current error state of the system. + measurement (np.ndarray): The measurement. + + Returns: + np.ndarray: The updated error state. + """ + # Define new error state value + new_error_state = StateVector_euler() + + # Define the measurement matrix + innovation = dvl_measure - z_pred.measurement + H = z_pred.measurement_matrix + R = self.R + P = error_state_pred.covariance + S = z_pred.measurement_covariance + + # Kalman gain calculation + W = np.dot(P, np.linalg.solve(S, H).T) + new_error_state.fill_states(np.dot(W, innovation)) + + I_WH = np.eye(15) - np.dot(W, H) + new_error_state.covariance = np.dot(np.dot(I_WH, P), I_WH.T) + np.dot( + np.dot(W, R), W.T + ) + + return new_error_state + + def imu_update_states( + self, + current_pred_nom: StateVector_quaternion, + current_pred_err: StateVector_euler, + imu_readings: np.array, + ) -> tuple[StateVector_quaternion, StateVector_euler]: + """Calculates the predicted state using the IMU readings. + + Args: + current_pred_nom (StateVector_quaternion): The current nominal state. + current_pred_err (StateVector_euler): The current error state. + imu_readings (np.array): The IMU readings. + + Returns: + tuple: The predicted nominal state and the predicted error state. + """ + pred_nom_state = self.nominal_state_update(current_pred_nom, imu_readings) + pred_err_state = self.error_state_update( + current_pred_err, current_pred_nom, imu_readings + ) + + return pred_nom_state, pred_err_state + + def dvl_update_states( + self, + current_pred_nom: StateVector_quaternion, + current_pred_err: StateVector_euler, + dvl_measure: np.array, + ) -> tuple[StateVector_quaternion, StateVector_euler]: + """Calculates the predicted state using the DVL readings. + + Args: + current_pred_nom (StateVector_quaternion): The current nominal state. + current_pred_err (StateVector_euler): The current error state. + dvl_measure (np.array): The DVL readings. + + Returns: + tuple: The predicted nominal state and the predicted error state. + """ + z_pred = self.prediction_from_estimates( + current_pred_nom, current_pred_err, dvl_measure + ) + new_error_state = self.measurement_update(current_pred_err, z_pred, dvl_measure) + + return current_pred_nom, new_error_state + + def injection_and_reset( + self, next_state: StateVector_quaternion, next_error_state: StateVector_euler + ) -> tuple[StateVector_quaternion, StateVector_euler]: + """Injects the error state into the nominal state and resets the error state. + + Args: + next_state (StateVector_quaternion): The next nominal state. + next_error_state (StateVector_euler): The next error state. + + Returns: + tuple: The injected nominal state and the reset error state. + """ + # Define the new state + inj_state = StateVector_quaternion() + + # Injecting the error state + inj_state.position = next_state.position + next_error_state.position + inj_state.velocity = next_state.velocity + next_error_state.velocity + inj_state.orientation = self.quaternion_super_product( + next_state.orientation, + 0.5 + * np.array( + [ + 2, + next_error_state.orientation[0], + next_error_state.orientation[1], + next_error_state.orientation[2], + ] + ), + ) + inj_state.acceleration_bias = ( + next_state.acceleration_bias + next_error_state.acceleration_bias + ) + inj_state.gyro_bias = next_state.gyro_bias + next_error_state.gyro_bias + + # Resetting the error state + G = np.eye(15) + G[6:9, 6:9] = np.eye(3) - self.skew_symmetric( + 0.5 * next_error_state.orientation + ) + + next_error_state.covariance = np.dot( + np.dot(G, next_error_state.covariance), G.T + ) + next_error_state.fill_states(np.zeros(15)) + + return inj_state, next_error_state diff --git a/navigation/eskf_python/eskf_python/eskf_python_node.py b/navigation/eskf_python/eskf_python/eskf_python_node.py new file mode 100644 index 000000000..25e5b6ca9 --- /dev/null +++ b/navigation/eskf_python/eskf_python/eskf_python_node.py @@ -0,0 +1,103 @@ +#!/usr/bin/env python3 + +import rclpy +from nav_msgs.msg import Odometry +from rclpy.node import Node +from rclpy.qos import QoSProfile, qos_profile_sensor_data + +# NEED TO CHANGE THIS TO THE CORRECT PATH +from eskf_python.eskf_python_filter import ( + ErrorStateKalmanFilter, + MeasurementModel, + StateVector_euler, + StateVector_quaternion, +) + +qos_profile = QoSProfile( + depth=1, + history=qos_profile_sensor_data.history, + reliability=qos_profile_sensor_data.reliability, +) + + +class ESKalmanFilterNode(Node): + def __init__(self): + super().__init__("eskf_python_node") + + # This callback will supply information from the IMU (Inertial Measurement Unit) 1000 Hz + # TEMPORARILY ADDED FOR TESTING + self.imu_subscriber_ = self.create_subscription( + Odometry, '/orca/imu', self.state_callback, qos_profile=qos_profile + ) + + # This publisher will publish the estimtaed state of the vehicle + self.state_publisher_ = self.create_publisher( + Odometry, '/orca/odom', qos_profile=qos_profile + ) + + self.eskf_modual = ErrorStateKalmanFilter() + self.current_state_nom = StateVector_quaternion() + self.current_state_error = StateVector_euler() + self.measurement_pred = MeasurementModel() + + self.get_logger().info("hybridpath_controller_node started") + + def imu_callback(self, msg: Odometry): + self.get_logger().info(f"Received IMU message: {msg}") + + # Get the IMU data + + # SOME CONVERSION HERE TO SUITABLE TYPE + imu_data = "something" + + # Update the filter with the IMU data + self.current_state_nom, self.current_state_error = ( + ErrorStateKalmanFilter.imu_update_states( + self.current_state_nom, self.current_state_error, imu_data + ) + ) + + # Publish the estimated state + """ + Some conversion function from the custom state type to odometry message + This needs to be worked on + """ + + def filter_callback(self): + """Callback function for the filter measurement update, + this will be called when the filter needs to be updated with the DVL data. + """ + self.get_logger().info("Filter callback, got DVL data") + + # Get the DVL data + dvl_data = "something" + + # Update the filter with the DVL data + self.current_state_nom, self.current_state_error = ( + ErrorStateKalmanFilter.dvl_update_states( + self.current_state_nom, self.current_state_error, dvl_data + ) + ) + self.current_state_nom, self.current_state_error = ( + ErrorStateKalmanFilter.injection_and_reset( + self.current_state_nom, self.current_state_error + ) + ) + + # Publish the estimated state + """ + Some conversion function from the custom state type to odometry message + This needs to be worked on + """ + + +def main(args=None): + rclpy.init(args=args) + node = ESKalmanFilterNode() + rclpy.spin(node) + node.destroy_node() + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/navigation/eskf_python/launch/eskf.launch.py b/navigation/eskf_python/launch/eskf.launch.py new file mode 100644 index 000000000..3cae83dce --- /dev/null +++ b/navigation/eskf_python/launch/eskf.launch.py @@ -0,0 +1,22 @@ +import os + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch_ros.actions import Node + + +def generate_launch_description(): + eskf_python_node = Node( + package='eskf_python', + executable='eskf_python_node.py', + name='eskf_python_node', + parameters=[ + os.path.join( + get_package_share_directory('eskf_python'), + 'config', + 'eskf_python.yaml', + ), + ], + output='screen', + ) + return LaunchDescription([eskf_python_node]) diff --git a/navigation/eskf_python/package.xml b/navigation/eskf_python/package.xml new file mode 100644 index 000000000..980653c40 --- /dev/null +++ b/navigation/eskf_python/package.xml @@ -0,0 +1,23 @@ + + + + eskf_python + 1.0.0 + This package provides the implementation of a error-state kalman filter in python + talhanc + MIT + + ament_cmake_python + + rclpy + python-transforms3d-pip + geometry_msgs + vortex_msgs + + python3-pytest + + + + ament_cmake + + From dff90b70400a3709533f639795d62dbc55182156 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Mon, 10 Feb 2025 14:28:18 +0100 Subject: [PATCH 02/30] feat: added in the IMU msg and DVL msg, pluss ros2 setup --- .../eskf_python/eskf_python_filter.py | 12 +-- .../eskf_python/eskf_python_node.py | 74 ++++++++++++++----- 2 files changed, 56 insertions(+), 30 deletions(-) diff --git a/navigation/eskf_python/eskf_python/eskf_python_filter.py b/navigation/eskf_python/eskf_python/eskf_python_filter.py index 286747467..392c705c2 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_filter.py +++ b/navigation/eskf_python/eskf_python/eskf_python_filter.py @@ -353,16 +353,8 @@ def prediction_from_estimates( z_pred = MeasurementModel() # Define the z_pred values separately - z_pred_1 = np.hstack((current_state.position, current_state.velocity)) - z_pred_2 = np.hstack( - np.dot(current_state.R_q(), self.lever_arm), - np.dot( - current_state.R_q, - np.dot( - self.skew_symmetric(current_state.angular_velocity), self.lever_arm - ), - ), - ) + z_pred_1 = current_state.velocity + z_pred_2 = 0 # Currently assuming no lever arm compensation # Combine the z_pred values z_pred.measurement = z_pred_1 + z_pred_2 diff --git a/navigation/eskf_python/eskf_python/eskf_python_node.py b/navigation/eskf_python/eskf_python/eskf_python_node.py index 25e5b6ca9..5b860582e 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_node.py +++ b/navigation/eskf_python/eskf_python/eskf_python_node.py @@ -4,6 +4,9 @@ from nav_msgs.msg import Odometry from rclpy.node import Node from rclpy.qos import QoSProfile, qos_profile_sensor_data +from sensor_msgs.msg import Imu, +import numpy as np +from geometry_msgs.msg import TwistWithCovarianceStamped # NEED TO CHANGE THIS TO THE CORRECT PATH from eskf_python.eskf_python_filter import ( @@ -25,9 +28,12 @@ def __init__(self): super().__init__("eskf_python_node") # This callback will supply information from the IMU (Inertial Measurement Unit) 1000 Hz - # TEMPORARILY ADDED FOR TESTING self.imu_subscriber_ = self.create_subscription( - Odometry, '/orca/imu', self.state_callback, qos_profile=qos_profile + Imu, '/orca/imu', self.imu_callback, qos_profile=qos_profile + ) + + self.twist_dvl_subscriber_ = self.create_subscription( + TwistWithCovarianceStamped, '/dvl/twist', self.filter_callback, qos_profile=qos_profile ) # This publisher will publish the estimtaed state of the vehicle @@ -39,16 +45,19 @@ def __init__(self): self.current_state_nom = StateVector_quaternion() self.current_state_error = StateVector_euler() self.measurement_pred = MeasurementModel() + self.odom_msg = Odometry() - self.get_logger().info("hybridpath_controller_node started") + self.get_logger().info("Error State Kalman Filter started") - def imu_callback(self, msg: Odometry): - self.get_logger().info(f"Received IMU message: {msg}") + def imu_callback(self, msg: Imu): # Get the IMU data - # SOME CONVERSION HERE TO SUITABLE TYPE - imu_data = "something" + imu_acceleartion = msg.linear_acceleration + imu_angular_velocity = msg.angular_velocity + + # Combine the IMU data + imu_data = np.array([imu_acceleartion.x, imu_acceleartion.y, imu_acceleartion.z, imu_angular_velocity.x, imu_angular_velocity.y, imu_angular_velocity.z]) # Update the filter with the IMU data self.current_state_nom, self.current_state_error = ( @@ -57,20 +66,34 @@ def imu_callback(self, msg: Odometry): ) ) - # Publish the estimated state - """ - Some conversion function from the custom state type to odometry message - This needs to be worked on - """ + # Inserting the nominal state into the msg + self.odom_msg.pose.pose.position.x = self.current_state_nom.position[0] + self.odom_msg.pose.pose.position.y = self.current_state_nom.position[1] + self.odom_msg.pose.pose.position.z = self.current_state_nom.position[2] + self.odom_msg.pose.pose.orientation.x = self.current_state_nom.orientation[0] + self.odom_msg.pose.pose.orientation.y = self.current_state_nom.orientation[1] + self.odom_msg.pose.pose.orientation.z = self.current_state_nom.orientation[2] + self.odom_msg.pose.pose.orientation.w = self.current_state_nom.orientation[3] + self.odom_msg.twist.twist.linear.x = self.current_state_nom.velocity[0] + self.odom_msg.twist.twist.linear.y = self.current_state_nom.velocity[1] + self.odom_msg.twist.twist.linear.z = self.current_state_nom.velocity[2] + self.odom_msg.twist.twist.angular.x = imu_angular_velocity.x + self.odom_msg.twist.twist.angular.y = imu_angular_velocity.y + self.odom_msg.twist.twist.angular.z = imu_angular_velocity.z + + # Publish + self.state_publisher_.publish(self.odom_msg) - def filter_callback(self): + + + def filter_callback(self, msg: TwistWithCovarianceStamped): """Callback function for the filter measurement update, this will be called when the filter needs to be updated with the DVL data. """ self.get_logger().info("Filter callback, got DVL data") - # Get the DVL data - dvl_data = "something" + # Get the DVL data (linear velocity) + dvl_data = np.array([msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z]) # Update the filter with the DVL data self.current_state_nom, self.current_state_error = ( @@ -84,11 +107,22 @@ def filter_callback(self): ) ) - # Publish the estimated state - """ - Some conversion function from the custom state type to odometry message - This needs to be worked on - """ + # Inserting data into the msg + self.odom_msg.pose.pose.position.x = self.current_state_nom.position[0] + self.odom_msg.pose.pose.position.y = self.current_state_nom.position[1] + self.odom_msg.pose.pose.position.z = self.current_state_nom.position[2] + self.odom_msg.pose.pose.orientation.x = self.current_state_nom.orientation[0] + self.odom_msg.pose.pose.orientation.y = self.current_state_nom.orientation[1] + self.odom_msg.pose.pose.orientation.z = self.current_state_nom.orientation[2] + self.odom_msg.pose.pose.orientation.w = self.current_state_nom.orientation[3] + self.odom_msg.twist.twist.linear.x = self.current_state_nom.velocity[0] + self.odom_msg.twist.twist.linear.y = self.current_state_nom.velocity[1] + self.odom_msg.twist.twist.linear.z = self.current_state_nom.velocity[2] + self.odom_msg.twist.twist.linear.z = self.current_state_nom.velocity[2] + + # Publishing the data + self.state_publisher_.publish(self.odom_msg) + def main(args=None): From d428dfbff1bb10778d790fbc2da87156efe1d312 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Fri, 21 Feb 2025 17:07:58 +0100 Subject: [PATCH 03/30] feat: added ES-UKF filter --- .../eskf_python/eskf_python_filter.py | 4 +- navigation/sp_ukf_python/CMakeLists.txt | 33 ++ navigation/sp_ukf_python/README.md | 0 .../sp_ukf_python/config/sp_ukf_python.yaml | 3 + navigation/sp_ukf_python/launch/ukf.launch.py | 22 + navigation/sp_ukf_python/package.xml | 23 + .../sp_ukf_python/sp_ukf_python/__init__.py | 0 .../sp_ukf_python/sp_ukf_python.py | 440 ++++++++++++++++++ .../sp_ukf_python/sp_ukf_python_class.py | 280 +++++++++++ .../sp_ukf_python/sp_ukf_python_node.py | 137 ++++++ .../sp_ukf_python/sp_ukf_python_utils.py | 107 +++++ .../sp_ukf_python/sp_ukf_python/test_ukf.py | 218 +++++++++ 12 files changed, 1265 insertions(+), 2 deletions(-) create mode 100644 navigation/sp_ukf_python/CMakeLists.txt create mode 100644 navigation/sp_ukf_python/README.md create mode 100644 navigation/sp_ukf_python/config/sp_ukf_python.yaml create mode 100644 navigation/sp_ukf_python/launch/ukf.launch.py create mode 100644 navigation/sp_ukf_python/package.xml create mode 100644 navigation/sp_ukf_python/sp_ukf_python/__init__.py create mode 100644 navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py create mode 100644 navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py create mode 100644 navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_node.py create mode 100644 navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_utils.py create mode 100644 navigation/sp_ukf_python/sp_ukf_python/test_ukf.py diff --git a/navigation/eskf_python/eskf_python/eskf_python_filter.py b/navigation/eskf_python/eskf_python/eskf_python_filter.py index 392c705c2..edf39dcc0 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_filter.py +++ b/navigation/eskf_python/eskf_python/eskf_python_filter.py @@ -2,7 +2,7 @@ from typing import tuple import numpy as np - +from scipy.linalg import expm @dataclass class StateVector_quaternion: @@ -212,7 +212,7 @@ def van_loan_discretization( * self.dt ) - van_loan_matrix = np.linalg.expm(matrix_exp) + van_loan_matrix = expm(matrix_exp) V1 = van_loan_matrix[A_c.shape[0] :, A_c.shape[0] :] V2 = van_loan_matrix[: A_c.shape[0], A_c.shape[0] :] diff --git a/navigation/sp_ukf_python/CMakeLists.txt b/navigation/sp_ukf_python/CMakeLists.txt new file mode 100644 index 000000000..a40f065cd --- /dev/null +++ b/navigation/sp_ukf_python/CMakeLists.txt @@ -0,0 +1,33 @@ +cmake_minimum_required(VERSION 3.8) +project(sp_ukf_python) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake_python REQUIRED) +find_package(rclpy REQUIRED) +find_package(vortex_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) + +ament_python_install_package(${PROJECT_NAME}) + +install(DIRECTORY + launch + config + DESTINATION share/${PROJECT_NAME} +) + +install(PROGRAMS + sp_ukf_python/sp_ukf_python_node.py + DESTINATION lib/${PROJECT_NAME} +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + find_package(ament_cmake_pytest REQUIRED) + set(ament_cmake_copyright_FOUND TRUE) + set(ament_cmake_cpplint_FOUND TRUE) +endif() + +ament_package() diff --git a/navigation/sp_ukf_python/README.md b/navigation/sp_ukf_python/README.md new file mode 100644 index 000000000..e69de29bb diff --git a/navigation/sp_ukf_python/config/sp_ukf_python.yaml b/navigation/sp_ukf_python/config/sp_ukf_python.yaml new file mode 100644 index 000000000..d3d18145d --- /dev/null +++ b/navigation/sp_ukf_python/config/sp_ukf_python.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + sp_ukf_python_node: diff --git a/navigation/sp_ukf_python/launch/ukf.launch.py b/navigation/sp_ukf_python/launch/ukf.launch.py new file mode 100644 index 000000000..fdd3f07e6 --- /dev/null +++ b/navigation/sp_ukf_python/launch/ukf.launch.py @@ -0,0 +1,22 @@ +import os + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch_ros.actions import Node + + +def generate_launch_description(): + sp_ukf_python_node = Node( + package='sp_ukf_python', + executable='sp_ukf_python_node.py', + name='sp_ukf_python_node', + parameters=[ + os.path.join( + get_package_share_directory('sp_ukf_python'), + 'config', + 'sp_ukf_python.yaml', + ), + ], + output='screen', + ) + return LaunchDescription([sp_ukf_python_node]) diff --git a/navigation/sp_ukf_python/package.xml b/navigation/sp_ukf_python/package.xml new file mode 100644 index 000000000..6aa4edbc0 --- /dev/null +++ b/navigation/sp_ukf_python/package.xml @@ -0,0 +1,23 @@ + + + + sp_ukf_python + 1.0.0 + This package provides the implementation of a sigma point based Unscented Error-state Kalman Filter + talhanc + MIT + + ament_cmake_python + + rclpy + python-transforms3d-pip + geometry_msgs + vortex_msgs + + python3-pytest + + + + ament_cmake + + diff --git a/navigation/sp_ukf_python/sp_ukf_python/__init__.py b/navigation/sp_ukf_python/sp_ukf_python/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py new file mode 100644 index 000000000..6f9d1b2f6 --- /dev/null +++ b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py @@ -0,0 +1,440 @@ +from dataclasses import dataclass +from typing import Tuple +from sp_ukf_python_class import StateVector_quaternion, StateVector_euler +from sp_ukf_python_utils import skew_symmetric, quaternion_super_product +from scipy.linalg import expm + +import numpy as np + +class ErrorStateUnscentedKalmanFilter: + def __init__( + self, + P_ab: float, + P_wb: float, + Q: np.ndarray, + lever_arm: np.array, + R: np.ndarray, + g: float, + dt: float, + ) -> None: + self.P_ab = P_ab + self.P_wb = P_wb + self.Q_process_noise = Q + self.lever_arm = lever_arm + self.R = R + self.g = np.array([0, 0, g]) + self.dt = dt + self.y_i = np.zeros((15, 2*15)) + + def mean_set(self, set: np.ndarray) -> np.ndarray: + """ + Calculates the mean of a set of values. + + Args: + set (np.ndarray): The set of values. + + Returns: + np.ndarray: The mean of the set. + """ + # Define the number of columns + n = set.shape[0] + + # Calculate the mean value + mean_value = (1 / (2 * n)) * np.sum(set, axis=1) + + return mean_value + + def weighted_mean_set(self, set: np.ndarray, weight: np.ndarray) -> np.ndarray: + """ + Calculates the mean of a set of values. + + Args: + set (np.ndarray): The set of values. + + Returns: + np.ndarray: The mean of the set. + """ + # Define the number of columns + n = set.shape[0] + mean_value = np.zeros(n) + + for i in range(2*n + 1): + mean_value += weight[i] * set[:, i] + + mean_value = (1 / (2 * n + 1)) * mean_value + + return mean_value + + def covariance_set(self, mean: np.ndarray, set: np.ndarray, mean_2: np.ndarray = None, set_2: np.ndarray = None) -> np.ndarray: + """ + Calculate the covarince of a set of sigmapoints + + Args: + mean (np.ndarray): The mean of the set. + set (np.ndarray): The set of values. + + Returns: + np.ndarray: The covariance of the set. + """ + + if mean_2 is not None: + + n = set.shape[0] + n2 = set_2.shape[0] + covariance_set = np.zeros((n, n2)) + + for i in range(2*n): + vector = StateVector_euler() + vector.position = set[:, i][:3] + vector.velocity = set[:, i][3:6] + vector.orientation = set[:, i][6:9] + vector.acceleration_bias = set[:, i][9:12] + vector.gyro_bias = set[:, i][12:] + + vector_2 = StateVector_euler() + vector_2.position = set_2[:, i][:3] + vector_2.velocity = set_2[:, i][3:6] + vector_2.orientation = set_2[:, i][6:9] + vector_2.acceleration_bias = set_2[:, i][9:12] + vector_2.gyro_bias = set_2[:, i][12:] + W_i = vector - mean + W_i_2 = vector_2 - mean_2 + + covariance_set += (1 / (2*n)) * np.outer(W_i, W_i_2) + + return covariance_set + else: + + n = set.shape[0] + covariance_set = np.zeros((n, n)) + + for i in range(2*n): + vector = StateVector_euler() + vector.position = set[:, i][:3] + vector.velocity = set[:, i][3:6] + vector.orientation = set[:, i][6:9] + vector.acceleration_bias = set[:, i][9:12] + vector.gyro_bias = set[:, i][12:] + + W_i = vector - mean + covariance_set += (1 / (2*n)) * np.outer(W_i, W_i) + + return covariance_set + + def weighted_covariance_set(self, mean: np.ndarray, set: np.ndarray, weight: np.ndarray) -> np.ndarray: + """ + Calculate the covarince of a set of sigmapoints + + Args: + mean (np.ndarray): The mean of the set. + set (np.ndarray): The set of values. + + Returns: + np.ndarray: The covariance of the set. + """ + + n = set.shape[0] + covariance_set = np.zeros((n, n)) + + for i in range(2*n): + vector = StateVector_euler() + vector.position = set[:, i][:3] + vector.velocity = set[:, i][3:6] + vector.orientation = set[:, i][6:9] + vector.acceleration_bias = set[:, i][9:12] + vector.gyro_bias = set[:, i][12:] + + W_i = vector - mean + covariance_set += weight[i] * np.outer(W_i, W_i) + + return covariance_set + + + + def generate_sigma_points(self, error_state: StateVector_euler, Q_process_noise) -> tuple[list[StateVector_euler], np.ndarray]: + """ + Generates the sigma points for the UKF + This is done using the Cholesky decomposition method + """ + + # Define n + n = len(error_state.covariance) + kappa = 3 - n + + # Computing S matrix using cholensky decomposition + S = np.linalg.cholesky(error_state.covariance + Q_process_noise) + + S_scaled = np.sqrt(n + kappa) * S + + weighted_points = np.concatenate((S_scaled , -S_scaled), axis=1) + + sigma_points = [StateVector_euler() for _ in range(2 * n + 1)] + + sigma_points[0].fill_states(error_state.as_vector()) + for i in range(2*n): + sigma_points[i + 1].fill_states(error_state + weighted_points[:,i]) + + W = np.zeros(2*n + 1) + W[0] = kappa / (n + kappa) + + for i in range(2*n): + W[i + 1] = 1 / (2 * (n + kappa)) + + return sigma_points, W + + def nominal_state_update( + self, current_state: StateVector_quaternion, imu_reading: np.ndarray + ) -> StateVector_quaternion: + """Updates the nominal state of the system. + + Args: + current_state (np.ndarray): The current state of the system. + imu_reading (np.ndarray): The IMU reading. + + Returns: + np.ndarray: The updated nominal state. + """ + # Defining the IMU readings + imu_acceleration = imu_reading[0:3] + imu_gyro = imu_reading[3:6] + + # Define the derivative of the state + current_state_dot = StateVector_quaternion() + + # Define the state derivates + current_state_dot.position = current_state.velocity + current_state_dot.velocity = ( + np.dot( + current_state.R_q(), + (imu_acceleration - current_state.acceleration_bias), + ) + + self.g + ) + + # Define the quaternion derivatives + current_state_dot.orientation = 0.5 * quaternion_super_product( + current_state.orientation, + np.array([0, imu_gyro[0] - current_state.gyro_bias[0], imu_gyro[1] - current_state.gyro_bias[1], imu_gyro[2] - current_state.gyro_bias[2]]), + ) + + # Define the bias + current_state_dot.acceleration_bias = ( + -np.dot(self.P_ab, np.eye(3)) @ current_state.acceleration_bias + ) + current_state_dot.gyro_bias = ( + -np.dot(self.P_wb, np.eye(3)) @ current_state.gyro_bias + ) + + return current_state_dot.euler_forward(current_state, self.dt) + + def error_state_update( + self, + current_error_state: StateVector_euler, + current_state: StateVector_quaternion, + imu_reading: np.ndarray, + ) -> np.ndarray: + """Updates the error state of the system. + + Args: + current_error_state (np.ndarray): The current error state of the system. + current_state (np.ndarray): The current state of the system. + imu_reading (np.ndarray): The IMU reading. + + Returns: + np.ndarray: The updated error state. + """ + # Defining the IMU readings + imu_acceleration = imu_reading[0:3] + imu_gyro = imu_reading[3:6] + + A_c = np.zeros((15, 15)) + A_c[0:3, 3:6] = np.eye(3) + A_c[3:6, 6:9] = -np.dot( + current_state.R_q(), + skew_symmetric(imu_acceleration - current_state.acceleration_bias), + ) + A_c[6:9, 6:9] = -skew_symmetric(imu_gyro - current_state.gyro_bias) + A_c[3:6, 9:12] = -current_state.R_q() + A_c[6:9, 12:15] = -np.eye(3) + A_c[9:12, 9:12] = -self.P_ab * np.eye(3) + A_c[12:15, 12:15] = -self.P_wb * np.eye(3) + + # Exact matrix exponential + A_d = expm(A_c * self.dt) + + next_error_state = A_d @ current_error_state.as_vector() + + return next_error_state + + def unscented_transform(self, sigma_points: list[StateVector_euler], current_state: StateVector_quaternion, + imu_reading: np.ndarray,) -> StateVector_euler: + """ + Performs the Unscented Transform + This is the corresponding to a preditction step in the EKF + """ + + n = len(sigma_points[0].as_vector()) + + self.y_i = np.zeros((n, 2*n)) + + for i in range(2*n): + self.y_i[:, i] = self.error_state_update(sigma_points[i], current_state, imu_reading) + + error_state_estimate = StateVector_euler() + + x = self.mean_set(self.y_i) + + error_state_estimate.fill_states(x) + error_state_estimate.covariance = self.covariance_set(x, self.y_i) + + return error_state_estimate + + def H(self) -> np.ndarray: + """Calculates the measurement matrix. + + Returns: + np.ndarray: The measurement matrix. + """ + # Define the measurement matrix + H = np.zeros((3, 15)) + + # For now assume only velocity is measured + H[0:3, 3:6] = np.eye(3) + + return H + + def measurement_update(self, sigma_points: list[StateVector_euler], current_error_state: StateVector_euler, dvl_data: np.ndarray, Weight: np.ndarray) -> StateVector_euler: + """ + Updates the state vector with the DVL data + """ + + H = self.H() + R = self.R + + n = len(sigma_points[0].as_vector()) + + Z_i = np.zeros((H.shape[0], 2 * n)) + + for i in range(2*n): + Z_i[:, i] = np.dot(H, sigma_points[i].as_vector()) + + z = self.weighted_mean_set(Z_i, Weight) + S = self.weighted_covariance_set(z, Z_i, Weight) + + x = self.mean_set(self.y_i) + + # Calculate the rest + innovation = dvl_data - z + + P_innovation = S + R + + P_xz = self.covariance_set(x, self.y_i, z, Z_i) + + # Kalman gain + K_k = np.dot(P_xz, np.linalg.inv(P_innovation)) + + updated_error_state = StateVector_euler() + + # Update the state + updated_error_state.fill_states(x + np.dot(K_k, innovation)) + + # Update the covariance + updated_error_state.covariance = current_error_state.covariance - np.dot(K_k, np.dot(P_innovation, K_k.T)) + + return updated_error_state + + def imu_update_states(self, current_state_nom: StateVector_quaternion, current_state_error: StateVector_euler, imu_data: np.ndarray) -> tuple[StateVector_quaternion, StateVector_euler]: + """ + Updates the state vector with the IMU data + + Args: + current_state_nom (StateVector_quaternion): The current nominal state + current_state_error (StateVector_euler): The current error state + imu_data (np.ndarray): The IMU data + + Returns: + tuple[StateVector_quaternion, StateVector_euler]: The updated nominal and error states + + """ + + # Update the nominal state + current_state_nom = self.nominal_state_update(current_state_nom, imu_data) + + # Generate the sigma points + sigma_points, _ = self.generate_sigma_points(current_state_error, self.Q_process_noise) + + # Update the error state + current_state_error = self.unscented_transform(sigma_points, current_state_nom, imu_data) + + return current_state_nom, current_state_error + + def dvl_update_states(self, current_state_nom: StateVector_quaternion, current_state_error: StateVector_euler, dvl_data: np.ndarray) -> tuple[StateVector_quaternion, StateVector_euler]: + """ + Update the error state given the DVL data + + Args: + current_state_nom (StateVector_quaternion): The current nominal state + current_state_error (StateVector_euler): The current error state + dvl_data (np.ndarray): The DVL data to update the state with + + Returns: + tuple[StateVector_quaternion, StateVector_euler]: The updated nominal and error states + """ + + # Generate the sigma points + sigma_points, weight = self.generate_sigma_points(current_state_error, self.Q_process_noise) + + # Update the error state + current_state_error = self.measurement_update(sigma_points, current_state_error, dvl_data, weight) + + return current_state_nom, current_state_error + + def inject_and_reset(self, current_state_nom: StateVector_quaternion, current_state_error: StateVector_euler) -> tuple[StateVector_quaternion, StateVector_euler]: + """ + Injects the error state into the nominal state and resets the error state + + Args: + current_state_nom (StateVector_quaternion): The current nominal state + current_state_error (StateVector_euler): The current error state + + Returns: + tuple[StateVector_quaternion, StateVector_euler]: The updated nominal and error states + """ + + inj_state = StateVector_quaternion() + + inj_state.position = current_state_nom.position + current_state_error.position + inj_state.velocity = current_state_nom.velocity + current_state_error.velocity + inj_state.orientation = quaternion_super_product( + current_state_nom.orientation, + 0.5 + * np.array( + [ + 2, + current_state_error.orientation[0], + current_state_error.orientation[1], + current_state_error.orientation[2], + ] + ), + ) + inj_state.acceleration_bias = ( + current_state_nom.acceleration_bias + current_state_error.acceleration_bias + ) + inj_state.gyro_bias = current_state_nom.gyro_bias + current_state_error.gyro_bias + + + # Resetting the error state + G = np.eye(15) + G[6:9, 6:9] = np.eye(3) - skew_symmetric( + 0.5 * current_state_error.orientation + ) + + current_state_error.covariance = np.dot( + np.dot(G, current_state_error.covariance), G.T + ) + + current_state_error.fill_states(np.zeros(15)) + + + return inj_state, current_state_error + diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py new file mode 100644 index 000000000..629ce460e --- /dev/null +++ b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py @@ -0,0 +1,280 @@ +import numpy as np +from dataclasses import dataclass, field +from sp_ukf_python_utils import quaternion_super_product, quaternion_error, euler_rotation_quaternion, ssa + +@dataclass +class StateVector_quaternion: + position: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Position vector (x, y, z) + velocity: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Velocity vector (u, v, w) + orientation: np.ndarray = field( + default_factory=lambda: np.zeros(4) + ) # Orientation quaternion (w, x, y, z) + acceleration_bias: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Acceleration bias vector (b_ax, b_ay, b_az) + gyro_bias: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Gyro bias vector (b_gx, b_gy, b_gz) + + def as_vector(self) -> np.ndarray: + """Calculates the state vector. + + Returns: + np.ndarray: The state vector. + """ + return np.concatenate( + [ + self.position, + self.velocity, + self.orientation, + self.acceleration_bias, + self.gyro_bias, + ] + ) + + def fill_states(self, state: np.ndarray) -> None: + """Fills the state vector with the values from a numpy array. + + Args: + state (np.ndarray): The state vector. + """ + if len(state) == 15: + self.position = state[0:3] + self.velocity = state[3:6] + self.orientation = state[6:10] + self.acceleration_bias = state[10:13] + self.gyro_bias = state[13:] + else: + self.position = state[0:3] + self.velocity = state[3:6] + self.orientation = euler_rotation_quaternion(state[6:9]) + self.acceleration_bias = state[9:12] + self.gyro_bias = state[12:] + + def R_q(self) -> np.ndarray: + """Calculates the rotation matrix from the orientation quaternion. + + Returns: + np.ndarray: The rotation matrix. + """ + q0, q1, q2, q3 = self.orientation + R = np.array( + [ + [ + 1 - 2 * q2**2 - 2 * q3**2, + 2 * (q1 * q2 - q0 * q3), + 2 * (q0 * q2 + q1 * q3), + ], + [ + 2 * (q1 * q2 + q0 * q3), + 1 - 2 * q1**2 - 2 * q3**2, + 2 * (q2 * q3 - q0 * q1), + ], + [ + 2 * (q1 * q3 - q0 * q2), + 2 * (q0 * q1 + q2 * q3), + 1 - 2 * q1**2 - 2 * q2**2, + ], + ] + ) + + return R + + def euler_forward( + self, current_state: 'StateVector_quaternion', dt: float + ) -> 'StateVector_quaternion': + # Define the new state + new_state = StateVector_quaternion() + + # Define the state derivatives + new_state.position = current_state.position + self.position * dt + new_state.velocity = current_state.velocity + self.velocity * dt + new_state.orientation = current_state.orientation + self.orientation * dt + new_state.acceleration_bias = ( + current_state.acceleration_bias + self.acceleration_bias * dt + ) + new_state.gyro_bias = current_state.gyro_bias + self.gyro_bias * dt + + # Normalize the orientation quaternion + new_state.orientation /= np.linalg.norm(new_state.orientation) + + return new_state + + def __sub__(self, other: 'StateVector_quaternion') -> np.ndarray: + """Subtracts two StateVector_quaternion objects. + + Args: + other (StateVector_quaternion): The other StateVector_quaternion object. + + Returns: + np.ndarray: The difference between the two StateVector_quaternion objects. + """ + position_diff = self.position - other.position + velocity_diff = self.velocity - other.velocity + orientation_diff = quaternion_error(self.orientation, other.orientation) + acceleration_bias_diff = self.acceleration_bias - other.acceleration_bias + gyro_bias_diff = self.gyro_bias - other.gyro_bias + + return np.concatenate( + [ + position_diff, + velocity_diff, + orientation_diff, + acceleration_bias_diff, + gyro_bias_diff, + ] + ) + + def __add__(self, other: 'np.ndarray') -> 'np.ndarray': + """Adds a numpy array to this StateVector_quaternion. + + Args: + other (np.ndarray): The numpy array to add. + + Returns: + np.ndarray: The result of the addition. + """ + # Construct the quaternion from the array + add_to_position = other[:3] + add_to_orientation = euler_rotation_quaternion(other[6:10]) + + new_position = self.position + add_to_position + new_velcoity = self.velocity + other[3:6] + new_orientation = quaternion_super_product(self.orientation, add_to_orientation) + new_acceleration_bias = self.acceleration_bias + other[10:13] + new_gyro_bias = self.gyro_bias + other[13:] + + return np.concatenate( + [ + new_position, + new_velcoity, + new_orientation, + new_acceleration_bias, + new_gyro_bias, + ] + ) + + +@dataclass +class StateVector_euler: + position: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Position vector (x, y, z) + velocity: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Velocity vector (u, v, w) + orientation: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Orientation angles (roll, pitch, yaw) + acceleration_bias: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Acceleration bias vector (b_ax, b_ay, b_az) + gyro_bias: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Gyro bias vector (b_gx, b_gy, b_gz) + covariance: np.ndarray = field( + default_factory=lambda: np.zeros((15, 15)) + ) # Covariance matrix + + def as_vector(self) -> np.ndarray: + """Calculates the state estimate vector. + + Returns: + np.ndarray: The state estimate vector. + """ + return np.concatenate( + [ + self.position, + self.velocity, + self.orientation, + self.acceleration_bias, + self.gyro_bias, + ] + ) + + def fill_states(self, state: np.ndarray) -> None: + """Fills the state vector with the values from a numpy array. + + Args: + state (np.ndarray): The state vector. + """ + self.position = state[0:3] + self.velocity = state[3:6] + self.orientation = state[6:9] + self.acceleration_bias = state[9:12] + self.gyro_bias = state[12:15] + + def copy_state(self, wanted_state: 'StateVector_euler') -> None: + """Copies the state from a StateVector object into the current StateVector object. + + Args: + wanted_state (StateVector_euler): The quaternion state to copy from. + """ + self.position = wanted_state.position + self.velocity = wanted_state.velocity + self.orientation = wanted_state.orientation + self.acceleration_bias = wanted_state.acceleration_bias + self.gyro_bias = wanted_state.gyro_bias + + def __add__(self, other: 'np.ndarray') -> 'np.ndarray': + """Adds a numpy array to this StateVector_quaternion. + + Args: + other (np.ndarray): The numpy array to add. + + Returns: + np.ndarray: The result of the addition. + """ + + new_position = self.position + other[:3] + new_velcoity = self.velocity + other[3:6] + new_orientation = self.orientation + other[6:9] + new_acceleration_bias = self.acceleration_bias + other[9:12] + new_gyro_bias = self.gyro_bias + other[12:] + + return np.concatenate( + [ + new_position, + new_velcoity, + new_orientation, + new_acceleration_bias, + new_gyro_bias, + ] + ) + + def __sub__(self, other_state: 'StateVector_euler') -> 'StateVector_euler': + """ + Subtracts two StateVector_euler objects. + + Args: + other (StateVector_euler): The other StateVector_euler object. + + Returns: + StateVector_euler: The difference between the two StateVector_euler objects. + """ + position_diff = self.position - other_state[:3] + velocity_diff = self.velocity - other_state[3:6] + orientation_diff = ssa(self.orientation - other_state[6:9]) + acceleration_bias_diff = self.acceleration_bias - other_state[9:12] + gyro_bias_diff = self.gyro_bias - other_state[12:] + + return np.concatenate( + (position_diff, velocity_diff, orientation_diff, acceleration_bias_diff, gyro_bias_diff) + ) + + +@dataclass +class MeasurementModel: + measurement: np.ndarray = field( + default_factory=lambda: np.zeros(6) + ) # Measurement vector + measurement_matrix: np.ndarray = field( + default_factory=lambda: np.zeros((6, 15)) + ) # Measurement matrix + measurement_covariance: np.ndarray = field( + default_factory=lambda: np.zeros((6, 6)) + ) # Measurement noise matrix \ No newline at end of file diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_node.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_node.py new file mode 100644 index 000000000..103528ef2 --- /dev/null +++ b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_node.py @@ -0,0 +1,137 @@ +#!/usr/bin/env python3 + +import rclpy +from nav_msgs.msg import Odometry +from rclpy.node import Node +from rclpy.qos import QoSProfile, qos_profile_sensor_data +from sensor_msgs.msg import Imu, +import numpy as np +from geometry_msgs.msg import TwistWithCovarianceStamped + +# NEED TO CHANGE THIS TO THE CORRECT PATH +from eskf_python.eskf_python_filter import ( + ErrorStateKalmanFilter, + MeasurementModel, + StateVector_euler, + StateVector_quaternion, +) + +qos_profile = QoSProfile( + depth=1, + history=qos_profile_sensor_data.history, + reliability=qos_profile_sensor_data.reliability, +) + + +class ESKalmanFilterNode(Node): + def __init__(self): + super().__init__("sp_ukf_python_node") + + # This callback will supply information from the IMU (Inertial Measurement Unit) 1000 Hz + self.imu_subscriber_ = self.create_subscription( + Imu, '/orca/imu', self.imu_callback, qos_profile=qos_profile + ) + + self.twist_dvl_subscriber_ = self.create_subscription( + TwistWithCovarianceStamped, '/dvl/twist', self.filter_callback, qos_profile=qos_profile + ) + + # This publisher will publish the estimtaed state of the vehicle + self.state_publisher_ = self.create_publisher( + Odometry, '/orca/odom', qos_profile=qos_profile + ) + + self.eskf_modual = ErrorStateKalmanFilter() + self.current_state_nom = StateVector_quaternion() + self.current_state_error = StateVector_euler() + self.measurement_pred = MeasurementModel() + self.odom_msg = Odometry() + + self.get_logger().info("Unscented Kalman Filter started") + + def imu_callback(self, msg: Imu): + + # Get the IMU data + + imu_acceleartion = msg.linear_acceleration + imu_angular_velocity = msg.angular_velocity + + # Combine the IMU data + imu_data = np.array([imu_acceleartion.x, imu_acceleartion.y, imu_acceleartion.z, imu_angular_velocity.x, imu_angular_velocity.y, imu_angular_velocity.z]) + + # Update the filter with the IMU data + self.current_state_nom, self.current_state_error = ( + ErrorStateKalmanFilter.imu_update_states( + self.current_state_nom, self.current_state_error, imu_data + ) + ) + + # Inserting the nominal state into the msg + self.odom_msg.pose.pose.position.x = self.current_state_nom.position[0] + self.odom_msg.pose.pose.position.y = self.current_state_nom.position[1] + self.odom_msg.pose.pose.position.z = self.current_state_nom.position[2] + self.odom_msg.pose.pose.orientation.x = self.current_state_nom.orientation[0] + self.odom_msg.pose.pose.orientation.y = self.current_state_nom.orientation[1] + self.odom_msg.pose.pose.orientation.z = self.current_state_nom.orientation[2] + self.odom_msg.pose.pose.orientation.w = self.current_state_nom.orientation[3] + self.odom_msg.twist.twist.linear.x = self.current_state_nom.velocity[0] + self.odom_msg.twist.twist.linear.y = self.current_state_nom.velocity[1] + self.odom_msg.twist.twist.linear.z = self.current_state_nom.velocity[2] + self.odom_msg.twist.twist.angular.x = imu_angular_velocity.x + self.odom_msg.twist.twist.angular.y = imu_angular_velocity.y + self.odom_msg.twist.twist.angular.z = imu_angular_velocity.z + + # Publish + self.state_publisher_.publish(self.odom_msg) + + + + def filter_callback(self, msg: TwistWithCovarianceStamped): + """Callback function for the filter measurement update, + this will be called when the filter needs to be updated with the DVL data. + """ + self.get_logger().info("Filter callback, got DVL data") + + # Get the DVL data (linear velocity) + dvl_data = np.array([msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z]) + + # Update the filter with the DVL data + self.current_state_nom, self.current_state_error = ( + ErrorStateKalmanFilter.dvl_update_states( + self.current_state_nom, self.current_state_error, dvl_data + ) + ) + self.current_state_nom, self.current_state_error = ( + ErrorStateKalmanFilter.injection_and_reset( + self.current_state_nom, self.current_state_error + ) + ) + + # Inserting data into the msg + self.odom_msg.pose.pose.position.x = self.current_state_nom.position[0] + self.odom_msg.pose.pose.position.y = self.current_state_nom.position[1] + self.odom_msg.pose.pose.position.z = self.current_state_nom.position[2] + self.odom_msg.pose.pose.orientation.x = self.current_state_nom.orientation[0] + self.odom_msg.pose.pose.orientation.y = self.current_state_nom.orientation[1] + self.odom_msg.pose.pose.orientation.z = self.current_state_nom.orientation[2] + self.odom_msg.pose.pose.orientation.w = self.current_state_nom.orientation[3] + self.odom_msg.twist.twist.linear.x = self.current_state_nom.velocity[0] + self.odom_msg.twist.twist.linear.y = self.current_state_nom.velocity[1] + self.odom_msg.twist.twist.linear.z = self.current_state_nom.velocity[2] + self.odom_msg.twist.twist.linear.z = self.current_state_nom.velocity[2] + + # Publishing the data + self.state_publisher_.publish(self.odom_msg) + + + +def main(args=None): + rclpy.init(args=args) + node = ESKalmanFilterNode() + rclpy.spin(node) + node.destroy_node() + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_utils.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_utils.py new file mode 100644 index 000000000..071180fc7 --- /dev/null +++ b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_utils.py @@ -0,0 +1,107 @@ +import numpy as np + +def quaternion_super_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: + """Calculates the quaternion super product of two quaternions. + + Args: + q1 (np.ndarray): The first quaternion. + q2 (np.ndarray): The second quaternion. + + Returns: + np.ndarray: The quaternion super product. + """ + eta_0, e_0_x, e_0_y, e_0_z = q1 + eta_1, e_1_x, e_1_y, e_1_z = q2 + + e_0 = np.array([e_0_x, e_0_y, e_0_z]) + e_1 = np.array([e_1_x, e_1_y, e_1_z]) + + eta_new = eta_0 * eta_1 - (e_0_x * e_1_x + e_0_y * e_1_y + e_0_z * e_1_z) + nu_new = e_1 * eta_0 + e_0 * eta_1 + np.dot(skew_symmetric(e_0), e_1) + + q_new = np.array([eta_new, nu_new[0], nu_new[1], nu_new[2]]) + q_new /= np.linalg.norm(q_new) + + return q_new + +def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: + """ + Calculates the error between two quaternions + """ + + quat_2_inv = np.array([quat_2[0], -quat_2[1], -quat_2[2], -quat_2[3]]) + + error_quat = quaternion_super_product(quat_1, quat_2_inv) + + return error_quat + +def euler_rotation_quaternion(self, euler_angles: np.ndarray) -> np.ndarray: + """ + Converts An vector assumed to be rotation vector to quaternion + + Args: + euler_angles (np.ndarray): Rotation vector + + Returns: + np.ndarray: Quaternion representation of the rotation vector + """ + + angle = np.linalg.norm(euler_angles) + + if angle == 0: + axis = np.array([0, 0, 0]) + else: + axis = euler_angles / angle + + quaternion = np.zeros(4) + quaternion[0] = np.cos(angle / 2) + quaternion[1:] = np.sin(angle / 2) * axis + + return quaternion + +def quaternion_rotation_euler(self, quaternion: np.ndarray) -> np.ndarray: + """ + Converts a quaternion to an euler rotation vector + Used to generate the covarince matrix + + Args: + quaternion (np.ndarray): The quaternion to convert + + Returns: + np.ndarray: The euler rotation vector + """ + nu, eta_x, eta_y, eta_z = quaternion + + phi = np.arctan2(2 * (nu * eta_x + eta_y * eta_z), 1 - 2 * (eta_x ** 2 + eta_y ** 2)) + theta = -np.arcsin(2 * (eta_z * eta_x - nu * eta_y)) + psi = np.arctan2(2 * (nu * eta_z + eta_x * eta_y), 1 - 2 * (eta_y ** 2 + eta_z ** 2)) + + return np.array([phi, theta, psi]) + +def skew_symmetric(vector: np.ndarray) -> np.ndarray: + """Calculates the skew symmetric matrix of a vector. + + Args: + vector (np.ndarray): The vector. + + Returns: + np.ndarray: The skew symmetric matrix. + """ + return np.array( + [ + [0, -vector[2], vector[1]], + [vector[2], 0, -vector[0]], + [-vector[1], vector[0], 0], + ] + ) + +def ssa(angle: np.ndarray) -> np.ndarray: + """ + smallest signed angle between two angles + """ + ssa_vector = np.zeros(len(angle)) + + for i in range(len(angle)): + ssa_vector[i] = (angle[i] + np.pi) % (2 * np.pi) - np.pi + + return ssa_vector \ No newline at end of file diff --git a/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py b/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py new file mode 100644 index 000000000..59e08aa55 --- /dev/null +++ b/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py @@ -0,0 +1,218 @@ +import numpy as np +import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D # for 3D plotting + +# (Assuming the following have been imported from your modules) +from sp_ukf_python_class import StateVector_quaternion, StateVector_euler +from sp_ukf_python_utils import skew_symmetric, quaternion_super_product +from sp_ukf_python import ErrorStateUnscentedKalmanFilter + +def quat_to_yaw(q: np.ndarray) -> float: + """ + Convert a quaternion (assumed [w, x, y, z]) with zero roll and pitch + into a yaw angle. + """ + return 2 * np.arctan2(q[3], q[0]) + +def run_ESUKF_simulation(): + # Simulation parameters + dt = 0.01 # time step [s] + T = 60.0 # total simulation time [s] + num_steps = int(T/dt) + g_val = 9.81 # gravitational acceleration + + # Define noise and covariance matrices + Q = np.diag([0.1]*15) # Process noise covariance (15x15) + R_meas = np.diag([0.08]*3) # DVL measurement noise (velocity noise) + P_ab = 0.005 # Accelerometer bias dynamics matrix + P_wb = 0.005 # Gyro bias dynamics matrix + lever_arm = np.array([0.0, 0.0, 0.0]) # Assume sensor is at the center of mass + + # Create ESUKF instance + esukf = ErrorStateUnscentedKalmanFilter(P_ab, P_wb, Q, lever_arm, R_meas, g_val, dt) + + # Initialize true state (StateVector_quaternion) with no biases. + true_state = StateVector_quaternion() + true_state.position = np.array([20.0, 0.0, 0.0]) + true_state.velocity = np.array([0.0, 1.0, 0.0]) + true_state.orientation = np.array([1.0, 0.0, 0.0, 0.0]) # No initial rotation + true_state.acceleration_bias = np.zeros(3) + true_state.gyro_bias = np.zeros(3) + + # Initialize estimated (nominal) state with a small offset. + est_state_nom = StateVector_quaternion() + est_state_nom.position = true_state.position + np.array([0.1, -0.1, 0.05]) + est_state_nom.velocity = true_state.velocity + np.array([0.05, 0.05, -0.05]) + est_state_nom.orientation = true_state.orientation.copy() + est_state_nom.acceleration_bias = np.zeros(3) + est_state_nom.gyro_bias = np.zeros(3) + + # Initialize error state (StateVector_euler) as zero with some initial covariance. + est_state_error = StateVector_euler() + est_state_error.fill_states(np.zeros(15)) + est_state_error.covariance = 0.1 * np.eye(15) + + # Prepare histories for plotting + time_hist = [] + true_pos_hist = [] + est_pos_hist = [] + true_vel_hist = [] + est_vel_hist = [] + true_yaw_hist = [] + est_yaw_hist = [] + + # For the true trajectory, we simulate a circle in the horizontal plane. + R_circle = 20.0 # circle radius [m] + omega = 0.05 # angular speed [rad/s] + + t = 0.0 + for step in range(num_steps): + # --- True State Generation --- + # Circular trajectory: position = [R*cos(omega*t), R*sin(omega*t), 0] + pos_true = np.array([R_circle * np.cos(omega * t), + R_circle * np.sin(omega * t), + 0.0]) + # Velocity is the derivative of position. + vel_true = np.array([-R_circle * omega * np.sin(omega * t), + R_circle * omega * np.cos(omega * t), + 0.0]) + # Acceleration is the second derivative. + acc_true = np.array([-R_circle * omega**2 * np.cos(omega * t), + -R_circle * omega**2 * np.sin(omega * t), + 0.0]) + # Update the true state. + true_state.position = pos_true + true_state.velocity = vel_true + # Compute heading (yaw) tangent to the path. + yaw_true = np.arctan2(vel_true[1], vel_true[0]) + # For simplicity, assume roll and pitch are zero. + true_state.orientation = np.array([np.cos(yaw_true/2), 0.0, 0.0, np.sin(yaw_true/2)]) + # Biases remain zero for the true state. + + # --- Simulated IMU Measurements --- + # The nominal state propagation uses: + # velocity_dot = R_q() @ (imu_acc - bias) + g + # Therefore, the ideal accelerometer measurement is: + # imu_acc = R_true.T @ (acc_true - g_vector) + R_true = true_state.R_q() # rotation matrix from quaternion + imu_acc_ideal = np.dot(R_true.T, (acc_true - np.array([0.0, 0.0, g_val]))) + # Add noise (e.g., 0.1 m/s^2 std dev). + imu_acc_noise = np.random.normal(0.0, 0.1, 3) + imu_acc_meas = imu_acc_ideal + imu_acc_noise + + # For the gyro: the true angular velocity in body frame. + # For a circular path with constant yaw rate, the ideal gyro reading is: + imu_gyro_ideal = np.array([0.0, 0.0, omega]) + # Add noise (e.g., 0.01 rad/s std dev). + imu_gyro_noise = np.random.normal(0.0, 0.01, 3) + imu_gyro_meas = imu_gyro_ideal + imu_gyro_noise + + # Combine to form the complete IMU measurement vector. + imu_meas = np.hstack((imu_acc_meas, imu_gyro_meas)) + + # --- Simulated DVL Measurement --- + # DVL measures velocity (here assumed in the inertial frame). + dvl_noise = np.random.normal(0.0, 0.05, 3) + dvl_meas = vel_true + dvl_noise + + # --- Filter Updates --- + # 1. Propagate the nominal state with IMU data. + est_state_nom, est_state_error = esukf.imu_update_states(est_state_nom, est_state_error, imu_meas) + # 2. Incorporate DVL measurement. + est_state_nom, est_state_error = esukf.dvl_update_states(est_state_nom, est_state_error, dvl_meas) + # 3. Inject the error state into the nominal state and reset the error state. + est_state_nom, est_state_error = esukf.inject_and_reset(est_state_nom, est_state_error) + + # --- Store Histories --- + time_hist.append(t) + true_pos_hist.append(pos_true) + est_pos_hist.append(est_state_nom.position.copy()) + true_vel_hist.append(vel_true) + est_vel_hist.append(est_state_nom.velocity.copy()) + true_yaw_hist.append(yaw_true) + est_yaw_hist.append(quat_to_yaw(est_state_nom.orientation)) + + t += dt + + # Convert histories to NumPy arrays. + true_pos_hist = np.array(true_pos_hist) + est_pos_hist = np.array(est_pos_hist) + true_vel_hist = np.array(true_vel_hist) + est_vel_hist = np.array(est_vel_hist) + true_yaw_hist = np.array(true_yaw_hist) + est_yaw_hist = np.array(est_yaw_hist) + time_hist = np.array(time_hist) + + # --- Plotting Results --- + + # Plot positions (each axis separately) + plt.figure(figsize=(10, 8)) + plt.subplot(3, 1, 1) + plt.plot(time_hist, true_pos_hist[:, 0], label='True X') + plt.plot(time_hist, est_pos_hist[:, 0], '--', label='Estimated X') + plt.ylabel('X Position (m)') + plt.legend() + + plt.subplot(3, 1, 2) + plt.plot(time_hist, true_pos_hist[:, 1], label='True Y') + plt.plot(time_hist, est_pos_hist[:, 1], '--', label='Estimated Y') + plt.ylabel('Y Position (m)') + plt.legend() + + plt.subplot(3, 1, 3) + plt.plot(time_hist, true_pos_hist[:, 2], label='True Z') + plt.plot(time_hist, est_pos_hist[:, 2], '--', label='Estimated Z') + plt.xlabel('Time (s)') + plt.ylabel('Z Position (m)') + plt.legend() + plt.tight_layout() + plt.show() + + # Plot velocities + plt.figure(figsize=(10, 8)) + plt.subplot(3, 1, 1) + plt.plot(time_hist, true_vel_hist[:, 0], label='True Vx') + plt.plot(time_hist, est_vel_hist[:, 0], '--', label='Estimated Vx') + plt.ylabel('Vx (m/s)') + plt.legend() + + plt.subplot(3, 1, 2) + plt.plot(time_hist, true_vel_hist[:, 1], label='True Vy') + plt.plot(time_hist, est_vel_hist[:, 1], '--', label='Estimated Vy') + plt.ylabel('Vy (m/s)') + plt.legend() + + plt.subplot(3, 1, 3) + plt.plot(time_hist, true_vel_hist[:, 2], label='True Vz') + plt.plot(time_hist, est_vel_hist[:, 2], '--', label='Estimated Vz') + plt.xlabel('Time (s)') + plt.ylabel('Vz (m/s)') + plt.legend() + plt.tight_layout() + plt.show() + + # Plot heading (yaw) + plt.figure(figsize=(10, 4)) + plt.plot(time_hist, np.degrees(true_yaw_hist), label='True Yaw') + plt.plot(time_hist, np.degrees(est_yaw_hist), '--', label='Estimated Yaw') + plt.xlabel('Time (s)') + plt.ylabel('Yaw (deg)') + plt.legend() + plt.title('Heading Comparison') + plt.tight_layout() + plt.show() + + # Plot 3D Trajectory + fig = plt.figure(figsize=(8, 6)) + ax = fig.add_subplot(111, projection='3d') + ax.plot(true_pos_hist[:, 0], true_pos_hist[:, 1], true_pos_hist[:, 2], label='True Trajectory', linewidth=2) + ax.plot(est_pos_hist[:, 0], est_pos_hist[:, 1], est_pos_hist[:, 2], '--', label='Estimated Trajectory', linewidth=2) + ax.set_xlabel('X (m)') + ax.set_ylabel('Y (m)') + ax.set_zlabel('Z (m)') + ax.legend() + plt.title('3D Trajectory') + plt.show() + +if __name__ == '__main__': + run_ESUKF_simulation() From 382b0799e89b14836558aa8734e751168b94fdfa Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Thu, 27 Feb 2025 16:18:15 +0100 Subject: [PATCH 04/30] feat: added UKF fix injection step --- .../sp_ukf_python/sp_ukf_python.py | 377 ++++++++++-------- .../sp_ukf_python/sp_ukf_python_class.py | 33 +- .../sp_ukf_python/sp_ukf_python/test_ukf.py | 295 +++++++++----- 3 files changed, 434 insertions(+), 271 deletions(-) diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py index 6f9d1b2f6..8d2ff6265 100644 --- a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py +++ b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py @@ -1,10 +1,9 @@ -from dataclasses import dataclass -from typing import Tuple -from sp_ukf_python_class import StateVector_quaternion, StateVector_euler -from sp_ukf_python_utils import skew_symmetric, quaternion_super_product -from scipy.linalg import expm import numpy as np +from scipy.linalg import expm +from sp_ukf_python_class import StateVector_euler, StateVector_quaternion +from sp_ukf_python_utils import quaternion_super_product, skew_symmetric + class ErrorStateUnscentedKalmanFilter: def __init__( @@ -24,11 +23,10 @@ def __init__( self.R = R self.g = np.array([0, 0, g]) self.dt = dt - self.y_i = np.zeros((15, 2*15)) - + self.y_i = np.zeros((15, 2 * 15)) + def mean_set(self, set: np.ndarray) -> np.ndarray: - """ - Calculates the mean of a set of values. + """Calculates the mean of a set of values. Args: set (np.ndarray): The set of values. @@ -38,15 +36,14 @@ def mean_set(self, set: np.ndarray) -> np.ndarray: """ # Define the number of columns n = set.shape[0] - + # Calculate the mean value mean_value = (1 / (2 * n)) * np.sum(set, axis=1) return mean_value - + def weighted_mean_set(self, set: np.ndarray, weight: np.ndarray) -> np.ndarray: - """ - Calculates the mean of a set of values. + """Calculates the mean of a set of values. Args: set (np.ndarray): The set of values. @@ -57,86 +54,94 @@ def weighted_mean_set(self, set: np.ndarray, weight: np.ndarray) -> np.ndarray: # Define the number of columns n = set.shape[0] mean_value = np.zeros(n) - - for i in range(2*n + 1): + + for i in range(2 * n + 1): mean_value += weight[i] * set[:, i] - mean_value = (1 / (2 * n + 1)) * mean_value + mean_value = (1 / (2 * n + 1)) * mean_value return mean_value - - def covariance_set(self, mean: np.ndarray, set: np.ndarray, mean_2: np.ndarray = None, set_2: np.ndarray = None) -> np.ndarray: - """ - Calculate the covarince of a set of sigmapoints - + + def covariance_set(self, mean: np.ndarray, set: np.ndarray) -> np.ndarray: + """Calculate the covarince of a set of sigmapoints + Args: mean (np.ndarray): The mean of the set. set (np.ndarray): The set of values. - + Returns: np.ndarray: The covariance of the set. """ + n = set.shape[0] + covariance_set = np.zeros((n, n)) - if mean_2 is not None: - - n = set.shape[0] - n2 = set_2.shape[0] - covariance_set = np.zeros((n, n2)) - - for i in range(2*n): - vector = StateVector_euler() - vector.position = set[:, i][:3] - vector.velocity = set[:, i][3:6] - vector.orientation = set[:, i][6:9] - vector.acceleration_bias = set[:, i][9:12] - vector.gyro_bias = set[:, i][12:] - - vector_2 = StateVector_euler() - vector_2.position = set_2[:, i][:3] - vector_2.velocity = set_2[:, i][3:6] - vector_2.orientation = set_2[:, i][6:9] - vector_2.acceleration_bias = set_2[:, i][9:12] - vector_2.gyro_bias = set_2[:, i][12:] - W_i = vector - mean - W_i_2 = vector_2 - mean_2 - - covariance_set += (1 / (2*n)) * np.outer(W_i, W_i_2) - - return covariance_set - else: - - n = set.shape[0] - covariance_set = np.zeros((n, n)) - - for i in range(2*n): - vector = StateVector_euler() - vector.position = set[:, i][:3] - vector.velocity = set[:, i][3:6] - vector.orientation = set[:, i][6:9] - vector.acceleration_bias = set[:, i][9:12] - vector.gyro_bias = set[:, i][12:] - - W_i = vector - mean - covariance_set += (1 / (2*n)) * np.outer(W_i, W_i) - - return covariance_set - - def weighted_covariance_set(self, mean: np.ndarray, set: np.ndarray, weight: np.ndarray) -> np.ndarray: + for i in range(2 * n + 1): + vector = StateVector_euler() + vector.position = set[:, i][:3] + vector.velocity = set[:, i][3:6] + vector.orientation = set[:, i][6:9] + vector.acceleration_bias = set[:, i][9:12] + vector.gyro_bias = set[:, i][12:] + + W_i = vector - mean + + covariance_set += (1 / (2 * n + 1)) * np.outer(W_i, W_i) + + return covariance_set + + def cross_covariance_set( + self, + mean: np.ndarray, + set: np.ndarray, + mean_2: np.ndarray, + set_2: np.ndarray, + weight: np.ndarray, + ) -> np.ndarray: + """Calculate the cross covariance of a set of sigmapoints + + Args: + mean (np.ndarray): The mean of the set. + set (np.ndarray): The set of values. + mean_2 (np.ndarray): The mean of the second set. + set_2 (np.ndarray): The second set of values. + + Returns: + np.ndarray: The cross covariance of the set. """ - Calculate the covarince of a set of sigmapoints - + n_x = set.shape[0] + n_z = set_2.shape[0] + covariance_mat = np.zeros((n_x, n_z)) + + for i in range(2 * n_x + 1): + # parse the 15-dim error state + err_vec = set[:, i] # shape (15,) + W_i = err_vec - mean # shape (15,) + + # parse the 3-dim measurement + meas_vec = set_2[:, i] # shape (3,) + W_i_2 = meas_vec - mean_2 # shape (3,) + + # outer product -> shape (15,3) + covariance_mat += weight[i] * np.outer(W_i, W_i_2) + + return covariance_mat + + def weighted_covariance_set( + self, mean: np.ndarray, set: np.ndarray, weight: np.ndarray + ) -> np.ndarray: + """Calculate the covarince of a set of sigmapoints + Args: mean (np.ndarray): The mean of the set. set (np.ndarray): The set of values. - + Returns: np.ndarray: The covariance of the set. """ - n = set.shape[0] covariance_set = np.zeros((n, n)) - for i in range(2*n): + for i in range(2 * n + 1): vector = StateVector_euler() vector.position = set[:, i][:3] vector.velocity = set[:, i][3:6] @@ -146,38 +151,38 @@ def weighted_covariance_set(self, mean: np.ndarray, set: np.ndarray, weight: np. W_i = vector - mean covariance_set += weight[i] * np.outer(W_i, W_i) - - return covariance_set - + return covariance_set - def generate_sigma_points(self, error_state: StateVector_euler, Q_process_noise) -> tuple[list[StateVector_euler], np.ndarray]: - """ - Generates the sigma points for the UKF + def generate_sigma_points( + self, error_state: StateVector_euler, Q_process_noise + ) -> tuple[list[StateVector_euler], np.ndarray]: + """Generates the sigma points for the UKF This is done using the Cholesky decomposition method """ - # Define n n = len(error_state.covariance) kappa = 3 - n # Computing S matrix using cholensky decomposition + # print(error_state.covariance + Q_process_noise) S = np.linalg.cholesky(error_state.covariance + Q_process_noise) + # print(S) S_scaled = np.sqrt(n + kappa) * S - weighted_points = np.concatenate((S_scaled , -S_scaled), axis=1) + weighted_points = np.concatenate((S_scaled, -S_scaled), axis=1) sigma_points = [StateVector_euler() for _ in range(2 * n + 1)] sigma_points[0].fill_states(error_state.as_vector()) - for i in range(2*n): - sigma_points[i + 1].fill_states(error_state + weighted_points[:,i]) + for i in range(2 * n): + sigma_points[i + 1].fill_states(error_state + weighted_points[:, i]) - W = np.zeros(2*n + 1) + W = np.zeros(2 * n + 1) W[0] = kappa / (n + kappa) - for i in range(2*n): + for i in range(2 * n): W[i + 1] = 1 / (2 * (n + kappa)) return sigma_points, W @@ -214,7 +219,14 @@ def nominal_state_update( # Define the quaternion derivatives current_state_dot.orientation = 0.5 * quaternion_super_product( current_state.orientation, - np.array([0, imu_gyro[0] - current_state.gyro_bias[0], imu_gyro[1] - current_state.gyro_bias[1], imu_gyro[2] - current_state.gyro_bias[2]]), + np.array( + [ + 0, + imu_gyro[0] - current_state.gyro_bias[0], + imu_gyro[1] - current_state.gyro_bias[1], + imu_gyro[2] - current_state.gyro_bias[2], + ] + ), ) # Define the bias @@ -265,20 +277,24 @@ def error_state_update( next_error_state = A_d @ current_error_state.as_vector() return next_error_state - - def unscented_transform(self, sigma_points: list[StateVector_euler], current_state: StateVector_quaternion, - imu_reading: np.ndarray,) -> StateVector_euler: - """ - Performs the Unscented Transform + + def unscented_transform( + self, + sigma_points: list[StateVector_euler], + current_state: StateVector_quaternion, + imu_reading: np.ndarray, + ) -> StateVector_euler: + """Performs the Unscented Transform This is the corresponding to a preditction step in the EKF """ - n = len(sigma_points[0].as_vector()) - self.y_i = np.zeros((n, 2*n)) + self.y_i = np.zeros((n, 2 * n + 1)) - for i in range(2*n): - self.y_i[:, i] = self.error_state_update(sigma_points[i], current_state, imu_reading) + for i in range(2 * n + 1): + self.y_i[:, i] = self.error_state_update( + sigma_points[i], current_state, imu_reading + ) error_state_estimate = StateVector_euler() @@ -286,9 +302,9 @@ def unscented_transform(self, sigma_points: list[StateVector_euler], current_sta error_state_estimate.fill_states(x) error_state_estimate.covariance = self.covariance_set(x, self.y_i) - + return error_state_estimate - + def H(self) -> np.ndarray: """Calculates the measurement matrix. @@ -296,39 +312,83 @@ def H(self) -> np.ndarray: np.ndarray: The measurement matrix. """ # Define the measurement matrix - H = np.zeros((3, 15)) + H = np.zeros((3, 16)) # For now assume only velocity is measured - H[0:3, 3:6] = np.eye(3) + H[:, 3:6] = np.eye(3) return H - - def measurement_update(self, sigma_points: list[StateVector_euler], current_error_state: StateVector_euler, dvl_data: np.ndarray, Weight: np.ndarray) -> StateVector_euler: - """ - Updates the state vector with the DVL data + + def injection( + self, + current_state_nom: StateVector_quaternion, + current_state_error: StateVector_euler, + ) -> StateVector_quaternion: + """Injects the error state into the nominal state + + Args: + current_state_nom (StateVector_quaternion): The current nominal state + current_state_error (StateVector_euler): The current error state + + Returns: + StateVector_quaternion: The updated nominal state """ + inj_state = StateVector_quaternion() + inj_state.position = current_state_nom.position + current_state_error.position + inj_state.velocity = current_state_nom.velocity + current_state_error.velocity + inj_state.orientation = quaternion_super_product( + current_state_nom.orientation, + 0.5 + * np.array( + [ + 2, + current_state_error.orientation[0], + current_state_error.orientation[1], + current_state_error.orientation[2], + ] + ), + ) + inj_state.acceleration_bias = ( + current_state_nom.acceleration_bias + current_state_error.acceleration_bias + ) + inj_state.gyro_bias = ( + current_state_nom.gyro_bias + current_state_error.gyro_bias + ) + + return inj_state + + def measurement_update( + self, + sigma_points: list[StateVector_euler], + current_nom_state: StateVector_quaternion, + current_error_state: StateVector_euler, + dvl_data: np.ndarray, + Weight: np.ndarray, + ) -> StateVector_euler: + """Updates the state vector with the DVL data + """ H = self.H() R = self.R n = len(sigma_points[0].as_vector()) - Z_i = np.zeros((H.shape[0], 2 * n)) + Z_i = np.zeros((H.shape[0], 2 * n + 1)) + + for i in range(2 * n + 1): + injected_state = self.injection(current_nom_state, sigma_points[i]) + Z_i[:, i] = np.dot(H, injected_state.as_vector()) - for i in range(2*n): - Z_i[:, i] = np.dot(H, sigma_points[i].as_vector()) - z = self.weighted_mean_set(Z_i, Weight) S = self.weighted_covariance_set(z, Z_i, Weight) x = self.mean_set(self.y_i) - # Calculate the rest innovation = dvl_data - z P_innovation = S + R - P_xz = self.covariance_set(x, self.y_i, z, Z_i) + P_xz = self.cross_covariance_set(x, self.y_i, z, Z_i, Weight) # Kalman gain K_k = np.dot(P_xz, np.linalg.inv(P_innovation)) @@ -339,102 +399,99 @@ def measurement_update(self, sigma_points: list[StateVector_euler], current_erro updated_error_state.fill_states(x + np.dot(K_k, innovation)) # Update the covariance - updated_error_state.covariance = current_error_state.covariance - np.dot(K_k, np.dot(P_innovation, K_k.T)) + updated_error_state.covariance = current_error_state.covariance - np.dot( + K_k, np.dot(P_innovation, K_k.T) + ) - return updated_error_state + return updated_error_state + + def imu_update_states( + self, + current_state_nom: StateVector_quaternion, + current_state_error: StateVector_euler, + imu_data: np.ndarray, + ) -> tuple[StateVector_quaternion, StateVector_euler]: + """Updates the state vector with the IMU data - def imu_update_states(self, current_state_nom: StateVector_quaternion, current_state_error: StateVector_euler, imu_data: np.ndarray) -> tuple[StateVector_quaternion, StateVector_euler]: - """ - Updates the state vector with the IMU data - Args: current_state_nom (StateVector_quaternion): The current nominal state current_state_error (StateVector_euler): The current error state imu_data (np.ndarray): The IMU data - + Returns: tuple[StateVector_quaternion, StateVector_euler]: The updated nominal and error states """ - # Update the nominal state current_state_nom = self.nominal_state_update(current_state_nom, imu_data) # Generate the sigma points - sigma_points, _ = self.generate_sigma_points(current_state_error, self.Q_process_noise) + sigma_points, _ = self.generate_sigma_points( + current_state_error, self.Q_process_noise + ) # Update the error state - current_state_error = self.unscented_transform(sigma_points, current_state_nom, imu_data) + current_state_error = self.unscented_transform( + sigma_points, current_state_nom, imu_data + ) return current_state_nom, current_state_error - - def dvl_update_states(self, current_state_nom: StateVector_quaternion, current_state_error: StateVector_euler, dvl_data: np.ndarray) -> tuple[StateVector_quaternion, StateVector_euler]: - """ - Update the error state given the DVL data + + def dvl_update_states( + self, + current_state_nom: StateVector_quaternion, + current_state_error: StateVector_euler, + dvl_data: np.ndarray, + ) -> tuple[StateVector_quaternion, StateVector_euler]: + """Update the error state given the DVL data Args: current_state_nom (StateVector_quaternion): The current nominal state current_state_error (StateVector_euler): The current error state dvl_data (np.ndarray): The DVL data to update the state with - + Returns: tuple[StateVector_quaternion, StateVector_euler]: The updated nominal and error states """ - # Generate the sigma points - sigma_points, weight = self.generate_sigma_points(current_state_error, self.Q_process_noise) + sigma_points, weight = self.generate_sigma_points( + current_state_error, self.Q_process_noise + ) # Update the error state - current_state_error = self.measurement_update(sigma_points, current_state_error, dvl_data, weight) + current_state_error = self.measurement_update( + sigma_points, current_state_nom, current_state_error, dvl_data, weight + ) return current_state_nom, current_state_error - - def inject_and_reset(self, current_state_nom: StateVector_quaternion, current_state_error: StateVector_euler) -> tuple[StateVector_quaternion, StateVector_euler]: - """ - Injects the error state into the nominal state and resets the error state + + def inject_and_reset( + self, + current_state_nom: StateVector_quaternion, + current_state_error: StateVector_euler, + ) -> tuple[StateVector_quaternion, StateVector_euler]: + """Injects the error state into the nominal state and resets the error state Args: current_state_nom (StateVector_quaternion): The current nominal state current_state_error (StateVector_euler): The current error state - - Returns: + + Returns: tuple[StateVector_quaternion, StateVector_euler]: The updated nominal and error states """ + inj_state = self.injection(current_state_nom, current_state_error) - inj_state = StateVector_quaternion() - - inj_state.position = current_state_nom.position + current_state_error.position - inj_state.velocity = current_state_nom.velocity + current_state_error.velocity - inj_state.orientation = quaternion_super_product( - current_state_nom.orientation, - 0.5 - * np.array( - [ - 2, - current_state_error.orientation[0], - current_state_error.orientation[1], - current_state_error.orientation[2], - ] - ), - ) - inj_state.acceleration_bias = ( - current_state_nom.acceleration_bias + current_state_error.acceleration_bias - ) - inj_state.gyro_bias = current_state_nom.gyro_bias + current_state_error.gyro_bias - - - # Resetting the error state G = np.eye(15) - G[6:9, 6:9] = np.eye(3) - skew_symmetric( - 0.5 * current_state_error.orientation - ) + G[6:9, 6:9] = np.eye(3) - skew_symmetric(0.5 * current_state_error.orientation) current_state_error.covariance = np.dot( np.dot(G, current_state_error.covariance), G.T ) + current_state_error.covariance += np.eye(15) * 1e-4 + + eigvals = np.linalg.eigvals(current_state_error.covariance) + print("Min eigenvalue:", np.min(eigvals)) current_state_error.fill_states(np.zeros(15)) - return inj_state, current_state_error - diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py index 629ce460e..b9a76e26f 100644 --- a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py +++ b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py @@ -1,6 +1,13 @@ -import numpy as np from dataclasses import dataclass, field -from sp_ukf_python_utils import quaternion_super_product, quaternion_error, euler_rotation_quaternion, ssa + +import numpy as np +from sp_ukf_python_utils import ( + euler_rotation_quaternion, + quaternion_error, + quaternion_super_product, + ssa, +) + @dataclass class StateVector_quaternion: @@ -48,7 +55,7 @@ def fill_states(self, state: np.ndarray) -> None: self.orientation = state[6:10] self.acceleration_bias = state[10:13] self.gyro_bias = state[13:] - else: + else: self.position = state[0:3] self.velocity = state[3:6] self.orientation = euler_rotation_quaternion(state[6:9]) @@ -103,7 +110,7 @@ def euler_forward( new_state.orientation /= np.linalg.norm(new_state.orientation) return new_state - + def __sub__(self, other: 'StateVector_quaternion') -> np.ndarray: """Subtracts two StateVector_quaternion objects. @@ -128,7 +135,7 @@ def __sub__(self, other: 'StateVector_quaternion') -> np.ndarray: gyro_bias_diff, ] ) - + def __add__(self, other: 'np.ndarray') -> 'np.ndarray': """Adds a numpy array to this StateVector_quaternion. @@ -229,7 +236,6 @@ def __add__(self, other: 'np.ndarray') -> 'np.ndarray': Returns: np.ndarray: The result of the addition. """ - new_position = self.position + other[:3] new_velcoity = self.velocity + other[3:6] new_orientation = self.orientation + other[6:9] @@ -247,9 +253,8 @@ def __add__(self, other: 'np.ndarray') -> 'np.ndarray': ) def __sub__(self, other_state: 'StateVector_euler') -> 'StateVector_euler': - """ - Subtracts two StateVector_euler objects. - + """Subtracts two StateVector_euler objects. + Args: other (StateVector_euler): The other StateVector_euler object. @@ -263,7 +268,13 @@ def __sub__(self, other_state: 'StateVector_euler') -> 'StateVector_euler': gyro_bias_diff = self.gyro_bias - other_state[12:] return np.concatenate( - (position_diff, velocity_diff, orientation_diff, acceleration_bias_diff, gyro_bias_diff) + [ + position_diff, + velocity_diff, + orientation_diff, + acceleration_bias_diff, + gyro_bias_diff, + ] ) @@ -277,4 +288,4 @@ class MeasurementModel: ) # Measurement matrix measurement_covariance: np.ndarray = field( default_factory=lambda: np.zeros((6, 6)) - ) # Measurement noise matrix \ No newline at end of file + ) # Measurement noise matrix diff --git a/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py b/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py index 59e08aa55..d46962797 100644 --- a/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py +++ b/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py @@ -1,45 +1,78 @@ -import numpy as np import matplotlib.pyplot as plt -from mpl_toolkits.mplot3d import Axes3D # for 3D plotting +import numpy as np # (Assuming the following have been imported from your modules) -from sp_ukf_python_class import StateVector_quaternion, StateVector_euler -from sp_ukf_python_utils import skew_symmetric, quaternion_super_product +from sp_ukf_python_class import StateVector_euler, StateVector_quaternion + from sp_ukf_python import ErrorStateUnscentedKalmanFilter + def quat_to_yaw(q: np.ndarray) -> float: - """ - Convert a quaternion (assumed [w, x, y, z]) with zero roll and pitch - into a yaw angle. + """Convert a quaternion (assumed [w, x, y, z]) into a yaw angle. + In NED, yaw is typically around the z-down axis. """ return 2 * np.arctan2(q[3], q[0]) + def run_ESUKF_simulation(): + # ------------------------------------------------------------------------- # Simulation parameters - dt = 0.01 # time step [s] - T = 60.0 # total simulation time [s] - num_steps = int(T/dt) - g_val = 9.81 # gravitational acceleration + # ------------------------------------------------------------------------- + dt = 0.01 # time step [s] + T = 60.0 # total simulation time [s] + num_steps = int(T / dt) + # In an NED frame, gravity is +9.81 in the z (down) direction. + g_val = 9.81 + + # ------------------------------------------------------------------------- # Define noise and covariance matrices - Q = np.diag([0.1]*15) # Process noise covariance (15x15) - R_meas = np.diag([0.08]*3) # DVL measurement noise (velocity noise) - P_ab = 0.005 # Accelerometer bias dynamics matrix - P_wb = 0.005 # Gyro bias dynamics matrix - lever_arm = np.array([0.0, 0.0, 0.0]) # Assume sensor is at the center of mass + # ------------------------------------------------------------------------- + Q = np.diag( + [ + 0.06, + 0.06, + 0.06, # position error + 0.04, + 0.04, + 0.04, # velocity error + 0.003, + 0.003, + 0.003, # orientation error + 0.02, + 0.02, + 0.02, # accelerometer bias error + 0.02, + 0.02, + 0.02, # gyro bias error + ] + ) + + R_meas = np.diag([0.52, 0.52, 0.52]) # Increased DVL measurement noise - # Create ESUKF instance + # Bias dynamics tuning remains the same here: + P_ab = 0.002 + P_wb = 0.002 + lever_arm = np.array([0.0, 0.0, 0.0]) # Sensor at the vehicle CG + + # Create the Error-State UKF instance (NED convention) esukf = ErrorStateUnscentedKalmanFilter(P_ab, P_wb, Q, lever_arm, R_meas, g_val, dt) - # Initialize true state (StateVector_quaternion) with no biases. + # ------------------------------------------------------------------------- + # Initialize the true state in NED + # ------------------------------------------------------------------------- + # We treat x as North, y as East, z as Down. + # We'll do a circular path in the horizontal plane (z=0). true_state = StateVector_quaternion() - true_state.position = np.array([20.0, 0.0, 0.0]) - true_state.velocity = np.array([0.0, 1.0, 0.0]) + true_state.position = np.array([20.0, 0.0, 0.0]) # [N, E, D]=[20, 0, 0] + true_state.velocity = np.array([0.0, 1.0, 0.0]) # 1 m/s in the East direction true_state.orientation = np.array([1.0, 0.0, 0.0, 0.0]) # No initial rotation true_state.acceleration_bias = np.zeros(3) true_state.gyro_bias = np.zeros(3) - # Initialize estimated (nominal) state with a small offset. + # ------------------------------------------------------------------------- + # Initialize the estimated state + # ------------------------------------------------------------------------- est_state_nom = StateVector_quaternion() est_state_nom.position = true_state.position + np.array([0.1, -0.1, 0.05]) est_state_nom.velocity = true_state.velocity + np.array([0.05, 0.05, -0.05]) @@ -47,12 +80,14 @@ def run_ESUKF_simulation(): est_state_nom.acceleration_bias = np.zeros(3) est_state_nom.gyro_bias = np.zeros(3) - # Initialize error state (StateVector_euler) as zero with some initial covariance. + # Initialize error state (Euler) with some covariance est_state_error = StateVector_euler() est_state_error.fill_states(np.zeros(15)) - est_state_error.covariance = 0.1 * np.eye(15) + est_state_error.covariance = 0.5 * np.eye(15) + # ------------------------------------------------------------------------- # Prepare histories for plotting + # ------------------------------------------------------------------------- time_hist = [] true_pos_hist = [] est_pos_hist = [] @@ -61,67 +96,110 @@ def run_ESUKF_simulation(): true_yaw_hist = [] est_yaw_hist = [] - # For the true trajectory, we simulate a circle in the horizontal plane. - R_circle = 20.0 # circle radius [m] - omega = 0.05 # angular speed [rad/s] + # ------------------------------------------------------------------------- + # Define the "circular" trajectory in the horizontal plane (z=0) + # in NED: x=North, y=East, z=Down + # We'll revolve in the XY-plane, at D=0, with radius=20 m, angular speed=0.05 rad/s + # ------------------------------------------------------------------------- + R_circle = 20.0 + omega = 0.05 + # ------------------------------------------------------------------------- + # Main simulation loop + # ------------------------------------------------------------------------- t = 0.0 for step in range(num_steps): - # --- True State Generation --- - # Circular trajectory: position = [R*cos(omega*t), R*sin(omega*t), 0] - pos_true = np.array([R_circle * np.cos(omega * t), - R_circle * np.sin(omega * t), - 0.0]) - # Velocity is the derivative of position. - vel_true = np.array([-R_circle * omega * np.sin(omega * t), - R_circle * omega * np.cos(omega * t), - 0.0]) - # Acceleration is the second derivative. - acc_true = np.array([-R_circle * omega**2 * np.cos(omega * t), - -R_circle * omega**2 * np.sin(omega * t), - 0.0]) - # Update the true state. + # --- True State Generation (NED) --- + # Position: circle in x-y plane at z=0 + pos_true = np.array( + [ + R_circle * np.cos(omega * t), # N + R_circle * np.sin(omega * t), # E + 0.0, # D + ] + ) + # Velocity: derivative of pos + vel_true = np.array( + [ + -R_circle * omega * np.sin(omega * t), # d/dt of cos => -sin + R_circle * omega * np.cos(omega * t), # d/dt of sin => cos + 0.0, + ] + ) + # Acceleration: second derivative + acc_true = np.array( + [ + -R_circle * omega**2 * np.cos(omega * t), + -R_circle * omega**2 * np.sin(omega * t), + 0.0, + ] + ) + + # Update the "true" state in NED true_state.position = pos_true true_state.velocity = vel_true - # Compute heading (yaw) tangent to the path. + + # Compute full quaternion from Euler angles (roll, pitch, yaw) + roll_true = 0.0 + pitch_true = 0.0 yaw_true = np.arctan2(vel_true[1], vel_true[0]) - # For simplicity, assume roll and pitch are zero. - true_state.orientation = np.array([np.cos(yaw_true/2), 0.0, 0.0, np.sin(yaw_true/2)]) - # Biases remain zero for the true state. - - # --- Simulated IMU Measurements --- - # The nominal state propagation uses: - # velocity_dot = R_q() @ (imu_acc - bias) + g - # Therefore, the ideal accelerometer measurement is: - # imu_acc = R_true.T @ (acc_true - g_vector) - R_true = true_state.R_q() # rotation matrix from quaternion - imu_acc_ideal = np.dot(R_true.T, (acc_true - np.array([0.0, 0.0, g_val]))) - # Add noise (e.g., 0.1 m/s^2 std dev). - imu_acc_noise = np.random.normal(0.0, 0.1, 3) + cy = np.cos(yaw_true * 0.5) + sy = np.sin(yaw_true * 0.5) + cp = np.cos(pitch_true * 0.5) + sp = np.sin(pitch_true * 0.5) + cr = np.cos(roll_true * 0.5) + sr = np.sin(roll_true * 0.5) + true_state.orientation = np.array( + [ + cr * cp * cy + sr * sp * sy, # w + sr * cp * cy - cr * sp * sy, # x + cr * sp * cy + sr * cp * sy, # y + cr * cp * sy - sr * sp * cy, # z + ] + ) + + # --- Simulated IMU Measurements (NED) --- + # Gravity is +9.81 in the down (z) direction in NED + R_true = true_state.R_q() # rotation from body to inertial + # The "specific force" in body frame is (acc_inertial - gravity_inertial) rotated to body + imu_acc_ideal = R_true.T @ ( + acc_true - np.array([0.0, 0.0, g_val]) + ) + np.random.normal(0.01, 0.01, 3) # [rad/s] + + # Add small noise + imu_acc_noise = np.random.normal(0.0, 0.05, 3) # [m/s^2] imu_acc_meas = imu_acc_ideal + imu_acc_noise - # For the gyro: the true angular velocity in body frame. - # For a circular path with constant yaw rate, the ideal gyro reading is: - imu_gyro_ideal = np.array([0.0, 0.0, omega]) - # Add noise (e.g., 0.01 rad/s std dev). - imu_gyro_noise = np.random.normal(0.0, 0.01, 3) + # Gyro: angular velocity about body axes. Yaw rate is ~omega for a flat circle + imu_gyro_ideal = np.array([0.0, 0.0, omega]) + np.random.normal( + 0.01, 0.01, 3 + ) # [rad/s] + imu_gyro_noise = np.random.normal(0.0, 0.05, 3) # [rad/s] imu_gyro_meas = imu_gyro_ideal + imu_gyro_noise - # Combine to form the complete IMU measurement vector. + # Combine imu_meas = np.hstack((imu_acc_meas, imu_gyro_meas)) # --- Simulated DVL Measurement --- - # DVL measures velocity (here assumed in the inertial frame). + # Velocity in inertial frame (NED) with zero noise for this test dvl_noise = np.random.normal(0.0, 0.05, 3) dvl_meas = vel_true + dvl_noise - # --- Filter Updates --- - # 1. Propagate the nominal state with IMU data. - est_state_nom, est_state_error = esukf.imu_update_states(est_state_nom, est_state_error, imu_meas) - # 2. Incorporate DVL measurement. - est_state_nom, est_state_error = esukf.dvl_update_states(est_state_nom, est_state_error, dvl_meas) - # 3. Inject the error state into the nominal state and reset the error state. - est_state_nom, est_state_error = esukf.inject_and_reset(est_state_nom, est_state_error) + # --------------------------------------------------------------------- + # Filter Updates + # --------------------------------------------------------------------- + # 1. IMU update (prediction) + est_state_nom, est_state_error = esukf.imu_update_states( + est_state_nom, est_state_error, imu_meas + ) + # 2. DVL update (measurement) + est_state_nom, est_state_error = esukf.dvl_update_states( + est_state_nom, est_state_error, dvl_meas + ) + # 3. Inject error state + est_state_nom, est_state_error = esukf.inject_and_reset( + est_state_nom, est_state_error + ) # --- Store Histories --- time_hist.append(t) @@ -134,7 +212,9 @@ def run_ESUKF_simulation(): t += dt - # Convert histories to NumPy arrays. + # ------------------------------------------------------------------------- + # Convert histories to arrays + # ------------------------------------------------------------------------- true_pos_hist = np.array(true_pos_hist) est_pos_hist = np.array(est_pos_hist) true_vel_hist = np.array(true_vel_hist) @@ -143,76 +223,91 @@ def run_ESUKF_simulation(): est_yaw_hist = np.array(est_yaw_hist) time_hist = np.array(time_hist) - # --- Plotting Results --- - - # Plot positions (each axis separately) + # ------------------------------------------------------------------------- + # Plotting + # ------------------------------------------------------------------------- + # Positions plt.figure(figsize=(10, 8)) plt.subplot(3, 1, 1) - plt.plot(time_hist, true_pos_hist[:, 0], label='True X') - plt.plot(time_hist, est_pos_hist[:, 0], '--', label='Estimated X') - plt.ylabel('X Position (m)') + plt.plot(time_hist, true_pos_hist[:, 0], label='True N') + plt.plot(time_hist, est_pos_hist[:, 0], '--', label='Estimated N') + plt.ylabel('N (m)') plt.legend() plt.subplot(3, 1, 2) - plt.plot(time_hist, true_pos_hist[:, 1], label='True Y') - plt.plot(time_hist, est_pos_hist[:, 1], '--', label='Estimated Y') - plt.ylabel('Y Position (m)') + plt.plot(time_hist, true_pos_hist[:, 1], label='True E') + plt.plot(time_hist, est_pos_hist[:, 1], '--', label='Estimated E') + plt.ylabel('E (m)') plt.legend() plt.subplot(3, 1, 3) - plt.plot(time_hist, true_pos_hist[:, 2], label='True Z') - plt.plot(time_hist, est_pos_hist[:, 2], '--', label='Estimated Z') + plt.plot(time_hist, true_pos_hist[:, 2], label='True D') + plt.plot(time_hist, est_pos_hist[:, 2], '--', label='Estimated D') plt.xlabel('Time (s)') - plt.ylabel('Z Position (m)') + plt.ylabel('D (m)') plt.legend() plt.tight_layout() plt.show() - # Plot velocities + # Velocities plt.figure(figsize=(10, 8)) plt.subplot(3, 1, 1) - plt.plot(time_hist, true_vel_hist[:, 0], label='True Vx') - plt.plot(time_hist, est_vel_hist[:, 0], '--', label='Estimated Vx') - plt.ylabel('Vx (m/s)') + plt.plot(time_hist, true_vel_hist[:, 0], label='True Vn') + plt.plot(time_hist, est_vel_hist[:, 0], '--', label='Estimated Vn') + plt.ylabel('Vn (m/s)') plt.legend() plt.subplot(3, 1, 2) - plt.plot(time_hist, true_vel_hist[:, 1], label='True Vy') - plt.plot(time_hist, est_vel_hist[:, 1], '--', label='Estimated Vy') - plt.ylabel('Vy (m/s)') + plt.plot(time_hist, true_vel_hist[:, 1], label='True Ve') + plt.plot(time_hist, est_vel_hist[:, 1], '--', label='Estimated Ve') + plt.ylabel('Ve (m/s)') plt.legend() plt.subplot(3, 1, 3) - plt.plot(time_hist, true_vel_hist[:, 2], label='True Vz') - plt.plot(time_hist, est_vel_hist[:, 2], '--', label='Estimated Vz') + plt.plot(time_hist, true_vel_hist[:, 2], label='True Vd') + plt.plot(time_hist, est_vel_hist[:, 2], '--', label='Estimated Vd') plt.xlabel('Time (s)') - plt.ylabel('Vz (m/s)') + plt.ylabel('Vd (m/s)') plt.legend() plt.tight_layout() plt.show() - # Plot heading (yaw) + # Heading (Yaw) plt.figure(figsize=(10, 4)) plt.plot(time_hist, np.degrees(true_yaw_hist), label='True Yaw') plt.plot(time_hist, np.degrees(est_yaw_hist), '--', label='Estimated Yaw') plt.xlabel('Time (s)') plt.ylabel('Yaw (deg)') plt.legend() - plt.title('Heading Comparison') + plt.title('Heading Comparison (NED)') plt.tight_layout() plt.show() - # Plot 3D Trajectory + # 3D Trajectory fig = plt.figure(figsize=(8, 6)) ax = fig.add_subplot(111, projection='3d') - ax.plot(true_pos_hist[:, 0], true_pos_hist[:, 1], true_pos_hist[:, 2], label='True Trajectory', linewidth=2) - ax.plot(est_pos_hist[:, 0], est_pos_hist[:, 1], est_pos_hist[:, 2], '--', label='Estimated Trajectory', linewidth=2) - ax.set_xlabel('X (m)') - ax.set_ylabel('Y (m)') - ax.set_zlabel('Z (m)') + ax.plot( + true_pos_hist[:, 0], + true_pos_hist[:, 1], + true_pos_hist[:, 2], + label='True Trajectory', + linewidth=2, + ) + ax.plot( + est_pos_hist[:, 0], + est_pos_hist[:, 1], + est_pos_hist[:, 2], + '--', + label='Estimated Trajectory', + linewidth=2, + ) + ax.set_xlabel('North (m)') + ax.set_ylabel('East (m)') + ax.set_zlabel('Down (m)') ax.legend() - plt.title('3D Trajectory') + plt.title('3D Trajectory (NED Frame)') plt.show() + if __name__ == '__main__': run_ESUKF_simulation() From 52bdaebd23f76be7c0ce0d22cbf013e48c141c9f Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Sun, 9 Mar 2025 01:32:46 +0100 Subject: [PATCH 05/30] feat: working ukf filter is added, some issue in the ESUKF --- .../sp_ukf_python/sp_ukf_python.py | 40 +- .../sp_ukf_python/sp_ukf_python_class.py | 3 +- .../sp_ukf_python/sp_ukf_python_utils.py | 11 +- .../sp_ukf_python/sp_ukf_python/test_ukf.py | 2 +- navigation/ukf_okid/ukf_python/__ini__.py | 0 navigation/ukf_okid/ukf_python/ukf_okid.py | 376 ++++++++++++ .../ukf_python/ukf_okid_class copy.py | 568 ++++++++++++++++++ .../ukf_okid/ukf_python/ukf_okid_class.py | 464 ++++++++++++++ navigation/ukf_okid/ukf_python/ukf_utils.py | 36 ++ 9 files changed, 1476 insertions(+), 24 deletions(-) create mode 100644 navigation/ukf_okid/ukf_python/__ini__.py create mode 100644 navigation/ukf_okid/ukf_python/ukf_okid.py create mode 100644 navigation/ukf_okid/ukf_python/ukf_okid_class copy.py create mode 100644 navigation/ukf_okid/ukf_python/ukf_okid_class.py create mode 100644 navigation/ukf_okid/ukf_python/ukf_utils.py diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py index 8d2ff6265..819cb737d 100644 --- a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py +++ b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py @@ -24,6 +24,7 @@ def __init__( self.g = np.array([0, 0, g]) self.dt = dt self.y_i = np.zeros((15, 2 * 15)) + self.W = np.zeros(2 * 15 + 1) def mean_set(self, set: np.ndarray) -> np.ndarray: """Calculates the mean of a set of values. @@ -34,11 +35,12 @@ def mean_set(self, set: np.ndarray) -> np.ndarray: Returns: np.ndarray: The mean of the set. """ - # Define the number of columns + # Define the number of sigma points based on columns n = set.shape[0] + mean_value = np.zeros(n) - # Calculate the mean value - mean_value = (1 / (2 * n)) * np.sum(set, axis=1) + for i in range(2 * n + 1): + mean_value += (1/(2 * n + 1)) * set[:, i] return mean_value @@ -58,8 +60,6 @@ def weighted_mean_set(self, set: np.ndarray, weight: np.ndarray) -> np.ndarray: for i in range(2 * n + 1): mean_value += weight[i] * set[:, i] - mean_value = (1 / (2 * n + 1)) * mean_value - return mean_value def covariance_set(self, mean: np.ndarray, set: np.ndarray) -> np.ndarray: @@ -160,31 +160,26 @@ def generate_sigma_points( """Generates the sigma points for the UKF This is done using the Cholesky decomposition method """ - # Define n n = len(error_state.covariance) kappa = 3 - n - # Computing S matrix using cholensky decomposition - # print(error_state.covariance + Q_process_noise) S = np.linalg.cholesky(error_state.covariance + Q_process_noise) - # print(S) S_scaled = np.sqrt(n + kappa) * S weighted_points = np.concatenate((S_scaled, -S_scaled), axis=1) sigma_points = [StateVector_euler() for _ in range(2 * n + 1)] + W = np.zeros(2 * n + 1) sigma_points[0].fill_states(error_state.as_vector()) - for i in range(2 * n): - sigma_points[i + 1].fill_states(error_state + weighted_points[:, i]) - - W = np.zeros(2 * n + 1) W[0] = kappa / (n + kappa) for i in range(2 * n): + sigma_points[i + 1].fill_states(error_state + weighted_points[:, i]) W[i + 1] = 1 / (2 * (n + kappa)) + self.W = W return sigma_points, W def nominal_state_update( @@ -298,10 +293,10 @@ def unscented_transform( error_state_estimate = StateVector_euler() - x = self.mean_set(self.y_i) + x = self.weighted_mean_set(self.y_i, self.W) error_state_estimate.fill_states(x) - error_state_estimate.covariance = self.covariance_set(x, self.y_i) + error_state_estimate.covariance = self.weighted_covariance_set(x, self.y_i, self.W) return error_state_estimate @@ -311,10 +306,10 @@ def H(self) -> np.ndarray: Returns: np.ndarray: The measurement matrix. """ - # Define the measurement matrix + # Define the measurement matrix (error state is 15-dim) H = np.zeros((3, 16)) - # For now assume only velocity is measured + # For now assume only velocity is measured (located at indices 3:6) H[:, 3:6] = np.eye(3) return H @@ -442,6 +437,7 @@ def dvl_update_states( current_state_nom: StateVector_quaternion, current_state_error: StateVector_euler, dvl_data: np.ndarray, + imu_data: np.ndarray, ) -> tuple[StateVector_quaternion, StateVector_euler]: """Update the error state given the DVL data @@ -458,6 +454,11 @@ def dvl_update_states( current_state_error, self.Q_process_noise ) + # Update the error state + current_state_error = self.unscented_transform( + sigma_points, current_state_nom, imu_data + ) + # Update the error state current_state_error = self.measurement_update( sigma_points, current_state_nom, current_state_error, dvl_data, weight @@ -487,10 +488,7 @@ def inject_and_reset( current_state_error.covariance = np.dot( np.dot(G, current_state_error.covariance), G.T ) - current_state_error.covariance += np.eye(15) * 1e-4 - - eigvals = np.linalg.eigvals(current_state_error.covariance) - print("Min eigenvalue:", np.min(eigvals)) + current_state_error.covariance += np.eye(15) current_state_error.fill_states(np.zeros(15)) diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py index b9a76e26f..f8ede884d 100644 --- a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py +++ b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py @@ -6,6 +6,7 @@ quaternion_error, quaternion_super_product, ssa, + quat_norm, ) @@ -100,7 +101,7 @@ def euler_forward( # Define the state derivatives new_state.position = current_state.position + self.position * dt new_state.velocity = current_state.velocity + self.velocity * dt - new_state.orientation = current_state.orientation + self.orientation * dt + new_state.orientation = quat_norm(current_state.orientation + self.orientation * dt) new_state.acceleration_bias = ( current_state.acceleration_bias + self.acceleration_bias * dt ) diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_utils.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_utils.py index 071180fc7..56285f031 100644 --- a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_utils.py +++ b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_utils.py @@ -104,4 +104,13 @@ def ssa(angle: np.ndarray) -> np.ndarray: for i in range(len(angle)): ssa_vector[i] = (angle[i] + np.pi) % (2 * np.pi) - np.pi - return ssa_vector \ No newline at end of file + return ssa_vector + +def quat_norm(quat: np.ndarray) -> np.ndarray: + """ + Function that normalizes a quaternion + """ + + quat = quat / np.linalg.norm(quat) + + return quat diff --git a/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py b/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py index d46962797..1d8c723b1 100644 --- a/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py +++ b/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py @@ -194,7 +194,7 @@ def run_ESUKF_simulation(): ) # 2. DVL update (measurement) est_state_nom, est_state_error = esukf.dvl_update_states( - est_state_nom, est_state_error, dvl_meas + est_state_nom, est_state_error, dvl_meas, imu_meas ) # 3. Inject error state est_state_nom, est_state_error = esukf.inject_and_reset( diff --git a/navigation/ukf_okid/ukf_python/__ini__.py b/navigation/ukf_okid/ukf_python/__ini__.py new file mode 100644 index 000000000..e69de29bb diff --git a/navigation/ukf_okid/ukf_python/ukf_okid.py b/navigation/ukf_okid/ukf_python/ukf_okid.py new file mode 100644 index 000000000..c588d579e --- /dev/null +++ b/navigation/ukf_okid/ukf_python/ukf_okid.py @@ -0,0 +1,376 @@ +from ukf_okid_class import * +import numpy as np +import time +import matplotlib.pyplot as plt + + +class UKF: + def __init__(self, process_model: process_model, x_0, P_0, Q, R): + self.x = x_0 + self.P = P_0 + self.Q = Q + self.R = R + self.process_model = process_model + self.sigma_points_list = None + self.y_i = None + self.weight = None + + def sigma_points(self, current_state: StateQuat) -> tuple[list[StateQuat], np.ndarray]: + """ + Functions that generate the sigma points for the UKF + """ + n = len(current_state.covariance) + kappa = 3 - n + + S = np.linalg.cholesky(current_state.covariance + self.Q) + S_scaled = np.sqrt(n + kappa) * S + + weighted_points = np.concatenate([S_scaled, -S_scaled], axis=1) + + self.sigma_points_list = [StateQuat() for _ in range(2 * n + 1)] + W = np.zeros(2 * n + 1) + + self.sigma_points_list [0].fill_states(current_state.as_vector()) + W[0] = kappa / (n + kappa) + for i in range(2 * n): + self.sigma_points_list [i + 1].fill_states(current_state.insert_weights(weighted_points[:, i])) + W[i + 1] = 1 / (2 * (n + kappa)) + + self.weight = W + + return self.sigma_points_list , self.weight + + + def unscented_transform(self, current_state: StateQuat) -> StateQuat: + """ + The unscented transform function generates the priori state estimate + """ + + _ , _ = self.sigma_points(current_state) + n = len(current_state.covariance) + + self.y_i = [StateQuat() for _ in range(2 * n + 1)] + + for i in range(2 * n + 1): + self.process_model.model_prediction(self.sigma_points_list[i]) + self.y_i[i] = self.process_model.euler_forward() + + state_estimate = StateQuat() + x = mean_set(self.y_i, self.weight) + + state_estimate.fill_states(x) + state_estimate.covariance = covariance_set(self.y_i, x, self.weight) + return state_estimate + + def measurement_update(self, current_state: StateQuat, measurement: MeasModel) -> tuple[MeasModel, np.ndarray]: + """ + Function that updates the state estimate with a measurement + Hopefully this is the DVL or GNSS + """ + + n = len(current_state.covariance) + z_i = [MeasModel() for _ in range(2 * n + 1)] + + for i in range(2 * n + 1): + z_i[i] = measurement.H(self.sigma_points_list[i]) + + meas_update = MeasModel() + + meas_update.measurement = mean_measurement(z_i, self.weight) + + meas_update.covariance = covariance_measurement(z_i, meas_update.measurement, self.weight) + + cross_correlation = cross_covariance(self.y_i, current_state.as_vector(), z_i, meas_update.measurement, self.weight) + + return meas_update, cross_correlation + + def posteriori_estimate(self, current_state: StateQuat, cross_correlation: np.ndarray, measurement: MeasModel, ex_measuremnt: MeasModel) -> StateQuat: + """ + Calculates the posteriori estimate using measurment and the prior estimate + """ + + nu_k = MeasModel() + + nu_k.measurement = measurement.measurement - ex_measuremnt.measurement + nu_k.covariance = ex_measuremnt.covariance + measurement.covariance + + K_k = np.dot(cross_correlation, np.linalg.inv(nu_k.covariance)) + + posteriori_estimate = StateQuat() + + posteriori_estimate.fill_states_different_dim(current_state.as_vector(), np.dot(K_k, nu_k.measurement)) + posteriori_estimate.covariance = current_state.covariance - np.dot(K_k, np.dot(nu_k.covariance, np.transpose(K_k))) + + self.process_model.state_vector_prev = posteriori_estimate + + return posteriori_estimate + +def add_quaternion_noise(q, noise_std): + + noise = np.random.normal(0, noise_std, 3) + + theta = np.linalg.norm(noise) + + if theta > 0: + + axis = noise / theta + + q_noise = np.hstack((np.cos(theta/2), np.sin(theta/2) * axis)) + + else: + + q_noise = np.array([1.0, 0.0, 0.0, 0.0]) + + q_new = quaternion_super_product(q, q_noise) + + return q_new / np.linalg.norm(q_new) + + +if __name__ == '__main__': + + # Create initial state vector and covariance matrix. + x0 = np.zeros(13) + x0[0:3] = [0.3, 0.3, 0.3] + x0[3] = 1 + x0[7:10] = [0.2, 0.2, 0.2] + dt = 0.01 + R = (0.1 / dt) * np.eye(3) + + Q = 0.1 * np.eye(12) + P0 = np.eye(12) * 0.1 + + model = process_model() + model.dt = 0.01 + model.mass_interia_matrix = np.array([ + [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] + ]) + model.m = 30.0 + model.r_b_bg = np.array([0.01, 0.0, 0.02]) + model.inertia = np.diag([0.68, 3.32, 3.34]) + model.damping_linear = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) + model.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) + model.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) + + model_ukf = model + + # Simulation parameters + simulation_time = 40 # seconds + num_steps = int(simulation_time / dt) + + # Initialize a dummy StateQuat. + test_state = StateQuat() + test_state.fill_states(x0) + test_state.covariance = P0 + + # Initialize a estimated state + estimated_state = StateQuat() + estimated_state.fill_states(x0) + estimated_state.covariance = P0 + + # Initialize a estimated state + noisy_state = StateQuat() + noisy_state.fill_states(x0) + noisy_state.covariance = P0 + + measurment_model = MeasModel() + measurment_model.measurement = np.array([0.0, 0.0, 0.0]) + measurment_model.covariance = R + + # Initialize arrays to store the results + positions = np.zeros((num_steps, 3)) + orientations = np.zeros((num_steps, 3)) + velocities = np.zeros((num_steps, 3)) + angular_velocities = np.zeros((num_steps, 3)) + + # Initialize arrays to store the estimates + positions_est = np.zeros((num_steps, 3)) + orientations_est = np.zeros((num_steps, 3)) + velocities_est = np.zeros((num_steps, 3)) + angular_velocities_est = np.zeros((num_steps, 3)) + + # Initialize the okid params + okid_params = np.zeros((num_steps, 21)) + + model.state_vector_prev = test_state + model.state_vector = test_state + + model_ukf.state_vector_prev = test_state + model_ukf.state_vector = test_state + + # initialize the ukf + ukf = UKF(model_ukf, x0, P0, Q, R) + + # Test + ukf.unscented_transform(test_state) + + elapsed_times = [] + + u = lambda t: np.array([2 * np.sin(1 * t), 2 * np.sin(1 * t), 2 * np.sin(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t)]) + + # Run the simulation + for step in range(num_steps): + # Insert control input + model.Control_input = u(step * dt) + model_ukf.Control_input = u(step * dt) + + # Perform the unscented transform + model.model_prediction(test_state) + new_state = model.euler_forward() + + # Adding noise in the state vector + noisy_state.position = new_state.position + np.random.normal(0, 0.1, 3) + noisy_state.orientation = add_quaternion_noise(new_state.orientation, 0.1) + noisy_state.velocity = new_state.velocity + np.random.normal(0, 0.1, 3) + noisy_state.angular_velocity = new_state.angular_velocity + np.random.normal(0, 0.1, 3) + + start_time = time.time() + estimated_state = ukf.unscented_transform(noisy_state) + elapsed_time = time.time() - start_time + elapsed_times.append(elapsed_time) + + if step % 20 == 0: + measurment_model.measurement = new_state.velocity + np.random.normal(0, 0.2, 3) + meas_update, covariance_matrix = ukf.measurement_update(estimated_state, measurment_model) + estimated_state = ukf.posteriori_estimate(estimated_state, covariance_matrix, measurment_model, meas_update) + + + positions[step, :] = new_state.position + orientations[step, :] = quat_to_euler(new_state.orientation) + velocities[step, :] = new_state.velocity + angular_velocities[step, :] = new_state.angular_velocity + + positions_est[step, :] = estimated_state.position + orientations_est[step, :] = quat_to_euler(estimated_state.orientation) + velocities_est[step, :] = estimated_state.velocity + angular_velocities_est[step, :] = estimated_state.angular_velocity + + # Update the state for the next iteration + model.state_vector_prev = new_state + + print('Average elapsed time: ', np.mean(elapsed_times)) + print('Max elapsed time: ', np.max(elapsed_times)) + print('Min elapsed time: ', np.min(elapsed_times)) + print('median elapsed time: ', np.median(elapsed_times)) + # Plot the results + time = np.linspace(0, simulation_time, num_steps) + + # Plot positions + plt.figure() + plt.subplot(3, 1, 1) + plt.plot(time, positions[:, 0], label='True') + plt.plot(time, positions_est[:, 0], label='Estimated') + plt.title('Position X') + plt.xlabel('Time [s]') + plt.ylabel('Position X [m]') + plt.legend() + + plt.subplot(3, 1, 2) + plt.plot(time, positions[:, 1], label='True') + plt.plot(time, positions_est[:, 1], label='Estimated') + plt.title('Position Y') + plt.xlabel('Time [s]') + plt.ylabel('Position Y [m]') + plt.legend() + + plt.subplot(3, 1, 3) + plt.plot(time, positions[:, 2], label='True') + plt.plot(time, positions_est[:, 2], label='Estimated') + plt.title('Position Z') + plt.xlabel('Time [s]') + plt.ylabel('Position Z [m]') + plt.legend() + + plt.tight_layout() + plt.show() + + # Plot orientations (Euler angles) + plt.figure() + plt.subplot(3, 1, 1) + plt.plot(time, orientations[:, 0], label='True') + plt.plot(time, orientations_est[:, 0], label='Estimated') + plt.title('Orientation Roll') + plt.xlabel('Time [s]') + plt.ylabel('Roll [rad]') + plt.legend() + + plt.subplot(3, 1, 2) + plt.plot(time, orientations[:, 1], label='True') + plt.plot(time, orientations_est[:, 1], label='Estimated') + plt.title('Orientation Pitch') + plt.xlabel('Time [s]') + plt.ylabel('Pitch [rad]') + plt.legend() + + plt.subplot(3, 1, 3) + plt.plot(time, orientations[:, 2], label='True') + plt.plot(time, orientations_est[:, 2], label='Estimated') + plt.title('Orientation Yaw') + plt.xlabel('Time [s]') + plt.ylabel('Yaw [rad]') + plt.legend() + + plt.tight_layout() + plt.show() + + # Plot velocities + plt.figure() + plt.subplot(3, 1, 1) + plt.plot(time, velocities[:, 0], label='True') + plt.plot(time, velocities_est[:, 0], label='Estimated') + plt.title('Velocity X') + plt.xlabel('Time [s]') + plt.ylabel('Velocity X [m/s]') + plt.legend() + + plt.subplot(3, 1, 2) + plt.plot(time, velocities[:, 1], label='True') + plt.plot(time, velocities_est[:, 1], label='Estimated') + plt.title('Velocity Y') + plt.xlabel('Time [s]') + plt.ylabel('Velocity Y [m/s]') + plt.legend() + + plt.subplot(3, 1, 3) + plt.plot(time, velocities[:, 2], label='True') + plt.plot(time, velocities_est[:, 2], label='Estimated') + plt.title('Velocity Z') + plt.xlabel('Time [s]') + plt.ylabel('Velocity Z [m/s]') + plt.legend() + + plt.tight_layout() + plt.show() + + # Plot angular velocities + plt.figure() + plt.subplot(3, 1, 1) + plt.plot(time, angular_velocities[:, 0], label='True') + plt.plot(time, angular_velocities_est[:, 0], label='Estimated') + plt.title('Angular Velocity X') + plt.xlabel('Time [s]') + plt.ylabel('Angular Velocity X [rad/s]') + plt.legend() + + plt.subplot(3, 1, 2) + plt.plot(time, angular_velocities[:, 1], label='True') + plt.plot(time, angular_velocities_est[:, 1], label='Estimated') + plt.title('Angular Velocity Y') + plt.xlabel('Time [s]') + plt.ylabel('Angular Velocity Y [rad/s]') + plt.legend() + + plt.subplot(3, 1, 3) + plt.plot(time, angular_velocities[:, 2], label='True') + plt.plot(time, angular_velocities_est[:, 2], label='Estimated') + plt.title('Angular Velocity Z') + plt.xlabel('Time [s]') + plt.ylabel('Angular Velocity Z [rad/s]') + plt.legend() + + plt.tight_layout() + plt.show() \ No newline at end of file diff --git a/navigation/ukf_okid/ukf_python/ukf_okid_class copy.py b/navigation/ukf_okid/ukf_python/ukf_okid_class copy.py new file mode 100644 index 000000000..86b7beb49 --- /dev/null +++ b/navigation/ukf_okid/ukf_python/ukf_okid_class copy.py @@ -0,0 +1,568 @@ +from dataclasses import dataclass, field +import numpy as np + + +from dataclasses import dataclass, field +import numpy as np + +@dataclass +class StateQuat: + """ + A class to represent the state to be estimated by the UKF. + """ + position: np.ndarray = field(default_factory=lambda: np.zeros(3)) + orientation: np.ndarray = field(default_factory=lambda: np.array([1, 0, 0, 0])) + velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) + angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) + okid_params: np.ndarray = field(default_factory=lambda: np.zeros(21)) + covariance: np.ndarray = field(default_factory=lambda: np.zeros((33, 33))) + + def as_vector(self) -> np.ndarray: + """Returns the StateVector as a numpy array.""" + return np.concatenate([self.position, self.orientation, self.velocity, self.angular_velocity, self.okid_params]) + + def nu(self) -> np.ndarray: + """Calculates the nu vector.""" + return np.concatenate([self.velocity, self.angular_velocity]) + + def R_q(self) -> np.ndarray: + """Calculates the rotation matrix from the orientation quaternion.""" + q0, q1, q2, q3 = self.orientation + R = np.array([ + [1 - 2 * q2**2 - 2 * q3**2, 2 * (q1 * q2 - q0 * q3), 2 * (q0 * q2 + q1 * q3)], + [2 * (q1 * q2 + q0 * q3), 1 - 2 * q1**2 - 2 * q3**2, 2 * (q2 * q3 - q0 * q1)], + [2 * (q1 * q3 - q0 * q2), 2 * (q0 * q1 + q2 * q3), 1 - 2 * q1**2 - 2 * q2**2] + ]) + return R + + def fill_states(self, state: np.ndarray) -> None: + """Fills the state vector with the values from a numpy array.""" + self.position = state[0:3] + self.orientation = state[3:7] + self.velocity = state[7:10] + self.angular_velocity = state[10:13] + + if len(state) > 13: + self.okid_params = state[13:] + + def fill_states_different_dim(self, state: np.ndarray, state_euler: np.ndarray) -> None: + """Fills states when the state vector has different dimensions than the default state vector.""" + self.position = state[0:3] + state_euler[0:3] + self.orientation = quaternion_super_product(state[3:7], euler_to_quat(state_euler[3:6])) + self.velocity = state[7:10] + state_euler[6:9] + self.angular_velocity = state[10:13] + state_euler[9:12] + + if len(state) > 13: + self.okid_params = state[13:] + + def subtract(self, other: 'StateQuat') -> np.ndarray: + """Subtracts two StateQuat objects, returning the difference with Euler angles.""" + new_array = np.zeros(len(self.as_vector()) - 1) + new_array[:3] = self.position - other.position + new_array[3:6] = quat_to_euler(quaternion_error(self.orientation, other.orientation)) + new_array[6:9] = self.velocity - other.velocity + new_array[9:12] = self.angular_velocity - other.angular_velocity + + new_array[12:] = self.okid_params - other.okid_params + + return new_array + + def __add__(self, other: 'StateQuat') -> 'StateQuat': + """Adds two StateQuat objects.""" + new_state = StateQuat() + new_state.position = self.position + other.position + new_state.orientation = quaternion_super_product(self.orientation, other.orientation) + new_state.velocity = self.velocity + other.velocity + new_state.angular_velocity = self.angular_velocity + other.angular_velocity + + new_state.okid_params = self.okid_params + other.okid_params + + return new_state + + def __sub__(self, other: 'StateQuat') -> 'StateQuat': + """Subtracts two StateQuat objects.""" + new_state = StateQuat() + new_state.position = self.position - other.position + new_state.orientation = quaternion_error(self.orientation, other.orientation) + new_state.velocity = self.velocity - other.velocity + new_state.angular_velocity = self.angular_velocity - other.angular_velocity + + new_state.okid_params = self.okid_params - other.okid_params + + return new_state.as_vector() + + def __rmul__(self, scalar: float) -> 'StateQuat': + """Multiplies the StateQuat object by a scalar.""" + new_state = StateQuat() + new_state.position = scalar * self.position + new_state.orientation = quat_norm(scalar * self.orientation) + new_state.velocity = scalar * self.velocity + new_state.angular_velocity = scalar * self.angular_velocity + + new_state.okid_params = scalar * self.okid_params + + return new_state + + def insert_weights(self, weights: np.ndarray) -> np.ndarray: + """Inserts the weights into the covariance matrix.""" + new_state = StateQuat() + new_state.position = self.position - weights[:3] + new_state.orientation = quaternion_error(self.orientation, euler_to_quat(weights[3:6])) + new_state.velocity = self.velocity - weights[6:9] + new_state.angular_velocity = self.angular_velocity - weights[9:12] + new_state.okid_params = self.okid_params - weights[12:] + + return new_state.as_vector() + + def add_without_quaternions(self, other: 'StateQuat') -> None: + """Adds elements into the state vector without considering the quaternions.""" + self.position += other.position + self.velocity += other.velocity + self.angular_velocity += other.angular_velocity + self.okid_params += other.okid_params + +@dataclass +class MeasModel: + """ + A class defined for a general measurement model. + """ + measurement: np.ndarray = field(default_factory=lambda: np.zeros(3)) + covariance: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) + + def H(self, state: StateQuat) -> 'MeasModel': + """Calculates the measurement matrix.""" + H = np.zeros((3, 34)) + H[:, 7:10] = np.eye(3) + z_i = MeasModel() + z_i.measurement = np.dot(H, state.as_vector()) + return z_i + + def __add__(self, other: 'MeasModel') -> 'MeasModel': + """Defines the addition operation between two MeasModel objects.""" + result = MeasModel() + result.measurement = self.measurement + other.measurement + return result + + def __rmul__(self, scalar: float) -> 'MeasModel': + """Defines multiplication between scalar value and MeasModel object.""" + result = MeasModel() + result.measurement = scalar * self.measurement + return result + + def __sub__(self, other: 'MeasModel') -> 'MeasModel': + """Defines the subtraction between two MeasModel objects.""" + result = MeasModel() + result.measurement = self.measurement - other.measurement + return result + +@dataclass +class process_model: + """ + A class defined for a general process model. + """ + state_vector: StateQuat = field(default_factory=StateQuat) + state_vector_dot: StateQuat = field(default_factory=StateQuat) + state_vector_prev: StateQuat = field(default_factory=StateQuat) + Control_input: np.ndarray = field(default_factory=lambda: np.zeros(6)) + mass_interia_matrix: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) + added_mass: np.ndarray = field(default_factory=lambda: np.zeros(6)) + damping_linear: np.ndarray = field(default_factory=lambda: np.zeros(6)) + damping_nonlinear: np.ndarray = field(default_factory=lambda: np.zeros(6)) + m: float = 0.0 + inertia: np.ndarray = field(default_factory=lambda: np.zeros((3,3))) + r_b_bg: np.ndarray = field(default_factory=lambda: np.zeros(3)) + dt: float = 0.0 + integral_error_position: np.ndarray = field(default_factory=lambda: np.zeros(3)) + integral_error_orientation: np.ndarray = field(default_factory=lambda: np.zeros(4)) + prev_position_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) + prev_orientation_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) + + def R(self) -> np.ndarray: + """Calculates the rotation matrix.""" + nu, e_1, e_2, e_3 = self.state_vector.orientation + R = np.array([ + [1 - 2 * e_2 ** 2 - 2 * e_3 ** 2, 2 * e_1 * e_2 - 2 * nu * e_3, 2 * e_1 * e_3 + 2 * nu * e_2], + [2 * e_1 * e_2 + 2 * nu * e_3, 1 - 2 * e_1 ** 2 - 2 * e_3 ** 2, 2 * e_2 * e_3 - 2 * nu * e_1], + [2 * e_1 * e_3 - 2 * nu * e_2, 2 * e_2 * e_3 + 2 * nu * e_1, 1 - 2 * e_1 ** 2 - 2 * e_2 ** 2] + ]) + return R + + def T(self) -> np.ndarray: + """Calculates the transformation matrix.""" + nu, e_1, e_2, e_3 = self.state_vector.orientation + T = 0.5 * np.array([ + [-e_1, -e_2, -e_3], + [nu, -e_3, e_2], + [e_3, nu, -e_1], + [-e_2, e_1, nu] + ]) + return T + + def Crb(self) -> np.ndarray: + """Calculates the Coriolis matrix.""" + ang_vel = self.state_vector.angular_velocity + ang_vel_skew = skew_symmetric(ang_vel) + lever_arm_skew = skew_symmetric(self.r_b_bg) + Crb = np.zeros((6, 6)) + Crb[0:3, 0:3] = self.m * ang_vel_skew + Crb[3:6, 3:6] = -skew_symmetric(np.dot(self.inertia, ang_vel)) + Crb[0:3, 3:6] = -self.m * np.dot(ang_vel_skew, lever_arm_skew) + Crb[3:6, 0:3] = self.m * np.dot(lever_arm_skew, ang_vel_skew) + return Crb + + def D(self) -> np.ndarray: + """Calculates the damping matrix.""" + D_l = -np.diag(self.damping_linear) + D_nl = -np.diag(self.damping_nonlinear) * np.abs(self.state_vector.nu()) + return D_l + D_nl + + def model_prediction(self, state: StateQuat) -> None: + """Calculates the model of the system.""" + self.state_vector = state + self.state_vector_dot.position = np.dot(self.R(), self.state_vector.velocity) + self.state_vector_dot.orientation = np.dot(self.T(), self.state_vector.angular_velocity) + Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ (self.Control_input - np.dot(self.Crb(), self.state_vector.nu()) - np.dot(self.D(), self.state_vector.nu())) + self.state_vector_dot.velocity = Nu[:3] + self.state_vector_dot.angular_velocity = Nu[3:] + + def euler_forward(self) -> StateQuat: + """Calculates the forward Euler integration.""" + self.state_vector.position = self.state_vector_prev.position + self.state_vector_dot.position * self.dt + self.state_vector.orientation = quat_norm(self.state_vector_prev.orientation + self.state_vector_dot.orientation * self.dt) + self.state_vector.velocity = self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt + self.state_vector.angular_velocity = self.state_vector_prev.angular_velocity + self.state_vector_dot.angular_velocity * self.dt + return self.state_vector + +@dataclass +class okid_model: + """ + A class defined for a general process model. + """ + state_vector: StateQuat = field(default_factory=StateQuat) + state_vector_dot: StateQuat = field(default_factory=StateQuat) + state_vector_prev: StateQuat = field(default_factory=StateQuat) + Control_input: np.ndarray = field(default_factory=lambda: np.zeros(6)) + mass_interia_matrix: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) + m: float = 0.0 + inertia: np.ndarray = field(default_factory=lambda: np.zeros((3,3))) + r_b_bg: np.ndarray = field(default_factory=lambda: np.zeros(3)) + dt: float = 0.0 + prev_position_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) + prev_orientation_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) + D_matrix: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) + added_mass: np.ndarray = field(default_factory=lambda: np.zeros(6)) + + def R(self) -> np.ndarray: + """Calculates the rotation matrix.""" + nu, e_1, e_2, e_3 = self.state_vector.orientation + R = np.array([ + [1 - 2 * e_2 ** 2 - 2 * e_3 ** 2, 2 * e_1 * e_2 - 2 * nu * e_3, 2 * e_1 * e_3 + 2 * nu * e_2], + [2 * e_1 * e_2 + 2 * nu * e_3, 1 - 2 * e_1 ** 2 - 2 * e_3 ** 2, 2 * e_2 * e_3 - 2 * nu * e_1], + [2 * e_1 * e_3 - 2 * nu * e_2, 2 * e_2 * e_3 + 2 * nu * e_1, 1 - 2 * e_1 ** 2 - 2 * e_2 ** 2] + ]) + return R + + def T(self) -> np.ndarray: + """Calculates the transformation matrix.""" + nu, e_1, e_2, e_3 = self.state_vector.orientation + T = 0.5 * np.array([ + [-e_1, -e_2, -e_3], + [nu, -e_3, e_2], + [e_3, nu, -e_1], + [-e_2, e_1, nu] + ]) + return T + + def Crb(self) -> np.ndarray: + """Calculates the Coriolis matrix.""" + ang_vel = self.state_vector.angular_velocity + ang_vel_skew = skew_symmetric(ang_vel) + lever_arm_skew = skew_symmetric(self.r_b_bg) + Crb = np.zeros((6, 6)) + Crb[0:3, 0:3] = self.m * ang_vel_skew + Crb[3:6, 3:6] = -skew_symmetric(np.dot(self.inertia, ang_vel)) + Crb[0:3, 3:6] = -self.m * np.dot(ang_vel_skew, lever_arm_skew) + Crb[3:6, 0:3] = self.m * np.dot(lever_arm_skew, ang_vel_skew) + return Crb + + def D(self, linear_damping: np.ndarray, nonlinear_damping: np.ndarray) -> np.ndarray: + """Calculates the damping matrix.""" + D_l = -np.diag(linear_damping) + D_nl = -np.diag(nonlinear_damping) * np.abs(self.state_vector.nu()) + return D_l + D_nl + + def model_prediction(self, state: StateQuat) -> None: + """Calculates the model of the system.""" + self.state_vector = state + + self.inertia = np.diag(self.state_vector.okid_params[:3]) + self.mass_interia_matrix[3:6, 3:6] = self.inertia + self.D_matrix = self.D(self.state_vector.okid_params[3:9], self.state_vector.okid_params[9:15]) + self.added_mass = self.state_vector.okid_params[15:21] + + self.state_vector_dot.position = np.dot(self.R(), self.state_vector.velocity) + self.state_vector_dot.orientation = np.dot(self.T(), self.state_vector.angular_velocity) + + Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ (self.Control_input - np.dot(self.Crb(), self.state_vector.nu()) - np.dot(self.D_matrix, self.state_vector.nu())) + self.state_vector_dot.velocity = Nu[:3] + self.state_vector_dot.angular_velocity = Nu[3:] + + self.state_vector_dot.okid_params = np.zeros(21) + + def euler_forward(self) -> StateQuat: + """Calculates the forward Euler integration.""" + self.state_vector.position = self.state_vector_prev.position + self.state_vector_dot.position * self.dt + self.state_vector.orientation = quat_norm(self.state_vector_prev.orientation + self.state_vector_dot.orientation * self.dt) + self.state_vector.velocity = self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt + self.state_vector.angular_velocity = self.state_vector_prev.angular_velocity + self.state_vector_dot.angular_velocity * self.dt + self.state_vector.okid_params = self.state_vector_prev.okid_params + return self.state_vector + + + +def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: + """ + Converts Euler angles to a quaternion + """ + psi, theta, phi = euler_angles + c_psi = np.cos(psi / 2) + s_psi = np.sin(psi / 2) + c_theta = np.cos(theta / 2) + s_theta = np.sin(theta / 2) + c_phi = np.cos(phi / 2) + s_phi = np.sin(phi / 2) + + quat = np.array([ + c_psi * c_theta * c_phi + s_psi * s_theta * s_phi, + c_psi * c_theta * s_phi - s_psi * s_theta * c_phi, + s_psi * c_theta * s_phi + c_psi * s_theta * c_phi, + s_psi * c_theta * c_phi - c_psi * s_theta * s_phi + ]) + + return quat + +def quat_to_euler(quat: np.ndarray) -> np.ndarray: + """ + Converts a quaternion to Euler angles + """ + nu, eta_1, eta_2, eta_3 = quat + + phi = np.arctan2(2*(eta_2 * eta_3 + nu * eta_1), 1 - 2 * (eta_1 ** 2 + eta_2 ** 2)) + theta = -np.arcsin(2 * (eta_1 * eta_3 - nu * eta_2)) + psi = np.arctan2(2 * (nu * eta_3 + eta_1 * eta_2), 1 - 2 * (eta_2 ** 2 + eta_3 ** 2)) + + return np.array([phi, theta, psi]) + +def quat_norm(quat: np.ndarray) -> np.ndarray: + """ + Function that normalizes a quaternion + """ + + quat = quat / np.linalg.norm(quat) + + return quat + +def skew_symmetric(vector: np.ndarray) -> np.ndarray: + """Calculates the skew symmetric matrix of a vector. + + Args: + vector (np.ndarray): The vector. + + Returns: + np.ndarray: The skew symmetric matrix. + """ + return np.array( + [ + [0, -vector[2], vector[1]], + [vector[2], 0, -vector[0]], + [-vector[1], vector[0], 0], + ] + ) + +def quaternion_super_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: + """Calculates the quaternion super product of two quaternions. + + Args: + q1 (np.ndarray): The first quaternion. + q2 (np.ndarray): The second quaternion. + + Returns: + np.ndarray: The quaternion super product. + """ + eta_0, e_0_x, e_0_y, e_0_z = q1 + eta_1, e_1_x, e_1_y, e_1_z = q2 + + e_0 = np.array([e_0_x, e_0_y, e_0_z]) + e_1 = np.array([e_1_x, e_1_y, e_1_z]) + + eta_new = eta_0 * eta_1 - (e_0_x * e_1_x + e_0_y * e_1_y + e_0_z * e_1_z) + nu_new = e_1 * eta_0 + e_0 * eta_1 + np.dot(skew_symmetric(e_0), e_1) + + q_new = quat_norm(np.array([eta_new, nu_new[0], nu_new[1], nu_new[2]])) + + return q_new + +def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: + """ + Calculates the error between two quaternions + """ + + quat_2_inv = np.array([quat_2[0], -quat_2[1], -quat_2[2], -quat_2[3]]) + + error_quat = quaternion_super_product(quat_1, quat_2_inv) + + return error_quat + +def iterative_quaternion_mean_statequat(state_list: list[StateQuat], weights: np.ndarray, tol: float = 1e-6, max_iter: int = 100) -> np.ndarray: + """ + Computes the weighted mean of the quaternion orientations from a list of StateQuat objects + using an iterative approach, without requiring the caller to manually extract the quaternion. + + Parameters: + state_list (list[StateQuat]): List of StateQuat objects. + weights (np.ndarray): Weights for each state. + tol (float): Convergence tolerance. + max_iter (int): Maximum number of iterations. + + Returns: + np.ndarray: The averaged quaternion as a 4-element numpy array. + """ + # Internally extract the quaternion from each state + sigma_quats = [state.orientation for state in state_list] + + # Initialize the mean quaternion with the first quaternion + mean_q = sigma_quats[0].copy() + + for _ in range(max_iter): + weighted_error_vectors = [] + for i, q in enumerate(sigma_quats): + # Compute the error quaternion: e = q * inv(mean_q) + # For unit quaternions, the inverse is the conjugate. + mean_q_conj = np.array([mean_q[0], -mean_q[1], -mean_q[2], -mean_q[3]]) + e = quaternion_super_product(q, mean_q_conj) + + # Clip to avoid numerical issues + e0_clipped = np.clip(e[0], -1.0, 1.0) + angle = 2 * np.arccos(e0_clipped) + if np.abs(angle) < 1e-8: + error_vec = np.zeros(3) + else: + # Compute the full rotation vector (angle * axis) + error_vec = (angle / np.sin(angle / 2)) * e[1:4] + weighted_error_vectors.append(weights[i] * error_vec) + + error_avg = np.sum(weighted_error_vectors, axis=0) + if np.linalg.norm(error_avg) < tol: + break + + error_norm = np.linalg.norm(error_avg) + delta_q = (np.array([np.cos(error_norm / 2), + *(np.sin(error_norm / 2) * (error_avg / error_norm))]) + if error_norm > 0 else np.array([1.0, 0.0, 0.0, 0.0])) + mean_q = quaternion_super_product(delta_q, mean_q) + mean_q = quat_norm(mean_q) + + return mean_q + + + +def mean_set(set_points: list[StateQuat], weights: np.ndarray = None) -> np.ndarray: + """ + Function that calculates the mean of a set of points + """ + n = len(set_points[0].as_vector()) - 1 + mean_value = StateQuat() + + if weights is None: + for i in range(2 * n + 1): + weight_temp_list = (1/ (2 * n + 1)) * np.ones(2 * n + 1) + mean_value.add_without_quaternions(weight_temp_list[i] * set_points[i]) + + mean_value.orientation = iterative_quaternion_mean_statequat(set_points, weight_temp_list) + + else: + for i in range(2 * n + 1): + mean_value.add_without_quaternions(weights[i] * set_points[i]) + + mean_value.orientation = iterative_quaternion_mean_statequat(set_points, weights) + + return mean_value.as_vector() + +def mean_measurement(set_points: list[MeasModel], weights: np.ndarray = None) -> np.ndarray: + """ + Function that calculates the mean of a set of points + """ + n = len(set_points) + mean_value = MeasModel() + + if weights is None: + for i in range(n): + mean_value = mean_value + set_points[i] + else: + for i in range(n): + mean_value = mean_value + (weights[i] * set_points[i]) + + return mean_value.measurement + +def covariance_set(set_points: list[StateQuat], mean: np.ndarray, weights: np.ndarray = None) -> np.ndarray: + """ + Function that calculates the covariance of a set of points + """ + n = len(set_points[0].as_vector()) - 1 + covariance = np.zeros((n, n)) + mean_quat = StateQuat() + mean_quat.fill_states(mean) + + if weights is None: + for i in range(2 * n + 1): + covariance += np.outer(set_points[i].subtract(mean_quat), set_points[i].subtract(mean_quat)) + + covariance = (1 / (2 * n + 1)) * covariance + + else: + for i in range(2 * n + 1): + covariance += weights[i] * np.outer(set_points[i].subtract(mean_quat), set_points[i].subtract(mean_quat)) + + return covariance + +def covariance_measurement(set_points: list[MeasModel], mean: np.ndarray, weights: np.ndarray = None) -> np.ndarray: + """ + Function that calculates the covariance of a set of points + """ + n = len(set_points) + co_size = len(set_points[0].measurement) + covariance = np.zeros((co_size, co_size)) + mean_meas = MeasModel() + mean_meas.measurement = mean + + if weights is None: + for i in range(n): + temp_model = set_points[i] - mean_meas + covariance += np.outer(temp_model.measurement, temp_model.measurement) + + covariance = (1 / (n)) * covariance + + else: + for i in range(n): + temp_model = set_points[i] - mean_meas + covariance += weights[i] * np.outer(temp_model.measurement, temp_model.measurement) + + return covariance + +def cross_covariance(set_y: list[StateQuat], mean_y: np.ndarray, set_z: list[MeasModel], mean_z: np.ndarray, weights: np.ndarray) -> np.ndarray: + """ + Calculates the cross covariance between the measurement and state prediction + """ + + n = len(mean_y) - 1 + m = len(mean_z) + cross_covariance = np.zeros((n,m)) + mean_quat = StateQuat() + mean_quat.fill_states(mean_y) + + for i in range(n): + cross_covariance += np.outer(set_y[i].subtract(mean_quat), set_z[i].measurement - mean_z) + + cross_covariance = (1 / len(set_y)) * cross_covariance + + return cross_covariance diff --git a/navigation/ukf_okid/ukf_python/ukf_okid_class.py b/navigation/ukf_okid/ukf_python/ukf_okid_class.py new file mode 100644 index 000000000..8444fd82e --- /dev/null +++ b/navigation/ukf_okid/ukf_python/ukf_okid_class.py @@ -0,0 +1,464 @@ +from dataclasses import dataclass, field +import numpy as np + + +from dataclasses import dataclass, field +import numpy as np + +@dataclass +class StateQuat: + """ + A class to represent the state to be estimated by the UKF. + """ + position: np.ndarray = field(default_factory=lambda: np.zeros(3)) + orientation: np.ndarray = field(default_factory=lambda: np.array([1, 0, 0, 0])) + velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) + angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) + covariance: np.ndarray = field(default_factory=lambda: np.zeros((12, 12))) + + def as_vector(self) -> np.ndarray: + """Returns the StateVector as a numpy array.""" + return np.concatenate([self.position, self.orientation, self.velocity, self.angular_velocity]) + + def nu(self) -> np.ndarray: + """Calculates the nu vector.""" + return np.concatenate([self.velocity, self.angular_velocity]) + + def R_q(self) -> np.ndarray: + """Calculates the rotation matrix from the orientation quaternion.""" + q0, q1, q2, q3 = self.orientation + R = np.array([ + [1 - 2 * q2**2 - 2 * q3**2, 2 * (q1 * q2 - q0 * q3), 2 * (q0 * q2 + q1 * q3)], + [2 * (q1 * q2 + q0 * q3), 1 - 2 * q1**2 - 2 * q3**2, 2 * (q2 * q3 - q0 * q1)], + [2 * (q1 * q3 - q0 * q2), 2 * (q0 * q1 + q2 * q3), 1 - 2 * q1**2 - 2 * q2**2] + ]) + return R + + def fill_states(self, state: np.ndarray) -> None: + """Fills the state vector with the values from a numpy array.""" + self.position = state[0:3] + self.orientation = state[3:7] + self.velocity = state[7:10] + self.angular_velocity = state[10:13] + + def fill_states_different_dim(self, state: np.ndarray, state_euler: np.ndarray) -> None: + """Fills states when the state vector has different dimensions than the default state vector.""" + self.position = state[0:3] + state_euler[0:3] + self.orientation = quaternion_super_product(state[3:7], euler_to_quat(state_euler[3:6])) + self.velocity = state[7:10] + state_euler[6:9] + self.angular_velocity = state[10:13] + state_euler[9:12] + + def subtract(self, other: 'StateQuat') -> np.ndarray: + """Subtracts two StateQuat objects, returning the difference with Euler angles.""" + new_array = np.zeros(len(self.as_vector()) - 1) + new_array[:3] = self.position - other.position + new_array[3:6] = quat_to_euler(quaternion_error(self.orientation, other.orientation)) + new_array[6:9] = self.velocity - other.velocity + new_array[9:12] = self.angular_velocity - other.angular_velocity + + return new_array + + def __add__(self, other: 'StateQuat') -> 'StateQuat': + """Adds two StateQuat objects.""" + new_state = StateQuat() + new_state.position = self.position + other.position + new_state.orientation = quaternion_super_product(self.orientation, other.orientation) + new_state.velocity = self.velocity + other.velocity + new_state.angular_velocity = self.angular_velocity + other.angular_velocity + + return new_state + + def __sub__(self, other: 'StateQuat') -> 'StateQuat': + """Subtracts two StateQuat objects.""" + new_state = StateQuat() + new_state.position = self.position - other.position + new_state.orientation = quaternion_error(self.orientation, other.orientation) + new_state.velocity = self.velocity - other.velocity + new_state.angular_velocity = self.angular_velocity - other.angular_velocity + + return new_state.as_vector() + + def __rmul__(self, scalar: float) -> 'StateQuat': + """Multiplies the StateQuat object by a scalar.""" + new_state = StateQuat() + new_state.position = scalar * self.position + new_state.orientation = quat_norm(scalar * self.orientation) + new_state.velocity = scalar * self.velocity + new_state.angular_velocity = scalar * self.angular_velocity + + return new_state + + def insert_weights(self, weights: np.ndarray) -> np.ndarray: + """Inserts the weights into the covariance matrix.""" + new_state = StateQuat() + new_state.position = self.position - weights[:3] + new_state.orientation = quaternion_error(self.orientation, euler_to_quat(weights[3:6])) + new_state.velocity = self.velocity - weights[6:9] + new_state.angular_velocity = self.angular_velocity - weights[9:12] + + return new_state.as_vector() + + def add_without_quaternions(self, other: 'StateQuat') -> None: + """Adds elements into the state vector without considering the quaternions.""" + self.position += other.position + self.velocity += other.velocity + self.angular_velocity += other.angular_velocity + +@dataclass +class MeasModel: + """ + A class defined for a general measurement model. + """ + measurement: np.ndarray = field(default_factory=lambda: np.zeros(3)) + covariance: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) + + def H(self, state: StateQuat) -> 'MeasModel': + """Calculates the measurement matrix.""" + H = np.zeros((3, 13)) + H[:, 7:10] = np.eye(3) + z_i = MeasModel() + z_i.measurement = np.dot(H, state.as_vector()) + return z_i + + def __add__(self, other: 'MeasModel') -> 'MeasModel': + """Defines the addition operation between two MeasModel objects.""" + result = MeasModel() + result.measurement = self.measurement + other.measurement + return result + + def __rmul__(self, scalar: float) -> 'MeasModel': + """Defines multiplication between scalar value and MeasModel object.""" + result = MeasModel() + result.measurement = scalar * self.measurement + return result + + def __sub__(self, other: 'MeasModel') -> 'MeasModel': + """Defines the subtraction between two MeasModel objects.""" + result = MeasModel() + result.measurement = self.measurement - other.measurement + return result + +@dataclass +class process_model: + """ + A class defined for a general process model. + """ + state_vector: StateQuat = field(default_factory=StateQuat) + state_vector_dot: StateQuat = field(default_factory=StateQuat) + state_vector_prev: StateQuat = field(default_factory=StateQuat) + Control_input: np.ndarray = field(default_factory=lambda: np.zeros(6)) + mass_interia_matrix: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) + added_mass: np.ndarray = field(default_factory=lambda: np.zeros(6)) + damping_linear: np.ndarray = field(default_factory=lambda: np.zeros(6)) + damping_nonlinear: np.ndarray = field(default_factory=lambda: np.zeros(6)) + m: float = 0.0 + inertia: np.ndarray = field(default_factory=lambda: np.zeros((3,3))) + r_b_bg: np.ndarray = field(default_factory=lambda: np.zeros(3)) + dt: float = 0.0 + integral_error_position: np.ndarray = field(default_factory=lambda: np.zeros(3)) + integral_error_orientation: np.ndarray = field(default_factory=lambda: np.zeros(4)) + prev_position_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) + prev_orientation_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) + + def R(self) -> np.ndarray: + """Calculates the rotation matrix.""" + nu, e_1, e_2, e_3 = self.state_vector.orientation + R = np.array([ + [1 - 2 * e_2 ** 2 - 2 * e_3 ** 2, 2 * e_1 * e_2 - 2 * nu * e_3, 2 * e_1 * e_3 + 2 * nu * e_2], + [2 * e_1 * e_2 + 2 * nu * e_3, 1 - 2 * e_1 ** 2 - 2 * e_3 ** 2, 2 * e_2 * e_3 - 2 * nu * e_1], + [2 * e_1 * e_3 - 2 * nu * e_2, 2 * e_2 * e_3 + 2 * nu * e_1, 1 - 2 * e_1 ** 2 - 2 * e_2 ** 2] + ]) + return R + + def T(self) -> np.ndarray: + """Calculates the transformation matrix.""" + nu, e_1, e_2, e_3 = self.state_vector.orientation + T = 0.5 * np.array([ + [-e_1, -e_2, -e_3], + [nu, -e_3, e_2], + [e_3, nu, -e_1], + [-e_2, e_1, nu] + ]) + return T + + def Crb(self) -> np.ndarray: + """Calculates the Coriolis matrix.""" + ang_vel = self.state_vector.angular_velocity + ang_vel_skew = skew_symmetric(ang_vel) + lever_arm_skew = skew_symmetric(self.r_b_bg) + Crb = np.zeros((6, 6)) + Crb[0:3, 0:3] = self.m * ang_vel_skew + Crb[3:6, 3:6] = -skew_symmetric(np.dot(self.inertia, ang_vel)) + Crb[0:3, 3:6] = -self.m * np.dot(ang_vel_skew, lever_arm_skew) + Crb[3:6, 0:3] = self.m * np.dot(lever_arm_skew, ang_vel_skew) + return Crb + + def D(self) -> np.ndarray: + """Calculates the damping matrix.""" + D_l = -np.diag(self.damping_linear) + D_nl = -np.diag(self.damping_nonlinear) * np.abs(self.state_vector.nu()) + return D_l + D_nl + + def model_prediction(self, state: StateQuat) -> None: + """Calculates the model of the system.""" + self.state_vector = state + self.state_vector_dot.position = np.dot(self.R(), self.state_vector.velocity) + self.state_vector_dot.orientation = np.dot(self.T(), self.state_vector.angular_velocity) + Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ (self.Control_input - np.dot(self.Crb(), self.state_vector.nu()) - np.dot(self.D(), self.state_vector.nu())) + self.state_vector_dot.velocity = Nu[:3] + self.state_vector_dot.angular_velocity = Nu[3:] + + def euler_forward(self) -> StateQuat: + """Calculates the forward Euler integration.""" + self.state_vector.position = self.state_vector_prev.position + self.state_vector_dot.position * self.dt + self.state_vector.orientation = quat_norm(self.state_vector_prev.orientation + self.state_vector_dot.orientation * self.dt) + self.state_vector.velocity = self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt + self.state_vector.angular_velocity = self.state_vector_prev.angular_velocity + self.state_vector_dot.angular_velocity * self.dt + return self.state_vector + +def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: + """ + Converts Euler angles to a quaternion + """ + psi, theta, phi = euler_angles + c_psi = np.cos(psi / 2) + s_psi = np.sin(psi / 2) + c_theta = np.cos(theta / 2) + s_theta = np.sin(theta / 2) + c_phi = np.cos(phi / 2) + s_phi = np.sin(phi / 2) + + quat = np.array([ + c_psi * c_theta * c_phi + s_psi * s_theta * s_phi, + c_psi * c_theta * s_phi - s_psi * s_theta * c_phi, + s_psi * c_theta * s_phi + c_psi * s_theta * c_phi, + s_psi * c_theta * c_phi - c_psi * s_theta * s_phi + ]) + + return quat + +def quat_to_euler(quat: np.ndarray) -> np.ndarray: + """ + Converts a quaternion to Euler angles + """ + nu, eta_1, eta_2, eta_3 = quat + + phi = np.arctan2(2*(eta_2 * eta_3 + nu * eta_1), 1 - 2 * (eta_1 ** 2 + eta_2 ** 2)) + theta = -np.arcsin(2 * (eta_1 * eta_3 - nu * eta_2)) + psi = np.arctan2(2 * (nu * eta_3 + eta_1 * eta_2), 1 - 2 * (eta_2 ** 2 + eta_3 ** 2)) + + return np.array([phi, theta, psi]) + +def quat_norm(quat: np.ndarray) -> np.ndarray: + """ + Function that normalizes a quaternion + """ + + quat = quat / np.linalg.norm(quat) + + return quat + +def skew_symmetric(vector: np.ndarray) -> np.ndarray: + """Calculates the skew symmetric matrix of a vector. + + Args: + vector (np.ndarray): The vector. + + Returns: + np.ndarray: The skew symmetric matrix. + """ + return np.array( + [ + [0, -vector[2], vector[1]], + [vector[2], 0, -vector[0]], + [-vector[1], vector[0], 0], + ] + ) + +def quaternion_super_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: + """Calculates the quaternion super product of two quaternions. + + Args: + q1 (np.ndarray): The first quaternion. + q2 (np.ndarray): The second quaternion. + + Returns: + np.ndarray: The quaternion super product. + """ + eta_0, e_0_x, e_0_y, e_0_z = q1 + eta_1, e_1_x, e_1_y, e_1_z = q2 + + e_0 = np.array([e_0_x, e_0_y, e_0_z]) + e_1 = np.array([e_1_x, e_1_y, e_1_z]) + + eta_new = eta_0 * eta_1 - (e_0_x * e_1_x + e_0_y * e_1_y + e_0_z * e_1_z) + nu_new = e_1 * eta_0 + e_0 * eta_1 + np.dot(skew_symmetric(e_0), e_1) + + q_new = quat_norm(np.array([eta_new, nu_new[0], nu_new[1], nu_new[2]])) + + return q_new + +def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: + """ + Calculates the error between two quaternions + """ + + quat_2_inv = np.array([quat_2[0], -quat_2[1], -quat_2[2], -quat_2[3]]) + + error_quat = quaternion_super_product(quat_1, quat_2_inv) + + return error_quat + +def iterative_quaternion_mean_statequat(state_list: list[StateQuat], weights: np.ndarray, tol: float = 1e-6, max_iter: int = 100) -> np.ndarray: + """ + Computes the weighted mean of the quaternion orientations from a list of StateQuat objects + using an iterative approach, without requiring the caller to manually extract the quaternion. + + Parameters: + state_list (list[StateQuat]): List of StateQuat objects. + weights (np.ndarray): Weights for each state. + tol (float): Convergence tolerance. + max_iter (int): Maximum number of iterations. + + Returns: + np.ndarray: The averaged quaternion as a 4-element numpy array. + """ + # Internally extract the quaternion from each state + sigma_quats = [state.orientation for state in state_list] + + # Initialize the mean quaternion with the first quaternion + mean_q = sigma_quats[0].copy() + + for _ in range(max_iter): + weighted_error_vectors = [] + for i, q in enumerate(sigma_quats): + # Compute the error quaternion: e = q * inv(mean_q) + # For unit quaternions, the inverse is the conjugate. + mean_q_conj = np.array([mean_q[0], -mean_q[1], -mean_q[2], -mean_q[3]]) + e = quaternion_super_product(q, mean_q_conj) + + # Clip to avoid numerical issues + e0_clipped = np.clip(e[0], -1.0, 1.0) + angle = 2 * np.arccos(e0_clipped) + if np.abs(angle) < 1e-8: + error_vec = np.zeros(3) + else: + # Compute the full rotation vector (angle * axis) + error_vec = (angle / np.sin(angle / 2)) * e[1:4] + weighted_error_vectors.append(weights[i] * error_vec) + + error_avg = np.sum(weighted_error_vectors, axis=0) + if np.linalg.norm(error_avg) < tol: + break + + error_norm = np.linalg.norm(error_avg) + delta_q = (np.array([np.cos(error_norm / 2), + *(np.sin(error_norm / 2) * (error_avg / error_norm))]) + if error_norm > 0 else np.array([1.0, 0.0, 0.0, 0.0])) + mean_q = quaternion_super_product(delta_q, mean_q) + mean_q = quat_norm(mean_q) + + return mean_q + + + +def mean_set(set_points: list[StateQuat], weights: np.ndarray = None) -> np.ndarray: + """ + Function that calculates the mean of a set of points + """ + n = len(set_points[0].as_vector()) - 1 + mean_value = StateQuat() + + if weights is None: + for i in range(2 * n + 1): + weight_temp_list = (1/ (2 * n + 1)) * np.ones(2 * n + 1) + mean_value.add_without_quaternions(weight_temp_list[i] * set_points[i]) + + mean_value.orientation = iterative_quaternion_mean_statequat(set_points, weight_temp_list) + + else: + for i in range(2 * n + 1): + mean_value.add_without_quaternions(weights[i] * set_points[i]) + + mean_value.orientation = iterative_quaternion_mean_statequat(set_points, weights) + + return mean_value.as_vector() + +def mean_measurement(set_points: list[MeasModel], weights: np.ndarray = None) -> np.ndarray: + """ + Function that calculates the mean of a set of points + """ + n = len(set_points) + mean_value = MeasModel() + + if weights is None: + for i in range(n): + mean_value = mean_value + set_points[i] + else: + for i in range(n): + mean_value = mean_value + (weights[i] * set_points[i]) + + return mean_value.measurement + +def covariance_set(set_points: list[StateQuat], mean: np.ndarray, weights: np.ndarray = None) -> np.ndarray: + """ + Function that calculates the covariance of a set of points + """ + n = len(set_points[0].as_vector()) - 1 + covariance = np.zeros((n, n)) + mean_quat = StateQuat() + mean_quat.fill_states(mean) + + if weights is None: + for i in range(2 * n + 1): + covariance += np.outer(set_points[i].subtract(mean_quat), set_points[i].subtract(mean_quat)) + + covariance = (1 / (2 * n + 1)) * covariance + + else: + for i in range(2 * n + 1): + covariance += weights[i] * np.outer(set_points[i].subtract(mean_quat), set_points[i].subtract(mean_quat)) + + return covariance + +def covariance_measurement(set_points: list[MeasModel], mean: np.ndarray, weights: np.ndarray = None) -> np.ndarray: + """ + Function that calculates the covariance of a set of points + """ + n = len(set_points) + co_size = len(set_points[0].measurement) + covariance = np.zeros((co_size, co_size)) + mean_meas = MeasModel() + mean_meas.measurement = mean + + if weights is None: + for i in range(n): + temp_model = set_points[i] - mean_meas + covariance += np.outer(temp_model.measurement, temp_model.measurement) + + covariance = (1 / (n)) * covariance + + else: + for i in range(n): + temp_model = set_points[i] - mean_meas + covariance += weights[i] * np.outer(temp_model.measurement, temp_model.measurement) + + return covariance + +def cross_covariance(set_y: list[StateQuat], mean_y: np.ndarray, set_z: list[MeasModel], mean_z: np.ndarray, weights: np.ndarray) -> np.ndarray: + """ + Calculates the cross covariance between the measurement and state prediction + """ + + n = len(mean_y) - 1 + m = len(mean_z) + cross_covariance = np.zeros((n,m)) + mean_quat = StateQuat() + mean_quat.fill_states(mean_y) + + for i in range(n): + cross_covariance += np.outer(set_y[i].subtract(mean_quat), set_z[i].measurement - mean_z) + + cross_covariance = (1 / len(set_y)) * cross_covariance + + return cross_covariance diff --git a/navigation/ukf_okid/ukf_python/ukf_utils.py b/navigation/ukf_okid/ukf_python/ukf_utils.py new file mode 100644 index 000000000..f52f2eb62 --- /dev/null +++ b/navigation/ukf_okid/ukf_python/ukf_utils.py @@ -0,0 +1,36 @@ +import numpy as np +from dataclasses import dataclass +from ukf_okid_class import StateQuat + +def print_StateQuat_list(state_list: list[StateQuat], name="StateQuat List", print_covariance=True): + """ + Custom print function to print a list of StateQuat objects in a formatted form. + """ + print(f"{name}:") + for i, state in enumerate(state_list): + print(f"Index {i}:") + print_StateQuat(state, f"StateQuat {i}", print_covariance) + +def print_StateQuat(state: StateQuat, name="StateQuat", print_covariance=True): + """ + Custom print function to print StateQuat objects in a formatted form. + """ + print(f"{name}:") + print(f" Position: {state.position}") + print(f" Orientation: {state.orientation}") + print(f" Velocity: {state.velocity}") + print(f" Angular Velocity: {state.angular_velocity}") + print(f" okid_params: {state.okid_params}") + if print_covariance: + print_matrix(state.covariance, "Covariance") + +def print_matrix(matrix, name="Matrix"): + """ + Custom print function to print matrices in a formatted form. + """ + print(f"{name}: {matrix.shape}") + if isinstance(matrix, np.ndarray): + for row in matrix: + print(" ".join(f"{val:.2f}" for val in row)) + else: + print(matrix) From 2a3daba296c16810d8f73c8278154d6f9ada03e2 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Fri, 14 Mar 2025 23:04:40 +0100 Subject: [PATCH 06/30] added in some changes to eskf and the ukf algorithm --- .../eskf_python/eskf_python_class.py | 215 +++++++ .../eskf_python/eskf_python_filter.py | 600 +++++------------- .../eskf_python/eskf_python_node.py | 2 +- .../eskf_python/eskf_python_utils.py | 95 +++ .../eskf_python/ukf_okid_class.py} | 110 +--- navigation/sp_ukf_python/CMakeLists.txt | 33 - navigation/sp_ukf_python/README.md | 0 .../sp_ukf_python/config/sp_ukf_python.yaml | 3 - navigation/sp_ukf_python/launch/ukf.launch.py | 22 - navigation/sp_ukf_python/package.xml | 23 - .../sp_ukf_python/sp_ukf_python/__init__.py | 0 .../sp_ukf_python/sp_ukf_python.py | 495 --------------- .../sp_ukf_python/sp_ukf_python_class.py | 292 --------- .../sp_ukf_python/sp_ukf_python_node.py | 137 ---- .../sp_ukf_python/sp_ukf_python_utils.py | 116 ---- .../sp_ukf_python/sp_ukf_python/test_ukf.py | 313 --------- navigation/ukf_okid/ukf_python/ukf_okid.py | 87 ++- 17 files changed, 551 insertions(+), 1992 deletions(-) create mode 100644 navigation/eskf_python/eskf_python/eskf_python_class.py create mode 100644 navigation/eskf_python/eskf_python/eskf_python_utils.py rename navigation/{ukf_okid/ukf_python/ukf_okid_class copy.py => eskf_python/eskf_python/ukf_okid_class.py} (78%) delete mode 100644 navigation/sp_ukf_python/CMakeLists.txt delete mode 100644 navigation/sp_ukf_python/README.md delete mode 100644 navigation/sp_ukf_python/config/sp_ukf_python.yaml delete mode 100644 navigation/sp_ukf_python/launch/ukf.launch.py delete mode 100644 navigation/sp_ukf_python/package.xml delete mode 100644 navigation/sp_ukf_python/sp_ukf_python/__init__.py delete mode 100644 navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py delete mode 100644 navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py delete mode 100644 navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_node.py delete mode 100644 navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_utils.py delete mode 100644 navigation/sp_ukf_python/sp_ukf_python/test_ukf.py diff --git a/navigation/eskf_python/eskf_python/eskf_python_class.py b/navigation/eskf_python/eskf_python/eskf_python_class.py new file mode 100644 index 000000000..949ab996d --- /dev/null +++ b/navigation/eskf_python/eskf_python/eskf_python_class.py @@ -0,0 +1,215 @@ +from dataclasses import dataclass, field +from typing import Tuple, List +from scipy.linalg import expm +import numpy as np +from eskf_python_utils import skew_matrix, quaternion_product + + +@dataclass +class StateQuat: + position: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Position vector (x, y, z) + velocity: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Velocity vector (u, v, w) + orientation: np.ndarray = field( + default_factory=lambda: np.array([1, 0, 0, 0]) + ) # Orientation quaternion (w, x, y, z) + acceleration_bias: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Acceleration bias vector (b_ax, b_ay, b_az) + gyro_bias: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Gyro bias vector (b_gx, b_gy, b_gz) + g: np.ndarray = field( + default_factory=lambda: np.array([0, 0, 0]) + ) # Gravity vector + + def as_vector(self) -> np.ndarray: + """Returns the state vector as a numpy array. + + Returns: + np.ndarray: The state vector. + """ + return np.concatenate( + [ + self.position, + self.velocity, + self.orientation, + self.acceleration_bias, + self.gyro_bias, + self.g, + ] + ) + + def fill_states(self, state: np.ndarray) -> None: + """Fills the state vector with the values from a numpy array. + + Args: + state (np.ndarray): The state vector. + """ + self.position = state[0:3] + self.velocity = state[3:6] + self.orientation = state[6:10] + self.acceleration_bias = state[10:13] + self.gyro_bias = state[13:16] + self.g = state[16:19] + + def R_q(self) -> np.ndarray: + """Calculates the rotation matrix from the orientation quaternion. + + Returns: + np.ndarray: The rotation matrix. + """ + q0, q1, q2, q3 = self.orientation + R = np.array( + [ + [ + 1 - 2 * q2**2 - 2 * q3**2, + 2 * (q1 * q2 - q0 * q3), + 2 * (q0 * q2 + q1 * q3), + ], + [ + 2 * (q1 * q2 + q0 * q3), + 1 - 2 * q1**2 - 2 * q3**2, + 2 * (q2 * q3 - q0 * q1), + ], + [ + 2 * (q1 * q3 - q0 * q2), + 2 * (q0 * q1 + q2 * q3), + 1 - 2 * q1**2 - 2 * q2**2, + ], + ] + ) + + return R + + # def inject(self, EulerState: 'StateEuler') -> 'StateQuat': + # inj_state = StateQuat() + + # # Injecting the error state + # inj_state.position = self.position + EulerState.position + # inj_state.velocity = self.velocity + EulerState.velocity + # inj_state.orientation = quaternion_product( + # self.orientation, + # 0.5 + # * np.array( + # [ + # 2, + # EulerState.orientation[0], + # EulerState.orientation[1], + # EulerState.orientation[2], + # ] + # ), + # ) + # inj_state.acceleration_bias = self.acceleration_bias + EulerState.acceleration_bias + # inj_state.gyro_bias = self.gyro_bias + EulerState.gyro_bias + + # return inj_state + + + +@dataclass +class StateEuler: + position: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Position vector (x, y, z) + velocity: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Velocity vector (u, v, w) + orientation: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Orientation angles (roll, pitch, yaw) + acceleration_bias: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Acceleration bias vector (b_ax, b_ay, b_az) + gyro_bias: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) # Gyro bias vector (b_gx, b_gy, b_gz) + g: np.ndarray = field( + default_factory=lambda: np.array([0, 0, 9.81]) + ) # Gravity vector + covariance: np.ndarray = field( + default_factory=lambda: np.zeros((18, 18)) + ) # Covariance matrix + + def as_vector(self) -> np.ndarray: + """Returns the state vector as a numpy array. + + Returns: + np.ndarray: The state vector. + """ + return np.concatenate( + [ + self.position, + self.velocity, + self.orientation, + self.acceleration_bias, + self.gyro_bias, + self.g, + ] + ) + + def fill_states(self, state: np.ndarray) -> None: + """Fills the state vector with the values from a numpy array. + + Args: + state (np.ndarray): The state vector. + """ + self.position = state[0:3] + self.velocity = state[3:6] + self.orientation = state[6:9] + self.acceleration_bias = state[9:12] + self.gyro_bias = state[12:15] + self.g = state[15:18] + + def copy_state(self, wanted_state: 'StateEuler') -> None: + """Copies the state from a StateVector object into the current StateVector object. + + Args: + wanted_state (StateVector_euler): The quaternion state to copy from. + """ + self.position = wanted_state.position + self.velocity = wanted_state.velocity + self.orientation = wanted_state.orientation + self.acceleration_bias = wanted_state.acceleration_bias + self.gyro_bias = wanted_state.gyro_bias + + +@dataclass +class MeasurementModel: + measurement: np.ndarray = field( + default_factory=lambda: np.zeros(6) + ) + measurement_covariance: np.ndarray = field( + default_factory=lambda: np.zeros((6, 6)) + ) + + def H(self) -> np.ndarray: + """Calculates the measurement matrix. + + Returns: + np.ndarray: The measurement matrix. + """ + H = np.zeros((3, 15)) + + H[0:3, 3:6] = np.eye(3) + + return H + +@dataclass +class Measurement: + acceleration: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) + angular_velocity: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) + aiding: np.ndarray = field( + default_factory=lambda: np.zeros(3) + ) + + aiding_covariance: np.ndarray = field( + default_factory=lambda: np.zeros((3, 3)) + ) \ No newline at end of file diff --git a/navigation/eskf_python/eskf_python/eskf_python_filter.py b/navigation/eskf_python/eskf_python/eskf_python_filter.py index edf39dcc0..a9c772e47 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_filter.py +++ b/navigation/eskf_python/eskf_python/eskf_python_filter.py @@ -1,503 +1,249 @@ -from dataclasses import dataclass, field -from typing import tuple +# from dataclasses import dataclass +from typing import Tuple import numpy as np from scipy.linalg import expm +from eskf_python_class import StateEuler, StateQuat, Measurement +from eskf_python_utils import skew_matrix, quaternion_product, R_from_angle_axis, angle_axis_to_quaternion +from ukf_okid_class import euler_to_quat +from scipy.linalg import block_diag + +class ESKF: + def __init__(self, Q: np.ndarray, P0, Hx, nom_state: StateQuat, p_accBias, p_gyroBias, dt): + self.Q = Q + self.Hx = Hx # Jacobian of the measurement model + self.dt = dt + self.nom_state = nom_state + self.error_state = StateEuler() + self.error_state.covariance = P0 + self.p_accBias = p_accBias + self.p_gyroBias = p_gyroBias + + def Fx(self, imu_data: Measurement) -> np.ndarray: + """Calculates the state transition matrix. -@dataclass -class StateVector_quaternion: - position: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Position vector (x, y, z) - velocity: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Velocity vector (u, v, w) - orientation: np.ndarray = field( - default_factory=lambda: np.zeros(4) - ) # Orientation quaternion (w, x, y, z) - acceleration_bias: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Acceleration bias vector (b_ax, b_ay, b_az) - gyro_bias: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Gyro bias vector (b_gx, b_gy, b_gz) - - def R_q(self) -> np.ndarray: - """Calculates the rotation matrix from the orientation quaternion. + Args: + imu_data (np.ndarray): The IMU data. Returns: - np.ndarray: The rotation matrix. + np.ndarray: The state transition matrix. """ - q0, q1, q2, q3 = self.orientation - R = np.array( - [ - [ - 1 - 2 * q2**2 - 2 * q3**2, - 2 * (q1 * q2 - q0 * q3), - 2 * (q0 * q2 + q1 * q3), - ], - [ - 2 * (q1 * q2 + q0 * q3), - 1 - 2 * q1**2 - 2 * q3**2, - 2 * (q2 * q3 - q0 * q1), - ], - [ - 2 * (q1 * q3 - q0 * q2), - 2 * (q0 * q1 + q2 * q3), - 1 - 2 * q1**2 - 2 * q2**2, - ], - ] - ) - return R + F_x = np.zeros((18, 18)) + I = np.eye(3) + + F_x[0:3, 0:3] = I + F_x[0:3, 3:6] = self.dt * I + F_x[3:6, 3:6] = I + F_x[3:6, 6:9] = -self.nom_state.R_q() @ skew_matrix(imu_data.acceleration - self.nom_state.acceleration_bias) * self.dt + F_x[6:9, 6:9] = R_from_angle_axis((imu_data.angular_velocity - self.nom_state.gyro_bias) * self.dt).T + F_x[3:6, 9:12] = -self.nom_state.R_q() * self.dt + F_x[3:6, 15:18] = I * self.dt + F_x[6:9, 12:15] = -I * self.dt + F_x[9:12, 9:12] = I + F_x[12:15, 12:15] = I + F_x[15:18, 15:18] = I + + return F_x + + def Fi(self) -> np.ndarray: + """Calculates the input matrix. + + Returns: + np.ndarray: The input matrix. + """ - def euler_forward( - self, current_state: 'StateVector_quaternion', dt: float - ) -> 'StateVector_quaternion': - # Define the new state - new_state = StateVector_quaternion() + F_i = np.zeros((18, 12)) + I = np.eye(3) - # Define the state derivatives - new_state.position = current_state.position + self.position * dt - new_state.velocity = current_state.velocity + self.velocity * dt - new_state.orientation = current_state.orientation + self.orientation * dt - new_state.acceleration_bias = ( - current_state.acceleration_bias + self.acceleration_bias * dt - ) - new_state.gyro_bias = current_state.gyro_bias + self.gyro_bias * dt - - # Normalize the orientation quaternion - new_state.orientation /= np.linalg.norm(new_state.orientation) - - return new_state - - -@dataclass -class StateVector_euler: - position: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Position vector (x, y, z) - velocity: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Velocity vector (u, v, w) - orientation: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Orientation angles (roll, pitch, yaw) - acceleration_bias: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Acceleration bias vector (b_ax, b_ay, b_az) - gyro_bias: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Gyro bias vector (b_gx, b_gy, b_gz) - covariance: np.ndarray = field( - default_factory=lambda: np.zeros((15, 15)) - ) # Covariance matrix - - def fill_states(self, state: np.ndarray) -> None: - """Fills the state vector with the values from a numpy array. + F_i[3:6, 0:3] = I + F_i[6:9, 3:6] = I + F_i[9:12, 6:9] = I + F_i[12:15, 9:12] = I - Args: - state (np.ndarray): The state vector. + return F_i + + def Q_delta_theta(self) -> np.ndarray: + """ + Calculates the Q_delta_theta matrix. + See Joan Solà. Quaternion kinematics for the error-state Kalman filter. + chapter: 6.1.1 eq. 281 """ - self.position = state[0:3] - self.velocity = state[3:6] - self.orientation = state[6:9] - self.acceleration_bias = state[9:12] - self.gyro_bias = state[12:15] - def copy_state(self, wanted_state: 'StateVector_euler') -> None: - """Copies the state from a StateVector object into the current StateVector object. + qw, qx, qy, qz = self.nom_state.orientation - Args: - wanted_state (StateVector_euler): The quaternion state to copy from. - """ - self.position = wanted_state.position - self.velocity = wanted_state.velocity - self.orientation = wanted_state.orientation - self.acceleration_bias = wanted_state.acceleration_bias - self.gyro_bias = wanted_state.gyro_bias - - -@dataclass -class MeasurementModel: - measurement: np.ndarray = field( - default_factory=lambda: np.zeros(6) - ) # Measurement vector - measurement_matrix: np.ndarray = field( - default_factory=lambda: np.zeros((6, 15)) - ) # Measurement matrix - measurement_covariance: np.ndarray = field( - default_factory=lambda: np.zeros((6, 6)) - ) # Measurement noise matrix - - -class ErrorStateKalmanFilter: - def __init__( - self, - P_ab: np.ndarray, - P_wb: np.ndarray, - Q: np.ndarray, - lever_arm: np.array, - R: np.ndarray, - g: float, - dt: float, - ) -> None: - self.P_ab = P_ab - self.P_wb = P_wb - self.Q_process_noise = Q - self.lever_arm = lever_arm - self.R = R - self.g = np.array([0, 0, g]) - self.dt = dt + Q_delta_theta = 0.5 * np.array([ + [-qx, -qy, -qz], + [qw, -qz, qy], + [qz, qw, -qx], + [-qy, qx, qw], + ]) - def skew_symmetric(self, vector: np.ndarray) -> np.ndarray: - """Calculates the skew symmetric matrix of a vector. + return Q_delta_theta - Args: - vector (np.ndarray): The vector. + def H(self) -> np.ndarray: + """Calculates the measurement matrix. Returns: - np.ndarray: The skew symmetric matrix. + np.ndarray: The measurement matrix. """ - return np.array( - [ - [0, -vector[2], vector[1]], - [vector[2], 0, -vector[0]], - [-vector[1], vector[0], 0], - ] - ) - def quaternion_super_product(self, q1: np.ndarray, q2: np.ndarray) -> np.ndarray: - """Calculates the quaternion super product of two quaternions. + X_deltax = block_diag(np.eye(6), self.Q_delta_theta(), np.eye(9)) - Args: - q1 (np.ndarray): The first quaternion. - q2 (np.ndarray): The second quaternion. + H = self.Hx @ X_deltax + + return H + + def h(self) -> np.ndarray: + """ + Calculates the measurement model. Returns: - np.ndarray: The quaternion super product. + np.ndarray: The measurement model. """ - nu_0, eta_0_x, eta_0_y, eta_0_z = q1 - nu_1, eta_1_x, eta_1_y, eta_1_z = q2 + return self.nom_state.velocity - eta_0 = np.array([[eta_1_x, eta_1_y, eta_1_z]]).T - eta_1 = np.array([[eta_0_x, eta_0_y, eta_0_z]]).T - eta_new = ( - nu_1 * eta_0 + nu_0 * eta_1 + np.dot(self.skew_symmetric(eta_0), eta_1) - ) - nu_new = nu_0 * nu_1 - np.dot(eta_0.T, eta_1) - q_new = np.array([nu_new, eta_new[0], eta_new[1], eta_new[2]]) - q_new /= np.linalg.norm(q_new) + def nominal_state_discrete(self, imu_data: Measurement) -> None: + """ + Calculates the next nominal state using the discrete-time process model defined in: + Joan Solà. Quaternion kinematics for the error-state Kalman filter. + Chapter: 5.4.1 The nominal state kinematics - return q_new + Args: + imu_data (np.ndarray): The IMU data. + """ - def van_loan_discretization( - self, A_c: np.ndarray, G_c: np.ndarray - ) -> tuple[np.ndarray, np.ndarray]: - """Calculates the Van Loan discretization of a continuous-time system. + # Rectify measurements. + acc_rect = imu_data.acceleration - self.nom_state.acceleration_bias + gyro_rect = imu_data.angular_velocity - self.nom_state.gyro_bias + + R = self.nom_state.R_q() + + self.nom_state.position = self.nom_state.position + self.nom_state.velocity * self.dt + 0.5 * (R @ acc_rect + self.nom_state.g) * self.dt**2 + self.nom_state.velocity = self.nom_state.velocity + (R @ acc_rect + self.nom_state.g) * self.dt + self.nom_state.orientation = quaternion_product(self.nom_state.orientation, angle_axis_to_quaternion(gyro_rect * self.dt)) + self.nom_state.acceleration_bias = np.exp(-self.p_accBias * self.dt) * self.nom_state.acceleration_bias + self.nom_state.gyro_bias = np.exp(-self.p_gyroBias * self.dt) * self.nom_state.gyro_bias + self.nom_state.g = self.nom_state.g + + def van_loan_discretization(self, A_c, G_c) -> Tuple[np.ndarray, np.ndarray]: + """ + Calculates the Van Loan discretization of a continuous-time system. Args: A_c (np.ndarray): The A matrix. G_c (np.ndarray): The G matrix. Returns: - tuple: The A_d and GQG_d matrices. + Tuple: The A_d and GQG_d matrices. """ - GQG_T = np.dot(np.dot(G_c, self.Q_process_noise), G_c.T) * self.dt + + GQG_T = np.dot(np.dot(G_c, self.Q), G_c.T) matrix_exp = ( - np.block([[A_c, GQG_T], [np.zeros((A_c.shape[0], A_c.shape[0])), A_c.T]]) + np.block([[- A_c, GQG_T], [np.zeros((A_c.shape[0], A_c.shape[0])), np.transpose(A_c)]]) * self.dt ) van_loan_matrix = expm(matrix_exp) - V1 = van_loan_matrix[A_c.shape[0] :, A_c.shape[0] :] - V2 = van_loan_matrix[: A_c.shape[0], A_c.shape[0] :] + V1 = van_loan_matrix[A_c.shape[0]:, A_c.shape[0]:] + V2 = van_loan_matrix[:A_c.shape[0], A_c.shape[0]:] A_d = V1.T GQG_d = A_d @ V2 return A_d, GQG_d - def nominal_state_update( - self, current_state: StateVector_quaternion, imu_reading: np.ndarray - ) -> StateVector_quaternion: - """Updates the nominal state of the system. + def error_state_prediction(self, imu_data: Measurement) -> None: - Args: - current_state (np.ndarray): The current state of the system. - imu_reading (np.ndarray): The IMU reading. + # Rectify measurements. + acc_rect = imu_data.acceleration - self.nom_state.acceleration_bias + gyro_rect = imu_data.angular_velocity - self.nom_state.gyro_bias - Returns: - np.ndarray: The updated nominal state. - """ - # Defining the IMU readings - imu_acceleration = imu_reading[0:3] - imu_gyro = imu_reading[3:6] - - # Define the derivative of the state - current_state_dot = StateVector_quaternion() - - # Define the state derivates - current_state_dot.position = current_state.velocity - current_state_dot.velocity = ( - np.dot( - current_state.R_q(), - (imu_acceleration - current_state.acceleration_bias), - ) - + self.g - ) + R = self.nom_state.R_q() - # Define the quaternion derivatives - current_state_dot.orientation = 0.5 * self.quaternion_super_product( - current_state.orientation, - np.array([0, imu_gyro[0], imu_gyro[1], imu_gyro[2]]), - ) + A_c = np.zeros((18, 18)) - # Define the bias - current_state_dot.acceleration_bias = ( - -np.dot(self.P_ab, np.eye(3)) @ current_state.acceleration_bias - ) - current_state_dot.gyro_bias = ( - -np.dot(self.P_wb, np.eye(3)) @ current_state.gyro_bias - ) - - return current_state_dot.euler_forward(current_state, self.dt) - - def error_state_update( - self, - current_error_state: StateVector_euler, - current_state: StateVector_quaternion, - imu_reading: np.ndarray, - ) -> StateVector_euler: - """Updates the error state of the system. - - Args: - current_error_state (np.ndarray): The current error state of the system. - current_state (np.ndarray): The current state of the system. - imu_reading (np.ndarray): The IMU reading. - - Returns: - np.ndarray: The updated error state. - """ - # Define the derivative of the state - next_error_state = StateVector_euler() - - # Defining the IMU readings - imu_acceleration = imu_reading[0:3] - imu_gyro = imu_reading[3:6] - - A_c = np.zeros((15, 15)) A_c[0:3, 3:6] = np.eye(3) - A_c[3:6, 6:9] = -np.dot( - current_state.R_q(), - self.skew_symmetric(imu_acceleration - current_state.acceleration_bias), - ) - A_c[6:9, 6:9] = -self.skew_symmetric(imu_gyro - current_state.gyro_bias) - A_c[3:6, 9:12] = -current_state.R_q() + A_c[3:6, 6:9] = - R @ skew_matrix(acc_rect) + A_c[6:9, 6:9] = - skew_matrix(gyro_rect) + A_c[3:6, 9:12] = - R + A_c[9:12, 9:12] = -self.p_accBias * np.eye(3) + A_c[12:15, 12:15] = -self.p_gyroBias * np.eye(3) A_c[6:9, 12:15] = -np.eye(3) - A_c[9:12, 9:12] = -self.P_ab * np.eye(3) - A_c[12:15, 12:15] = -self.P_wb * np.eye(3) + A_c[3:6, 15:18] = np.eye(3) + + G_c = np.zeros((18, 12)) - G_c = np.zeros((15, 12)) - G_c[3:6, 0:3] = -current_state.R_q() + G_c[3:6, 0:3] = -R G_c[6:9, 3:6] = -np.eye(3) G_c[9:12, 6:9] = np.eye(3) G_c[12:15, 9:12] = np.eye(3) - # Van loan discretization - A_d, GQG_d = self.van_loan_discretization(A_c, G_c, self.dt) + A_d, GQG_d = self.van_loan_discretization(A_c, G_c) - # Inserting the new state and covariance - next_error_state.copy_state(current_error_state) - next_error_state.covariance = ( - np.dot(np.dot(A_d, current_error_state.covariance), A_d.T) + GQG_d - ) - - return next_error_state - - def H(self) -> np.ndarray: - """Calculates the measurement matrix. + self.error_state.covariance = (A_d @ self.error_state.covariance @ A_d.T + GQG_d) - Returns: - np.ndarray: The measurement matrix. + def measurement_update(self, dvl_measurement:Measurement) -> None: """ - # Define the measurement matrix - H = np.zeros((3, 15)) - - # For now assume only velocity is measured - H[0:3, 3:6] = np.eye(3) - - return H - - def prediction_from_estimates( - self, - current_state: StateVector_quaternion, - current_error_state: StateVector_euler, - imu_reading: np.ndarray, - ) -> StateVector_euler: - """Predicts the measurement from the current state and error state. + Updates the error state using the DVL measurement. + Joan Solà. Quaternion kinematics for the error-state Kalman filter. + Chapter: 6.1 eq. 274-276 Args: - current_state (StateVector_quaternion): The current state of the system. - current_error_state (StateVector_euler): The current error state of the system. - imu_reading (np.ndarray): The IMU reading. - - Returns: - StateVector_euler: The predicted measurement. + dvl_measurement (np.ndarray): The DVL measurement. """ - # Define the z_pred matrix - z_pred = MeasurementModel() - - # Define the z_pred values separately - z_pred_1 = current_state.velocity - z_pred_2 = 0 # Currently assuming no lever arm compensation - - # Combine the z_pred values - z_pred.measurement = z_pred_1 + z_pred_2 - - # Define the H matrix - z_pred.measurement_matrix = self.H() - R = self.R - z_pred.measurement_covariance = ( - np.dot( - np.dot(z_pred.measurement_matrix, current_error_state.covariance), - z_pred.measurement_matrix.T, - ) - + R - ) - - return z_pred - def measurement_update( - self, - error_state_pred: StateVector_euler, - z_pred: MeasurementModel, - dvl_measure: np.array, - ) -> StateVector_euler: - """Updates the error state of the system. + H = self.H() + P = self.error_state.covariance + R= dvl_measurement.aiding_covariance + K = P @ H.T @ np.linalg.inv(H @ P @ H.T + R) + self.error_state.fill_states(K @ (dvl_measurement.aiding - self.h())) + self.error_state.covariance = (np.eye(18) - K @ H) @ P - Args: - current_error_state (np.ndarray): The current error state of the system. - measurement (np.ndarray): The measurement. - - Returns: - np.ndarray: The updated error state. + def injection(self) -> None: """ - # Define new error state value - new_error_state = StateVector_euler() - - # Define the measurement matrix - innovation = dvl_measure - z_pred.measurement - H = z_pred.measurement_matrix - R = self.R - P = error_state_pred.covariance - S = z_pred.measurement_covariance - - # Kalman gain calculation - W = np.dot(P, np.linalg.solve(S, H).T) - new_error_state.fill_states(np.dot(W, innovation)) - - I_WH = np.eye(15) - np.dot(W, H) - new_error_state.covariance = np.dot(np.dot(I_WH, P), I_WH.T) + np.dot( - np.dot(W, R), W.T - ) - - return new_error_state - - def imu_update_states( - self, - current_pred_nom: StateVector_quaternion, - current_pred_err: StateVector_euler, - imu_readings: np.array, - ) -> tuple[StateVector_quaternion, StateVector_euler]: - """Calculates the predicted state using the IMU readings. - - Args: - current_pred_nom (StateVector_quaternion): The current nominal state. - current_pred_err (StateVector_euler): The current error state. - imu_readings (np.array): The IMU readings. - - Returns: - tuple: The predicted nominal state and the predicted error state. + Injects the error state into the nominal state to produce the estimated state. + Joan Solà. Quaternion kinematics for the error-state Kalman filter. + Chapter 6.2 eq. 282-283 + """ - pred_nom_state = self.nominal_state_update(current_pred_nom, imu_readings) - pred_err_state = self.error_state_update( - current_pred_err, current_pred_nom, imu_readings - ) - - return pred_nom_state, pred_err_state - - def dvl_update_states( - self, - current_pred_nom: StateVector_quaternion, - current_pred_err: StateVector_euler, - dvl_measure: np.array, - ) -> tuple[StateVector_quaternion, StateVector_euler]: - """Calculates the predicted state using the DVL readings. - - Args: - current_pred_nom (StateVector_quaternion): The current nominal state. - current_pred_err (StateVector_euler): The current error state. - dvl_measure (np.array): The DVL readings. - - Returns: - tuple: The predicted nominal state and the predicted error state. + + self.nom_state.position = self.nom_state.position + self.error_state.position + self.nom_state.velocity = self.nom_state.velocity + self.error_state.velocity + self.nom_state.orientation = quaternion_product(self.nom_state.orientation, euler_to_quat(self.error_state.orientation)) + self.nom_state.acceleration_bias = self.nom_state.acceleration_bias + self.error_state.acceleration_bias + self.nom_state.gyro_bias = self.nom_state.gyro_bias + self.error_state.gyro_bias + self.nom_state.g = self.nom_state.g + self.error_state.g + + def reset_error_state(self) -> None: + """ + Resets the error state after injection. + Joan Solà. Quaternion kinematics for the error-state Kalman filter. + Chapter 6.3 eq. 284-286 """ - z_pred = self.prediction_from_estimates( - current_pred_nom, current_pred_err, dvl_measure - ) - new_error_state = self.measurement_update(current_pred_err, z_pred, dvl_measure) - return current_pred_nom, new_error_state + G = np.eye(18) # Neglecting the delta_theta as this is most common in practice - def injection_and_reset( - self, next_state: StateVector_quaternion, next_error_state: StateVector_euler - ) -> tuple[StateVector_quaternion, StateVector_euler]: - """Injects the error state into the nominal state and resets the error state. + self.error_state.covariance = G @ self.error_state.covariance @ G.T + self.error_state.fill_states(np.zeros(18)) - Args: - next_state (StateVector_quaternion): The next nominal state. - next_error_state (StateVector_euler): The next error state. - - Returns: - tuple: The injected nominal state and the reset error state. + def imu_update(self, imu_data: Measurement) -> None: + """ + Updates the state using the IMU data. """ - # Define the new state - inj_state = StateVector_quaternion() - - # Injecting the error state - inj_state.position = next_state.position + next_error_state.position - inj_state.velocity = next_state.velocity + next_error_state.velocity - inj_state.orientation = self.quaternion_super_product( - next_state.orientation, - 0.5 - * np.array( - [ - 2, - next_error_state.orientation[0], - next_error_state.orientation[1], - next_error_state.orientation[2], - ] - ), - ) - inj_state.acceleration_bias = ( - next_state.acceleration_bias + next_error_state.acceleration_bias - ) - inj_state.gyro_bias = next_state.gyro_bias + next_error_state.gyro_bias - - # Resetting the error state - G = np.eye(15) - G[6:9, 6:9] = np.eye(3) - self.skew_symmetric( - 0.5 * next_error_state.orientation - ) - - next_error_state.covariance = np.dot( - np.dot(G, next_error_state.covariance), G.T - ) - next_error_state.fill_states(np.zeros(15)) - return inj_state, next_error_state + self.nominal_state_discrete(imu_data) + self.error_state_prediction(imu_data) + + def dvl_update(self, dvl_measurement: Measurement) -> None: + """ + Updates the state using the DVL measurement. + """ + + self.measurement_update(dvl_measurement) + self.injection() + self.reset_error_state() \ No newline at end of file diff --git a/navigation/eskf_python/eskf_python/eskf_python_node.py b/navigation/eskf_python/eskf_python/eskf_python_node.py index 5b860582e..ec206ab64 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_node.py +++ b/navigation/eskf_python/eskf_python/eskf_python_node.py @@ -4,7 +4,7 @@ from nav_msgs.msg import Odometry from rclpy.node import Node from rclpy.qos import QoSProfile, qos_profile_sensor_data -from sensor_msgs.msg import Imu, +from sensor_msgs.msg import Imu import numpy as np from geometry_msgs.msg import TwistWithCovarianceStamped diff --git a/navigation/eskf_python/eskf_python/eskf_python_utils.py b/navigation/eskf_python/eskf_python/eskf_python_utils.py new file mode 100644 index 000000000..9ea439982 --- /dev/null +++ b/navigation/eskf_python/eskf_python/eskf_python_utils.py @@ -0,0 +1,95 @@ +import numpy as np + +def skew_matrix(vector: np.ndarray) -> np.ndarray: + """ + Returns the skew symmetric matrix of a 3x1 vector. + """ + return np.array( + [ + [0, -vector[2], vector[1]], + [vector[2], 0, -vector[0]], + [-vector[1], vector[0], 0] + ] + ) + +def quaternion_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: + """Calculates the quaternion super product of two quaternions. + + Args: + q1 (np.ndarray): The first quaternion. + q2 (np.ndarray): The second quaternion. + + Returns: + np.ndarray: The quaternion super product. + """ + + eta_0, e_0_x, e_0_y, e_0_z = q1 + eta_1, e_1_x, e_1_y, e_1_z = q2 + + e_0 = np.array([e_0_x, e_0_y, e_0_z]) + e_1 = np.array([e_1_x, e_1_y, e_1_z]) + + eta_new = eta_0 * eta_1 - np.dot(e_0, e_1) + nu_new = e_1 * eta_0 + e_0 * eta_1 + np.cross(e_0, e_1) + + q_new = np.array([eta_new, nu_new[0], nu_new[1], nu_new[2]]) + q_new = q_new / np.linalg.norm(q_new) + + return q_new + +def angle_axis_to_quaternion(vector: np.ndarray) -> np.ndarray: + """Converts an angle-axis representation to a quaternion. + + Args: + vector (np.ndarray): The angle-axis representation. + + Returns: + np.ndarray: The quaternion representation. + """ + angle = np.linalg.norm(vector) + if angle < 1e-8: + return np.array([1, 0, 0, 0]) + else: + axis = vector / angle + + + q = np.zeros(4) + q[0] = np.cos(angle / 2) + q[1:] = np.sin(angle / 2) * axis + + return q + + +def R_from_angle_axis(vector: np.ndarray) -> np.ndarray: + """Calculates the rotation matrix from the angle-axis representation. + + Args: + vector (np.ndarray): The angle-axis representation. + + Returns: + np.ndarray: The rotation matrix. + """ + quaternion = angle_axis_to_quaternion(vector) + q0, q1, q2, q3 = quaternion + + R = np.array( + [ + [ + 1 - 2 * q2**2 - 2 * q3**2, + 2 * (q1 * q2 - q0 * q3), + 2 * (q0 * q2 + q1 * q3), + ], + [ + 2 * (q1 * q2 + q0 * q3), + 1 - 2 * q1**2 - 2 * q3**2, + 2 * (q2 * q3 - q0 * q1), + ], + [ + 2 * (q1 * q3 - q0 * q2), + 2 * (q0 * q1 + q2 * q3), + 1 - 2 * q1**2 - 2 * q2**2, + ], + ] + ) + + return R diff --git a/navigation/ukf_okid/ukf_python/ukf_okid_class copy.py b/navigation/eskf_python/eskf_python/ukf_okid_class.py similarity index 78% rename from navigation/ukf_okid/ukf_python/ukf_okid_class copy.py rename to navigation/eskf_python/eskf_python/ukf_okid_class.py index 86b7beb49..8444fd82e 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid_class copy.py +++ b/navigation/eskf_python/eskf_python/ukf_okid_class.py @@ -14,12 +14,11 @@ class StateQuat: orientation: np.ndarray = field(default_factory=lambda: np.array([1, 0, 0, 0])) velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) - okid_params: np.ndarray = field(default_factory=lambda: np.zeros(21)) - covariance: np.ndarray = field(default_factory=lambda: np.zeros((33, 33))) + covariance: np.ndarray = field(default_factory=lambda: np.zeros((12, 12))) def as_vector(self) -> np.ndarray: """Returns the StateVector as a numpy array.""" - return np.concatenate([self.position, self.orientation, self.velocity, self.angular_velocity, self.okid_params]) + return np.concatenate([self.position, self.orientation, self.velocity, self.angular_velocity]) def nu(self) -> np.ndarray: """Calculates the nu vector.""" @@ -42,9 +41,6 @@ def fill_states(self, state: np.ndarray) -> None: self.velocity = state[7:10] self.angular_velocity = state[10:13] - if len(state) > 13: - self.okid_params = state[13:] - def fill_states_different_dim(self, state: np.ndarray, state_euler: np.ndarray) -> None: """Fills states when the state vector has different dimensions than the default state vector.""" self.position = state[0:3] + state_euler[0:3] @@ -52,9 +48,6 @@ def fill_states_different_dim(self, state: np.ndarray, state_euler: np.ndarray) self.velocity = state[7:10] + state_euler[6:9] self.angular_velocity = state[10:13] + state_euler[9:12] - if len(state) > 13: - self.okid_params = state[13:] - def subtract(self, other: 'StateQuat') -> np.ndarray: """Subtracts two StateQuat objects, returning the difference with Euler angles.""" new_array = np.zeros(len(self.as_vector()) - 1) @@ -63,8 +56,6 @@ def subtract(self, other: 'StateQuat') -> np.ndarray: new_array[6:9] = self.velocity - other.velocity new_array[9:12] = self.angular_velocity - other.angular_velocity - new_array[12:] = self.okid_params - other.okid_params - return new_array def __add__(self, other: 'StateQuat') -> 'StateQuat': @@ -75,8 +66,6 @@ def __add__(self, other: 'StateQuat') -> 'StateQuat': new_state.velocity = self.velocity + other.velocity new_state.angular_velocity = self.angular_velocity + other.angular_velocity - new_state.okid_params = self.okid_params + other.okid_params - return new_state def __sub__(self, other: 'StateQuat') -> 'StateQuat': @@ -87,8 +76,6 @@ def __sub__(self, other: 'StateQuat') -> 'StateQuat': new_state.velocity = self.velocity - other.velocity new_state.angular_velocity = self.angular_velocity - other.angular_velocity - new_state.okid_params = self.okid_params - other.okid_params - return new_state.as_vector() def __rmul__(self, scalar: float) -> 'StateQuat': @@ -99,8 +86,6 @@ def __rmul__(self, scalar: float) -> 'StateQuat': new_state.velocity = scalar * self.velocity new_state.angular_velocity = scalar * self.angular_velocity - new_state.okid_params = scalar * self.okid_params - return new_state def insert_weights(self, weights: np.ndarray) -> np.ndarray: @@ -110,7 +95,6 @@ def insert_weights(self, weights: np.ndarray) -> np.ndarray: new_state.orientation = quaternion_error(self.orientation, euler_to_quat(weights[3:6])) new_state.velocity = self.velocity - weights[6:9] new_state.angular_velocity = self.angular_velocity - weights[9:12] - new_state.okid_params = self.okid_params - weights[12:] return new_state.as_vector() @@ -119,7 +103,6 @@ def add_without_quaternions(self, other: 'StateQuat') -> None: self.position += other.position self.velocity += other.velocity self.angular_velocity += other.angular_velocity - self.okid_params += other.okid_params @dataclass class MeasModel: @@ -131,7 +114,7 @@ class MeasModel: def H(self, state: StateQuat) -> 'MeasModel': """Calculates the measurement matrix.""" - H = np.zeros((3, 34)) + H = np.zeros((3, 13)) H[:, 7:10] = np.eye(3) z_i = MeasModel() z_i.measurement = np.dot(H, state.as_vector()) @@ -233,93 +216,6 @@ def euler_forward(self) -> StateQuat: self.state_vector.angular_velocity = self.state_vector_prev.angular_velocity + self.state_vector_dot.angular_velocity * self.dt return self.state_vector -@dataclass -class okid_model: - """ - A class defined for a general process model. - """ - state_vector: StateQuat = field(default_factory=StateQuat) - state_vector_dot: StateQuat = field(default_factory=StateQuat) - state_vector_prev: StateQuat = field(default_factory=StateQuat) - Control_input: np.ndarray = field(default_factory=lambda: np.zeros(6)) - mass_interia_matrix: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) - m: float = 0.0 - inertia: np.ndarray = field(default_factory=lambda: np.zeros((3,3))) - r_b_bg: np.ndarray = field(default_factory=lambda: np.zeros(3)) - dt: float = 0.0 - prev_position_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) - prev_orientation_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) - D_matrix: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) - added_mass: np.ndarray = field(default_factory=lambda: np.zeros(6)) - - def R(self) -> np.ndarray: - """Calculates the rotation matrix.""" - nu, e_1, e_2, e_3 = self.state_vector.orientation - R = np.array([ - [1 - 2 * e_2 ** 2 - 2 * e_3 ** 2, 2 * e_1 * e_2 - 2 * nu * e_3, 2 * e_1 * e_3 + 2 * nu * e_2], - [2 * e_1 * e_2 + 2 * nu * e_3, 1 - 2 * e_1 ** 2 - 2 * e_3 ** 2, 2 * e_2 * e_3 - 2 * nu * e_1], - [2 * e_1 * e_3 - 2 * nu * e_2, 2 * e_2 * e_3 + 2 * nu * e_1, 1 - 2 * e_1 ** 2 - 2 * e_2 ** 2] - ]) - return R - - def T(self) -> np.ndarray: - """Calculates the transformation matrix.""" - nu, e_1, e_2, e_3 = self.state_vector.orientation - T = 0.5 * np.array([ - [-e_1, -e_2, -e_3], - [nu, -e_3, e_2], - [e_3, nu, -e_1], - [-e_2, e_1, nu] - ]) - return T - - def Crb(self) -> np.ndarray: - """Calculates the Coriolis matrix.""" - ang_vel = self.state_vector.angular_velocity - ang_vel_skew = skew_symmetric(ang_vel) - lever_arm_skew = skew_symmetric(self.r_b_bg) - Crb = np.zeros((6, 6)) - Crb[0:3, 0:3] = self.m * ang_vel_skew - Crb[3:6, 3:6] = -skew_symmetric(np.dot(self.inertia, ang_vel)) - Crb[0:3, 3:6] = -self.m * np.dot(ang_vel_skew, lever_arm_skew) - Crb[3:6, 0:3] = self.m * np.dot(lever_arm_skew, ang_vel_skew) - return Crb - - def D(self, linear_damping: np.ndarray, nonlinear_damping: np.ndarray) -> np.ndarray: - """Calculates the damping matrix.""" - D_l = -np.diag(linear_damping) - D_nl = -np.diag(nonlinear_damping) * np.abs(self.state_vector.nu()) - return D_l + D_nl - - def model_prediction(self, state: StateQuat) -> None: - """Calculates the model of the system.""" - self.state_vector = state - - self.inertia = np.diag(self.state_vector.okid_params[:3]) - self.mass_interia_matrix[3:6, 3:6] = self.inertia - self.D_matrix = self.D(self.state_vector.okid_params[3:9], self.state_vector.okid_params[9:15]) - self.added_mass = self.state_vector.okid_params[15:21] - - self.state_vector_dot.position = np.dot(self.R(), self.state_vector.velocity) - self.state_vector_dot.orientation = np.dot(self.T(), self.state_vector.angular_velocity) - - Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ (self.Control_input - np.dot(self.Crb(), self.state_vector.nu()) - np.dot(self.D_matrix, self.state_vector.nu())) - self.state_vector_dot.velocity = Nu[:3] - self.state_vector_dot.angular_velocity = Nu[3:] - - self.state_vector_dot.okid_params = np.zeros(21) - - def euler_forward(self) -> StateQuat: - """Calculates the forward Euler integration.""" - self.state_vector.position = self.state_vector_prev.position + self.state_vector_dot.position * self.dt - self.state_vector.orientation = quat_norm(self.state_vector_prev.orientation + self.state_vector_dot.orientation * self.dt) - self.state_vector.velocity = self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt - self.state_vector.angular_velocity = self.state_vector_prev.angular_velocity + self.state_vector_dot.angular_velocity * self.dt - self.state_vector.okid_params = self.state_vector_prev.okid_params - return self.state_vector - - - def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: """ Converts Euler angles to a quaternion diff --git a/navigation/sp_ukf_python/CMakeLists.txt b/navigation/sp_ukf_python/CMakeLists.txt deleted file mode 100644 index a40f065cd..000000000 --- a/navigation/sp_ukf_python/CMakeLists.txt +++ /dev/null @@ -1,33 +0,0 @@ -cmake_minimum_required(VERSION 3.8) -project(sp_ukf_python) - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -find_package(ament_cmake_python REQUIRED) -find_package(rclpy REQUIRED) -find_package(vortex_msgs REQUIRED) -find_package(geometry_msgs REQUIRED) - -ament_python_install_package(${PROJECT_NAME}) - -install(DIRECTORY - launch - config - DESTINATION share/${PROJECT_NAME} -) - -install(PROGRAMS - sp_ukf_python/sp_ukf_python_node.py - DESTINATION lib/${PROJECT_NAME} -) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - find_package(ament_cmake_pytest REQUIRED) - set(ament_cmake_copyright_FOUND TRUE) - set(ament_cmake_cpplint_FOUND TRUE) -endif() - -ament_package() diff --git a/navigation/sp_ukf_python/README.md b/navigation/sp_ukf_python/README.md deleted file mode 100644 index e69de29bb..000000000 diff --git a/navigation/sp_ukf_python/config/sp_ukf_python.yaml b/navigation/sp_ukf_python/config/sp_ukf_python.yaml deleted file mode 100644 index d3d18145d..000000000 --- a/navigation/sp_ukf_python/config/sp_ukf_python.yaml +++ /dev/null @@ -1,3 +0,0 @@ -/**: - ros__parameters: - sp_ukf_python_node: diff --git a/navigation/sp_ukf_python/launch/ukf.launch.py b/navigation/sp_ukf_python/launch/ukf.launch.py deleted file mode 100644 index fdd3f07e6..000000000 --- a/navigation/sp_ukf_python/launch/ukf.launch.py +++ /dev/null @@ -1,22 +0,0 @@ -import os - -from ament_index_python.packages import get_package_share_directory -from launch import LaunchDescription -from launch_ros.actions import Node - - -def generate_launch_description(): - sp_ukf_python_node = Node( - package='sp_ukf_python', - executable='sp_ukf_python_node.py', - name='sp_ukf_python_node', - parameters=[ - os.path.join( - get_package_share_directory('sp_ukf_python'), - 'config', - 'sp_ukf_python.yaml', - ), - ], - output='screen', - ) - return LaunchDescription([sp_ukf_python_node]) diff --git a/navigation/sp_ukf_python/package.xml b/navigation/sp_ukf_python/package.xml deleted file mode 100644 index 6aa4edbc0..000000000 --- a/navigation/sp_ukf_python/package.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - sp_ukf_python - 1.0.0 - This package provides the implementation of a sigma point based Unscented Error-state Kalman Filter - talhanc - MIT - - ament_cmake_python - - rclpy - python-transforms3d-pip - geometry_msgs - vortex_msgs - - python3-pytest - - - - ament_cmake - - diff --git a/navigation/sp_ukf_python/sp_ukf_python/__init__.py b/navigation/sp_ukf_python/sp_ukf_python/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py deleted file mode 100644 index 819cb737d..000000000 --- a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python.py +++ /dev/null @@ -1,495 +0,0 @@ - -import numpy as np -from scipy.linalg import expm -from sp_ukf_python_class import StateVector_euler, StateVector_quaternion -from sp_ukf_python_utils import quaternion_super_product, skew_symmetric - - -class ErrorStateUnscentedKalmanFilter: - def __init__( - self, - P_ab: float, - P_wb: float, - Q: np.ndarray, - lever_arm: np.array, - R: np.ndarray, - g: float, - dt: float, - ) -> None: - self.P_ab = P_ab - self.P_wb = P_wb - self.Q_process_noise = Q - self.lever_arm = lever_arm - self.R = R - self.g = np.array([0, 0, g]) - self.dt = dt - self.y_i = np.zeros((15, 2 * 15)) - self.W = np.zeros(2 * 15 + 1) - - def mean_set(self, set: np.ndarray) -> np.ndarray: - """Calculates the mean of a set of values. - - Args: - set (np.ndarray): The set of values. - - Returns: - np.ndarray: The mean of the set. - """ - # Define the number of sigma points based on columns - n = set.shape[0] - mean_value = np.zeros(n) - - for i in range(2 * n + 1): - mean_value += (1/(2 * n + 1)) * set[:, i] - - return mean_value - - def weighted_mean_set(self, set: np.ndarray, weight: np.ndarray) -> np.ndarray: - """Calculates the mean of a set of values. - - Args: - set (np.ndarray): The set of values. - - Returns: - np.ndarray: The mean of the set. - """ - # Define the number of columns - n = set.shape[0] - mean_value = np.zeros(n) - - for i in range(2 * n + 1): - mean_value += weight[i] * set[:, i] - - return mean_value - - def covariance_set(self, mean: np.ndarray, set: np.ndarray) -> np.ndarray: - """Calculate the covarince of a set of sigmapoints - - Args: - mean (np.ndarray): The mean of the set. - set (np.ndarray): The set of values. - - Returns: - np.ndarray: The covariance of the set. - """ - n = set.shape[0] - covariance_set = np.zeros((n, n)) - - for i in range(2 * n + 1): - vector = StateVector_euler() - vector.position = set[:, i][:3] - vector.velocity = set[:, i][3:6] - vector.orientation = set[:, i][6:9] - vector.acceleration_bias = set[:, i][9:12] - vector.gyro_bias = set[:, i][12:] - - W_i = vector - mean - - covariance_set += (1 / (2 * n + 1)) * np.outer(W_i, W_i) - - return covariance_set - - def cross_covariance_set( - self, - mean: np.ndarray, - set: np.ndarray, - mean_2: np.ndarray, - set_2: np.ndarray, - weight: np.ndarray, - ) -> np.ndarray: - """Calculate the cross covariance of a set of sigmapoints - - Args: - mean (np.ndarray): The mean of the set. - set (np.ndarray): The set of values. - mean_2 (np.ndarray): The mean of the second set. - set_2 (np.ndarray): The second set of values. - - Returns: - np.ndarray: The cross covariance of the set. - """ - n_x = set.shape[0] - n_z = set_2.shape[0] - covariance_mat = np.zeros((n_x, n_z)) - - for i in range(2 * n_x + 1): - # parse the 15-dim error state - err_vec = set[:, i] # shape (15,) - W_i = err_vec - mean # shape (15,) - - # parse the 3-dim measurement - meas_vec = set_2[:, i] # shape (3,) - W_i_2 = meas_vec - mean_2 # shape (3,) - - # outer product -> shape (15,3) - covariance_mat += weight[i] * np.outer(W_i, W_i_2) - - return covariance_mat - - def weighted_covariance_set( - self, mean: np.ndarray, set: np.ndarray, weight: np.ndarray - ) -> np.ndarray: - """Calculate the covarince of a set of sigmapoints - - Args: - mean (np.ndarray): The mean of the set. - set (np.ndarray): The set of values. - - Returns: - np.ndarray: The covariance of the set. - """ - n = set.shape[0] - covariance_set = np.zeros((n, n)) - - for i in range(2 * n + 1): - vector = StateVector_euler() - vector.position = set[:, i][:3] - vector.velocity = set[:, i][3:6] - vector.orientation = set[:, i][6:9] - vector.acceleration_bias = set[:, i][9:12] - vector.gyro_bias = set[:, i][12:] - - W_i = vector - mean - covariance_set += weight[i] * np.outer(W_i, W_i) - - return covariance_set - - def generate_sigma_points( - self, error_state: StateVector_euler, Q_process_noise - ) -> tuple[list[StateVector_euler], np.ndarray]: - """Generates the sigma points for the UKF - This is done using the Cholesky decomposition method - """ - n = len(error_state.covariance) - kappa = 3 - n - - S = np.linalg.cholesky(error_state.covariance + Q_process_noise) - - S_scaled = np.sqrt(n + kappa) * S - - weighted_points = np.concatenate((S_scaled, -S_scaled), axis=1) - - sigma_points = [StateVector_euler() for _ in range(2 * n + 1)] - W = np.zeros(2 * n + 1) - - sigma_points[0].fill_states(error_state.as_vector()) - W[0] = kappa / (n + kappa) - - for i in range(2 * n): - sigma_points[i + 1].fill_states(error_state + weighted_points[:, i]) - W[i + 1] = 1 / (2 * (n + kappa)) - - self.W = W - return sigma_points, W - - def nominal_state_update( - self, current_state: StateVector_quaternion, imu_reading: np.ndarray - ) -> StateVector_quaternion: - """Updates the nominal state of the system. - - Args: - current_state (np.ndarray): The current state of the system. - imu_reading (np.ndarray): The IMU reading. - - Returns: - np.ndarray: The updated nominal state. - """ - # Defining the IMU readings - imu_acceleration = imu_reading[0:3] - imu_gyro = imu_reading[3:6] - - # Define the derivative of the state - current_state_dot = StateVector_quaternion() - - # Define the state derivates - current_state_dot.position = current_state.velocity - current_state_dot.velocity = ( - np.dot( - current_state.R_q(), - (imu_acceleration - current_state.acceleration_bias), - ) - + self.g - ) - - # Define the quaternion derivatives - current_state_dot.orientation = 0.5 * quaternion_super_product( - current_state.orientation, - np.array( - [ - 0, - imu_gyro[0] - current_state.gyro_bias[0], - imu_gyro[1] - current_state.gyro_bias[1], - imu_gyro[2] - current_state.gyro_bias[2], - ] - ), - ) - - # Define the bias - current_state_dot.acceleration_bias = ( - -np.dot(self.P_ab, np.eye(3)) @ current_state.acceleration_bias - ) - current_state_dot.gyro_bias = ( - -np.dot(self.P_wb, np.eye(3)) @ current_state.gyro_bias - ) - - return current_state_dot.euler_forward(current_state, self.dt) - - def error_state_update( - self, - current_error_state: StateVector_euler, - current_state: StateVector_quaternion, - imu_reading: np.ndarray, - ) -> np.ndarray: - """Updates the error state of the system. - - Args: - current_error_state (np.ndarray): The current error state of the system. - current_state (np.ndarray): The current state of the system. - imu_reading (np.ndarray): The IMU reading. - - Returns: - np.ndarray: The updated error state. - """ - # Defining the IMU readings - imu_acceleration = imu_reading[0:3] - imu_gyro = imu_reading[3:6] - - A_c = np.zeros((15, 15)) - A_c[0:3, 3:6] = np.eye(3) - A_c[3:6, 6:9] = -np.dot( - current_state.R_q(), - skew_symmetric(imu_acceleration - current_state.acceleration_bias), - ) - A_c[6:9, 6:9] = -skew_symmetric(imu_gyro - current_state.gyro_bias) - A_c[3:6, 9:12] = -current_state.R_q() - A_c[6:9, 12:15] = -np.eye(3) - A_c[9:12, 9:12] = -self.P_ab * np.eye(3) - A_c[12:15, 12:15] = -self.P_wb * np.eye(3) - - # Exact matrix exponential - A_d = expm(A_c * self.dt) - - next_error_state = A_d @ current_error_state.as_vector() - - return next_error_state - - def unscented_transform( - self, - sigma_points: list[StateVector_euler], - current_state: StateVector_quaternion, - imu_reading: np.ndarray, - ) -> StateVector_euler: - """Performs the Unscented Transform - This is the corresponding to a preditction step in the EKF - """ - n = len(sigma_points[0].as_vector()) - - self.y_i = np.zeros((n, 2 * n + 1)) - - for i in range(2 * n + 1): - self.y_i[:, i] = self.error_state_update( - sigma_points[i], current_state, imu_reading - ) - - error_state_estimate = StateVector_euler() - - x = self.weighted_mean_set(self.y_i, self.W) - - error_state_estimate.fill_states(x) - error_state_estimate.covariance = self.weighted_covariance_set(x, self.y_i, self.W) - - return error_state_estimate - - def H(self) -> np.ndarray: - """Calculates the measurement matrix. - - Returns: - np.ndarray: The measurement matrix. - """ - # Define the measurement matrix (error state is 15-dim) - H = np.zeros((3, 16)) - - # For now assume only velocity is measured (located at indices 3:6) - H[:, 3:6] = np.eye(3) - - return H - - def injection( - self, - current_state_nom: StateVector_quaternion, - current_state_error: StateVector_euler, - ) -> StateVector_quaternion: - """Injects the error state into the nominal state - - Args: - current_state_nom (StateVector_quaternion): The current nominal state - current_state_error (StateVector_euler): The current error state - - Returns: - StateVector_quaternion: The updated nominal state - """ - inj_state = StateVector_quaternion() - - inj_state.position = current_state_nom.position + current_state_error.position - inj_state.velocity = current_state_nom.velocity + current_state_error.velocity - inj_state.orientation = quaternion_super_product( - current_state_nom.orientation, - 0.5 - * np.array( - [ - 2, - current_state_error.orientation[0], - current_state_error.orientation[1], - current_state_error.orientation[2], - ] - ), - ) - inj_state.acceleration_bias = ( - current_state_nom.acceleration_bias + current_state_error.acceleration_bias - ) - inj_state.gyro_bias = ( - current_state_nom.gyro_bias + current_state_error.gyro_bias - ) - - return inj_state - - def measurement_update( - self, - sigma_points: list[StateVector_euler], - current_nom_state: StateVector_quaternion, - current_error_state: StateVector_euler, - dvl_data: np.ndarray, - Weight: np.ndarray, - ) -> StateVector_euler: - """Updates the state vector with the DVL data - """ - H = self.H() - R = self.R - - n = len(sigma_points[0].as_vector()) - - Z_i = np.zeros((H.shape[0], 2 * n + 1)) - - for i in range(2 * n + 1): - injected_state = self.injection(current_nom_state, sigma_points[i]) - Z_i[:, i] = np.dot(H, injected_state.as_vector()) - - z = self.weighted_mean_set(Z_i, Weight) - S = self.weighted_covariance_set(z, Z_i, Weight) - - x = self.mean_set(self.y_i) - - innovation = dvl_data - z - - P_innovation = S + R - - P_xz = self.cross_covariance_set(x, self.y_i, z, Z_i, Weight) - - # Kalman gain - K_k = np.dot(P_xz, np.linalg.inv(P_innovation)) - - updated_error_state = StateVector_euler() - - # Update the state - updated_error_state.fill_states(x + np.dot(K_k, innovation)) - - # Update the covariance - updated_error_state.covariance = current_error_state.covariance - np.dot( - K_k, np.dot(P_innovation, K_k.T) - ) - - return updated_error_state - - def imu_update_states( - self, - current_state_nom: StateVector_quaternion, - current_state_error: StateVector_euler, - imu_data: np.ndarray, - ) -> tuple[StateVector_quaternion, StateVector_euler]: - """Updates the state vector with the IMU data - - Args: - current_state_nom (StateVector_quaternion): The current nominal state - current_state_error (StateVector_euler): The current error state - imu_data (np.ndarray): The IMU data - - Returns: - tuple[StateVector_quaternion, StateVector_euler]: The updated nominal and error states - - """ - # Update the nominal state - current_state_nom = self.nominal_state_update(current_state_nom, imu_data) - - # Generate the sigma points - sigma_points, _ = self.generate_sigma_points( - current_state_error, self.Q_process_noise - ) - - # Update the error state - current_state_error = self.unscented_transform( - sigma_points, current_state_nom, imu_data - ) - - return current_state_nom, current_state_error - - def dvl_update_states( - self, - current_state_nom: StateVector_quaternion, - current_state_error: StateVector_euler, - dvl_data: np.ndarray, - imu_data: np.ndarray, - ) -> tuple[StateVector_quaternion, StateVector_euler]: - """Update the error state given the DVL data - - Args: - current_state_nom (StateVector_quaternion): The current nominal state - current_state_error (StateVector_euler): The current error state - dvl_data (np.ndarray): The DVL data to update the state with - - Returns: - tuple[StateVector_quaternion, StateVector_euler]: The updated nominal and error states - """ - # Generate the sigma points - sigma_points, weight = self.generate_sigma_points( - current_state_error, self.Q_process_noise - ) - - # Update the error state - current_state_error = self.unscented_transform( - sigma_points, current_state_nom, imu_data - ) - - # Update the error state - current_state_error = self.measurement_update( - sigma_points, current_state_nom, current_state_error, dvl_data, weight - ) - - return current_state_nom, current_state_error - - def inject_and_reset( - self, - current_state_nom: StateVector_quaternion, - current_state_error: StateVector_euler, - ) -> tuple[StateVector_quaternion, StateVector_euler]: - """Injects the error state into the nominal state and resets the error state - - Args: - current_state_nom (StateVector_quaternion): The current nominal state - current_state_error (StateVector_euler): The current error state - - Returns: - tuple[StateVector_quaternion, StateVector_euler]: The updated nominal and error states - """ - inj_state = self.injection(current_state_nom, current_state_error) - - G = np.eye(15) - G[6:9, 6:9] = np.eye(3) - skew_symmetric(0.5 * current_state_error.orientation) - - current_state_error.covariance = np.dot( - np.dot(G, current_state_error.covariance), G.T - ) - current_state_error.covariance += np.eye(15) - - current_state_error.fill_states(np.zeros(15)) - - return inj_state, current_state_error diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py deleted file mode 100644 index f8ede884d..000000000 --- a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_class.py +++ /dev/null @@ -1,292 +0,0 @@ -from dataclasses import dataclass, field - -import numpy as np -from sp_ukf_python_utils import ( - euler_rotation_quaternion, - quaternion_error, - quaternion_super_product, - ssa, - quat_norm, -) - - -@dataclass -class StateVector_quaternion: - position: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Position vector (x, y, z) - velocity: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Velocity vector (u, v, w) - orientation: np.ndarray = field( - default_factory=lambda: np.zeros(4) - ) # Orientation quaternion (w, x, y, z) - acceleration_bias: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Acceleration bias vector (b_ax, b_ay, b_az) - gyro_bias: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Gyro bias vector (b_gx, b_gy, b_gz) - - def as_vector(self) -> np.ndarray: - """Calculates the state vector. - - Returns: - np.ndarray: The state vector. - """ - return np.concatenate( - [ - self.position, - self.velocity, - self.orientation, - self.acceleration_bias, - self.gyro_bias, - ] - ) - - def fill_states(self, state: np.ndarray) -> None: - """Fills the state vector with the values from a numpy array. - - Args: - state (np.ndarray): The state vector. - """ - if len(state) == 15: - self.position = state[0:3] - self.velocity = state[3:6] - self.orientation = state[6:10] - self.acceleration_bias = state[10:13] - self.gyro_bias = state[13:] - else: - self.position = state[0:3] - self.velocity = state[3:6] - self.orientation = euler_rotation_quaternion(state[6:9]) - self.acceleration_bias = state[9:12] - self.gyro_bias = state[12:] - - def R_q(self) -> np.ndarray: - """Calculates the rotation matrix from the orientation quaternion. - - Returns: - np.ndarray: The rotation matrix. - """ - q0, q1, q2, q3 = self.orientation - R = np.array( - [ - [ - 1 - 2 * q2**2 - 2 * q3**2, - 2 * (q1 * q2 - q0 * q3), - 2 * (q0 * q2 + q1 * q3), - ], - [ - 2 * (q1 * q2 + q0 * q3), - 1 - 2 * q1**2 - 2 * q3**2, - 2 * (q2 * q3 - q0 * q1), - ], - [ - 2 * (q1 * q3 - q0 * q2), - 2 * (q0 * q1 + q2 * q3), - 1 - 2 * q1**2 - 2 * q2**2, - ], - ] - ) - - return R - - def euler_forward( - self, current_state: 'StateVector_quaternion', dt: float - ) -> 'StateVector_quaternion': - # Define the new state - new_state = StateVector_quaternion() - - # Define the state derivatives - new_state.position = current_state.position + self.position * dt - new_state.velocity = current_state.velocity + self.velocity * dt - new_state.orientation = quat_norm(current_state.orientation + self.orientation * dt) - new_state.acceleration_bias = ( - current_state.acceleration_bias + self.acceleration_bias * dt - ) - new_state.gyro_bias = current_state.gyro_bias + self.gyro_bias * dt - - # Normalize the orientation quaternion - new_state.orientation /= np.linalg.norm(new_state.orientation) - - return new_state - - def __sub__(self, other: 'StateVector_quaternion') -> np.ndarray: - """Subtracts two StateVector_quaternion objects. - - Args: - other (StateVector_quaternion): The other StateVector_quaternion object. - - Returns: - np.ndarray: The difference between the two StateVector_quaternion objects. - """ - position_diff = self.position - other.position - velocity_diff = self.velocity - other.velocity - orientation_diff = quaternion_error(self.orientation, other.orientation) - acceleration_bias_diff = self.acceleration_bias - other.acceleration_bias - gyro_bias_diff = self.gyro_bias - other.gyro_bias - - return np.concatenate( - [ - position_diff, - velocity_diff, - orientation_diff, - acceleration_bias_diff, - gyro_bias_diff, - ] - ) - - def __add__(self, other: 'np.ndarray') -> 'np.ndarray': - """Adds a numpy array to this StateVector_quaternion. - - Args: - other (np.ndarray): The numpy array to add. - - Returns: - np.ndarray: The result of the addition. - """ - # Construct the quaternion from the array - add_to_position = other[:3] - add_to_orientation = euler_rotation_quaternion(other[6:10]) - - new_position = self.position + add_to_position - new_velcoity = self.velocity + other[3:6] - new_orientation = quaternion_super_product(self.orientation, add_to_orientation) - new_acceleration_bias = self.acceleration_bias + other[10:13] - new_gyro_bias = self.gyro_bias + other[13:] - - return np.concatenate( - [ - new_position, - new_velcoity, - new_orientation, - new_acceleration_bias, - new_gyro_bias, - ] - ) - - -@dataclass -class StateVector_euler: - position: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Position vector (x, y, z) - velocity: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Velocity vector (u, v, w) - orientation: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Orientation angles (roll, pitch, yaw) - acceleration_bias: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Acceleration bias vector (b_ax, b_ay, b_az) - gyro_bias: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Gyro bias vector (b_gx, b_gy, b_gz) - covariance: np.ndarray = field( - default_factory=lambda: np.zeros((15, 15)) - ) # Covariance matrix - - def as_vector(self) -> np.ndarray: - """Calculates the state estimate vector. - - Returns: - np.ndarray: The state estimate vector. - """ - return np.concatenate( - [ - self.position, - self.velocity, - self.orientation, - self.acceleration_bias, - self.gyro_bias, - ] - ) - - def fill_states(self, state: np.ndarray) -> None: - """Fills the state vector with the values from a numpy array. - - Args: - state (np.ndarray): The state vector. - """ - self.position = state[0:3] - self.velocity = state[3:6] - self.orientation = state[6:9] - self.acceleration_bias = state[9:12] - self.gyro_bias = state[12:15] - - def copy_state(self, wanted_state: 'StateVector_euler') -> None: - """Copies the state from a StateVector object into the current StateVector object. - - Args: - wanted_state (StateVector_euler): The quaternion state to copy from. - """ - self.position = wanted_state.position - self.velocity = wanted_state.velocity - self.orientation = wanted_state.orientation - self.acceleration_bias = wanted_state.acceleration_bias - self.gyro_bias = wanted_state.gyro_bias - - def __add__(self, other: 'np.ndarray') -> 'np.ndarray': - """Adds a numpy array to this StateVector_quaternion. - - Args: - other (np.ndarray): The numpy array to add. - - Returns: - np.ndarray: The result of the addition. - """ - new_position = self.position + other[:3] - new_velcoity = self.velocity + other[3:6] - new_orientation = self.orientation + other[6:9] - new_acceleration_bias = self.acceleration_bias + other[9:12] - new_gyro_bias = self.gyro_bias + other[12:] - - return np.concatenate( - [ - new_position, - new_velcoity, - new_orientation, - new_acceleration_bias, - new_gyro_bias, - ] - ) - - def __sub__(self, other_state: 'StateVector_euler') -> 'StateVector_euler': - """Subtracts two StateVector_euler objects. - - Args: - other (StateVector_euler): The other StateVector_euler object. - - Returns: - StateVector_euler: The difference between the two StateVector_euler objects. - """ - position_diff = self.position - other_state[:3] - velocity_diff = self.velocity - other_state[3:6] - orientation_diff = ssa(self.orientation - other_state[6:9]) - acceleration_bias_diff = self.acceleration_bias - other_state[9:12] - gyro_bias_diff = self.gyro_bias - other_state[12:] - - return np.concatenate( - [ - position_diff, - velocity_diff, - orientation_diff, - acceleration_bias_diff, - gyro_bias_diff, - ] - ) - - -@dataclass -class MeasurementModel: - measurement: np.ndarray = field( - default_factory=lambda: np.zeros(6) - ) # Measurement vector - measurement_matrix: np.ndarray = field( - default_factory=lambda: np.zeros((6, 15)) - ) # Measurement matrix - measurement_covariance: np.ndarray = field( - default_factory=lambda: np.zeros((6, 6)) - ) # Measurement noise matrix diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_node.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_node.py deleted file mode 100644 index 103528ef2..000000000 --- a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_node.py +++ /dev/null @@ -1,137 +0,0 @@ -#!/usr/bin/env python3 - -import rclpy -from nav_msgs.msg import Odometry -from rclpy.node import Node -from rclpy.qos import QoSProfile, qos_profile_sensor_data -from sensor_msgs.msg import Imu, -import numpy as np -from geometry_msgs.msg import TwistWithCovarianceStamped - -# NEED TO CHANGE THIS TO THE CORRECT PATH -from eskf_python.eskf_python_filter import ( - ErrorStateKalmanFilter, - MeasurementModel, - StateVector_euler, - StateVector_quaternion, -) - -qos_profile = QoSProfile( - depth=1, - history=qos_profile_sensor_data.history, - reliability=qos_profile_sensor_data.reliability, -) - - -class ESKalmanFilterNode(Node): - def __init__(self): - super().__init__("sp_ukf_python_node") - - # This callback will supply information from the IMU (Inertial Measurement Unit) 1000 Hz - self.imu_subscriber_ = self.create_subscription( - Imu, '/orca/imu', self.imu_callback, qos_profile=qos_profile - ) - - self.twist_dvl_subscriber_ = self.create_subscription( - TwistWithCovarianceStamped, '/dvl/twist', self.filter_callback, qos_profile=qos_profile - ) - - # This publisher will publish the estimtaed state of the vehicle - self.state_publisher_ = self.create_publisher( - Odometry, '/orca/odom', qos_profile=qos_profile - ) - - self.eskf_modual = ErrorStateKalmanFilter() - self.current_state_nom = StateVector_quaternion() - self.current_state_error = StateVector_euler() - self.measurement_pred = MeasurementModel() - self.odom_msg = Odometry() - - self.get_logger().info("Unscented Kalman Filter started") - - def imu_callback(self, msg: Imu): - - # Get the IMU data - - imu_acceleartion = msg.linear_acceleration - imu_angular_velocity = msg.angular_velocity - - # Combine the IMU data - imu_data = np.array([imu_acceleartion.x, imu_acceleartion.y, imu_acceleartion.z, imu_angular_velocity.x, imu_angular_velocity.y, imu_angular_velocity.z]) - - # Update the filter with the IMU data - self.current_state_nom, self.current_state_error = ( - ErrorStateKalmanFilter.imu_update_states( - self.current_state_nom, self.current_state_error, imu_data - ) - ) - - # Inserting the nominal state into the msg - self.odom_msg.pose.pose.position.x = self.current_state_nom.position[0] - self.odom_msg.pose.pose.position.y = self.current_state_nom.position[1] - self.odom_msg.pose.pose.position.z = self.current_state_nom.position[2] - self.odom_msg.pose.pose.orientation.x = self.current_state_nom.orientation[0] - self.odom_msg.pose.pose.orientation.y = self.current_state_nom.orientation[1] - self.odom_msg.pose.pose.orientation.z = self.current_state_nom.orientation[2] - self.odom_msg.pose.pose.orientation.w = self.current_state_nom.orientation[3] - self.odom_msg.twist.twist.linear.x = self.current_state_nom.velocity[0] - self.odom_msg.twist.twist.linear.y = self.current_state_nom.velocity[1] - self.odom_msg.twist.twist.linear.z = self.current_state_nom.velocity[2] - self.odom_msg.twist.twist.angular.x = imu_angular_velocity.x - self.odom_msg.twist.twist.angular.y = imu_angular_velocity.y - self.odom_msg.twist.twist.angular.z = imu_angular_velocity.z - - # Publish - self.state_publisher_.publish(self.odom_msg) - - - - def filter_callback(self, msg: TwistWithCovarianceStamped): - """Callback function for the filter measurement update, - this will be called when the filter needs to be updated with the DVL data. - """ - self.get_logger().info("Filter callback, got DVL data") - - # Get the DVL data (linear velocity) - dvl_data = np.array([msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z]) - - # Update the filter with the DVL data - self.current_state_nom, self.current_state_error = ( - ErrorStateKalmanFilter.dvl_update_states( - self.current_state_nom, self.current_state_error, dvl_data - ) - ) - self.current_state_nom, self.current_state_error = ( - ErrorStateKalmanFilter.injection_and_reset( - self.current_state_nom, self.current_state_error - ) - ) - - # Inserting data into the msg - self.odom_msg.pose.pose.position.x = self.current_state_nom.position[0] - self.odom_msg.pose.pose.position.y = self.current_state_nom.position[1] - self.odom_msg.pose.pose.position.z = self.current_state_nom.position[2] - self.odom_msg.pose.pose.orientation.x = self.current_state_nom.orientation[0] - self.odom_msg.pose.pose.orientation.y = self.current_state_nom.orientation[1] - self.odom_msg.pose.pose.orientation.z = self.current_state_nom.orientation[2] - self.odom_msg.pose.pose.orientation.w = self.current_state_nom.orientation[3] - self.odom_msg.twist.twist.linear.x = self.current_state_nom.velocity[0] - self.odom_msg.twist.twist.linear.y = self.current_state_nom.velocity[1] - self.odom_msg.twist.twist.linear.z = self.current_state_nom.velocity[2] - self.odom_msg.twist.twist.linear.z = self.current_state_nom.velocity[2] - - # Publishing the data - self.state_publisher_.publish(self.odom_msg) - - - -def main(args=None): - rclpy.init(args=args) - node = ESKalmanFilterNode() - rclpy.spin(node) - node.destroy_node() - rclpy.shutdown() - - -if __name__ == "__main__": - main() diff --git a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_utils.py b/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_utils.py deleted file mode 100644 index 56285f031..000000000 --- a/navigation/sp_ukf_python/sp_ukf_python/sp_ukf_python_utils.py +++ /dev/null @@ -1,116 +0,0 @@ -import numpy as np - -def quaternion_super_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: - """Calculates the quaternion super product of two quaternions. - - Args: - q1 (np.ndarray): The first quaternion. - q2 (np.ndarray): The second quaternion. - - Returns: - np.ndarray: The quaternion super product. - """ - eta_0, e_0_x, e_0_y, e_0_z = q1 - eta_1, e_1_x, e_1_y, e_1_z = q2 - - e_0 = np.array([e_0_x, e_0_y, e_0_z]) - e_1 = np.array([e_1_x, e_1_y, e_1_z]) - - eta_new = eta_0 * eta_1 - (e_0_x * e_1_x + e_0_y * e_1_y + e_0_z * e_1_z) - nu_new = e_1 * eta_0 + e_0 * eta_1 + np.dot(skew_symmetric(e_0), e_1) - - q_new = np.array([eta_new, nu_new[0], nu_new[1], nu_new[2]]) - q_new /= np.linalg.norm(q_new) - - return q_new - -def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: - """ - Calculates the error between two quaternions - """ - - quat_2_inv = np.array([quat_2[0], -quat_2[1], -quat_2[2], -quat_2[3]]) - - error_quat = quaternion_super_product(quat_1, quat_2_inv) - - return error_quat - -def euler_rotation_quaternion(self, euler_angles: np.ndarray) -> np.ndarray: - """ - Converts An vector assumed to be rotation vector to quaternion - - Args: - euler_angles (np.ndarray): Rotation vector - - Returns: - np.ndarray: Quaternion representation of the rotation vector - """ - - angle = np.linalg.norm(euler_angles) - - if angle == 0: - axis = np.array([0, 0, 0]) - else: - axis = euler_angles / angle - - quaternion = np.zeros(4) - quaternion[0] = np.cos(angle / 2) - quaternion[1:] = np.sin(angle / 2) * axis - - return quaternion - -def quaternion_rotation_euler(self, quaternion: np.ndarray) -> np.ndarray: - """ - Converts a quaternion to an euler rotation vector - Used to generate the covarince matrix - - Args: - quaternion (np.ndarray): The quaternion to convert - - Returns: - np.ndarray: The euler rotation vector - """ - nu, eta_x, eta_y, eta_z = quaternion - - phi = np.arctan2(2 * (nu * eta_x + eta_y * eta_z), 1 - 2 * (eta_x ** 2 + eta_y ** 2)) - theta = -np.arcsin(2 * (eta_z * eta_x - nu * eta_y)) - psi = np.arctan2(2 * (nu * eta_z + eta_x * eta_y), 1 - 2 * (eta_y ** 2 + eta_z ** 2)) - - return np.array([phi, theta, psi]) - -def skew_symmetric(vector: np.ndarray) -> np.ndarray: - """Calculates the skew symmetric matrix of a vector. - - Args: - vector (np.ndarray): The vector. - - Returns: - np.ndarray: The skew symmetric matrix. - """ - return np.array( - [ - [0, -vector[2], vector[1]], - [vector[2], 0, -vector[0]], - [-vector[1], vector[0], 0], - ] - ) - -def ssa(angle: np.ndarray) -> np.ndarray: - """ - smallest signed angle between two angles - """ - ssa_vector = np.zeros(len(angle)) - - for i in range(len(angle)): - ssa_vector[i] = (angle[i] + np.pi) % (2 * np.pi) - np.pi - - return ssa_vector - -def quat_norm(quat: np.ndarray) -> np.ndarray: - """ - Function that normalizes a quaternion - """ - - quat = quat / np.linalg.norm(quat) - - return quat diff --git a/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py b/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py deleted file mode 100644 index 1d8c723b1..000000000 --- a/navigation/sp_ukf_python/sp_ukf_python/test_ukf.py +++ /dev/null @@ -1,313 +0,0 @@ -import matplotlib.pyplot as plt -import numpy as np - -# (Assuming the following have been imported from your modules) -from sp_ukf_python_class import StateVector_euler, StateVector_quaternion - -from sp_ukf_python import ErrorStateUnscentedKalmanFilter - - -def quat_to_yaw(q: np.ndarray) -> float: - """Convert a quaternion (assumed [w, x, y, z]) into a yaw angle. - In NED, yaw is typically around the z-down axis. - """ - return 2 * np.arctan2(q[3], q[0]) - - -def run_ESUKF_simulation(): - # ------------------------------------------------------------------------- - # Simulation parameters - # ------------------------------------------------------------------------- - dt = 0.01 # time step [s] - T = 60.0 # total simulation time [s] - num_steps = int(T / dt) - - # In an NED frame, gravity is +9.81 in the z (down) direction. - g_val = 9.81 - - # ------------------------------------------------------------------------- - # Define noise and covariance matrices - # ------------------------------------------------------------------------- - Q = np.diag( - [ - 0.06, - 0.06, - 0.06, # position error - 0.04, - 0.04, - 0.04, # velocity error - 0.003, - 0.003, - 0.003, # orientation error - 0.02, - 0.02, - 0.02, # accelerometer bias error - 0.02, - 0.02, - 0.02, # gyro bias error - ] - ) - - R_meas = np.diag([0.52, 0.52, 0.52]) # Increased DVL measurement noise - - # Bias dynamics tuning remains the same here: - P_ab = 0.002 - P_wb = 0.002 - lever_arm = np.array([0.0, 0.0, 0.0]) # Sensor at the vehicle CG - - # Create the Error-State UKF instance (NED convention) - esukf = ErrorStateUnscentedKalmanFilter(P_ab, P_wb, Q, lever_arm, R_meas, g_val, dt) - - # ------------------------------------------------------------------------- - # Initialize the true state in NED - # ------------------------------------------------------------------------- - # We treat x as North, y as East, z as Down. - # We'll do a circular path in the horizontal plane (z=0). - true_state = StateVector_quaternion() - true_state.position = np.array([20.0, 0.0, 0.0]) # [N, E, D]=[20, 0, 0] - true_state.velocity = np.array([0.0, 1.0, 0.0]) # 1 m/s in the East direction - true_state.orientation = np.array([1.0, 0.0, 0.0, 0.0]) # No initial rotation - true_state.acceleration_bias = np.zeros(3) - true_state.gyro_bias = np.zeros(3) - - # ------------------------------------------------------------------------- - # Initialize the estimated state - # ------------------------------------------------------------------------- - est_state_nom = StateVector_quaternion() - est_state_nom.position = true_state.position + np.array([0.1, -0.1, 0.05]) - est_state_nom.velocity = true_state.velocity + np.array([0.05, 0.05, -0.05]) - est_state_nom.orientation = true_state.orientation.copy() - est_state_nom.acceleration_bias = np.zeros(3) - est_state_nom.gyro_bias = np.zeros(3) - - # Initialize error state (Euler) with some covariance - est_state_error = StateVector_euler() - est_state_error.fill_states(np.zeros(15)) - est_state_error.covariance = 0.5 * np.eye(15) - - # ------------------------------------------------------------------------- - # Prepare histories for plotting - # ------------------------------------------------------------------------- - time_hist = [] - true_pos_hist = [] - est_pos_hist = [] - true_vel_hist = [] - est_vel_hist = [] - true_yaw_hist = [] - est_yaw_hist = [] - - # ------------------------------------------------------------------------- - # Define the "circular" trajectory in the horizontal plane (z=0) - # in NED: x=North, y=East, z=Down - # We'll revolve in the XY-plane, at D=0, with radius=20 m, angular speed=0.05 rad/s - # ------------------------------------------------------------------------- - R_circle = 20.0 - omega = 0.05 - - # ------------------------------------------------------------------------- - # Main simulation loop - # ------------------------------------------------------------------------- - t = 0.0 - for step in range(num_steps): - # --- True State Generation (NED) --- - # Position: circle in x-y plane at z=0 - pos_true = np.array( - [ - R_circle * np.cos(omega * t), # N - R_circle * np.sin(omega * t), # E - 0.0, # D - ] - ) - # Velocity: derivative of pos - vel_true = np.array( - [ - -R_circle * omega * np.sin(omega * t), # d/dt of cos => -sin - R_circle * omega * np.cos(omega * t), # d/dt of sin => cos - 0.0, - ] - ) - # Acceleration: second derivative - acc_true = np.array( - [ - -R_circle * omega**2 * np.cos(omega * t), - -R_circle * omega**2 * np.sin(omega * t), - 0.0, - ] - ) - - # Update the "true" state in NED - true_state.position = pos_true - true_state.velocity = vel_true - - # Compute full quaternion from Euler angles (roll, pitch, yaw) - roll_true = 0.0 - pitch_true = 0.0 - yaw_true = np.arctan2(vel_true[1], vel_true[0]) - cy = np.cos(yaw_true * 0.5) - sy = np.sin(yaw_true * 0.5) - cp = np.cos(pitch_true * 0.5) - sp = np.sin(pitch_true * 0.5) - cr = np.cos(roll_true * 0.5) - sr = np.sin(roll_true * 0.5) - true_state.orientation = np.array( - [ - cr * cp * cy + sr * sp * sy, # w - sr * cp * cy - cr * sp * sy, # x - cr * sp * cy + sr * cp * sy, # y - cr * cp * sy - sr * sp * cy, # z - ] - ) - - # --- Simulated IMU Measurements (NED) --- - # Gravity is +9.81 in the down (z) direction in NED - R_true = true_state.R_q() # rotation from body to inertial - # The "specific force" in body frame is (acc_inertial - gravity_inertial) rotated to body - imu_acc_ideal = R_true.T @ ( - acc_true - np.array([0.0, 0.0, g_val]) - ) + np.random.normal(0.01, 0.01, 3) # [rad/s] - - # Add small noise - imu_acc_noise = np.random.normal(0.0, 0.05, 3) # [m/s^2] - imu_acc_meas = imu_acc_ideal + imu_acc_noise - - # Gyro: angular velocity about body axes. Yaw rate is ~omega for a flat circle - imu_gyro_ideal = np.array([0.0, 0.0, omega]) + np.random.normal( - 0.01, 0.01, 3 - ) # [rad/s] - imu_gyro_noise = np.random.normal(0.0, 0.05, 3) # [rad/s] - imu_gyro_meas = imu_gyro_ideal + imu_gyro_noise - - # Combine - imu_meas = np.hstack((imu_acc_meas, imu_gyro_meas)) - - # --- Simulated DVL Measurement --- - # Velocity in inertial frame (NED) with zero noise for this test - dvl_noise = np.random.normal(0.0, 0.05, 3) - dvl_meas = vel_true + dvl_noise - - # --------------------------------------------------------------------- - # Filter Updates - # --------------------------------------------------------------------- - # 1. IMU update (prediction) - est_state_nom, est_state_error = esukf.imu_update_states( - est_state_nom, est_state_error, imu_meas - ) - # 2. DVL update (measurement) - est_state_nom, est_state_error = esukf.dvl_update_states( - est_state_nom, est_state_error, dvl_meas, imu_meas - ) - # 3. Inject error state - est_state_nom, est_state_error = esukf.inject_and_reset( - est_state_nom, est_state_error - ) - - # --- Store Histories --- - time_hist.append(t) - true_pos_hist.append(pos_true) - est_pos_hist.append(est_state_nom.position.copy()) - true_vel_hist.append(vel_true) - est_vel_hist.append(est_state_nom.velocity.copy()) - true_yaw_hist.append(yaw_true) - est_yaw_hist.append(quat_to_yaw(est_state_nom.orientation)) - - t += dt - - # ------------------------------------------------------------------------- - # Convert histories to arrays - # ------------------------------------------------------------------------- - true_pos_hist = np.array(true_pos_hist) - est_pos_hist = np.array(est_pos_hist) - true_vel_hist = np.array(true_vel_hist) - est_vel_hist = np.array(est_vel_hist) - true_yaw_hist = np.array(true_yaw_hist) - est_yaw_hist = np.array(est_yaw_hist) - time_hist = np.array(time_hist) - - # ------------------------------------------------------------------------- - # Plotting - # ------------------------------------------------------------------------- - # Positions - plt.figure(figsize=(10, 8)) - plt.subplot(3, 1, 1) - plt.plot(time_hist, true_pos_hist[:, 0], label='True N') - plt.plot(time_hist, est_pos_hist[:, 0], '--', label='Estimated N') - plt.ylabel('N (m)') - plt.legend() - - plt.subplot(3, 1, 2) - plt.plot(time_hist, true_pos_hist[:, 1], label='True E') - plt.plot(time_hist, est_pos_hist[:, 1], '--', label='Estimated E') - plt.ylabel('E (m)') - plt.legend() - - plt.subplot(3, 1, 3) - plt.plot(time_hist, true_pos_hist[:, 2], label='True D') - plt.plot(time_hist, est_pos_hist[:, 2], '--', label='Estimated D') - plt.xlabel('Time (s)') - plt.ylabel('D (m)') - plt.legend() - plt.tight_layout() - plt.show() - - # Velocities - plt.figure(figsize=(10, 8)) - plt.subplot(3, 1, 1) - plt.plot(time_hist, true_vel_hist[:, 0], label='True Vn') - plt.plot(time_hist, est_vel_hist[:, 0], '--', label='Estimated Vn') - plt.ylabel('Vn (m/s)') - plt.legend() - - plt.subplot(3, 1, 2) - plt.plot(time_hist, true_vel_hist[:, 1], label='True Ve') - plt.plot(time_hist, est_vel_hist[:, 1], '--', label='Estimated Ve') - plt.ylabel('Ve (m/s)') - plt.legend() - - plt.subplot(3, 1, 3) - plt.plot(time_hist, true_vel_hist[:, 2], label='True Vd') - plt.plot(time_hist, est_vel_hist[:, 2], '--', label='Estimated Vd') - plt.xlabel('Time (s)') - plt.ylabel('Vd (m/s)') - plt.legend() - plt.tight_layout() - plt.show() - - # Heading (Yaw) - plt.figure(figsize=(10, 4)) - plt.plot(time_hist, np.degrees(true_yaw_hist), label='True Yaw') - plt.plot(time_hist, np.degrees(est_yaw_hist), '--', label='Estimated Yaw') - plt.xlabel('Time (s)') - plt.ylabel('Yaw (deg)') - plt.legend() - plt.title('Heading Comparison (NED)') - plt.tight_layout() - plt.show() - - # 3D Trajectory - fig = plt.figure(figsize=(8, 6)) - ax = fig.add_subplot(111, projection='3d') - ax.plot( - true_pos_hist[:, 0], - true_pos_hist[:, 1], - true_pos_hist[:, 2], - label='True Trajectory', - linewidth=2, - ) - ax.plot( - est_pos_hist[:, 0], - est_pos_hist[:, 1], - est_pos_hist[:, 2], - '--', - label='Estimated Trajectory', - linewidth=2, - ) - ax.set_xlabel('North (m)') - ax.set_ylabel('East (m)') - ax.set_zlabel('Down (m)') - ax.legend() - plt.title('3D Trajectory (NED Frame)') - plt.show() - - -if __name__ == '__main__': - run_ESUKF_simulation() diff --git a/navigation/ukf_okid/ukf_python/ukf_okid.py b/navigation/ukf_okid/ukf_python/ukf_okid.py index c588d579e..dd52c6589 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid.py @@ -14,6 +14,31 @@ def __init__(self, process_model: process_model, x_0, P_0, Q, R): self.sigma_points_list = None self.y_i = None self.weight = None + # self.T = self.generate_T_matrix(len(P_0)) + + def generate_T_matrix(n): + """ + Generates the orthonormal transformation matrix T used in the TUKF sigma point generation. + + Parameters: + n (int): The state dimension. + + Returns: + T (np.ndarray): An n x 2n orthonormal transformation matrix used to generate TUKF sigma points. + """ + T = np.zeros((n, 2 * n)) + + for i in range(1, 2 * n + 1): # indexing matches equation (1, ..., 2n) + for j in range(1, (n // 2) + 1): + T[2 * j - 2, i - 1] = np.sqrt(2) * np.cos(((2 * j - 1) * i * np.pi) / n) + T[2 * j - 1, i - 1] = np.sqrt(2) * np.sin(((2 * j - 1) * i * np.pi) / n) + + if n % 2 == 1: # if n is odd, add the last term as described in the paper + T[n - 1, i - 1] = (-1) ** i + + T = T / np.sqrt(2) # Normalize matrix for orthonormality (unit scaling) + + return T def sigma_points(self, current_state: StateQuat) -> tuple[list[StateQuat], np.ndarray]: """ @@ -134,10 +159,10 @@ def add_quaternion_noise(q, noise_std): x0[3] = 1 x0[7:10] = [0.2, 0.2, 0.2] dt = 0.01 - R = (0.1 / dt) * np.eye(3) + R = (0.01) * np.eye(3) - Q = 0.1 * np.eye(12) - P0 = np.eye(12) * 0.1 + Q = 0.00015 * np.eye(12) + P0 = np.eye(12) * 0.0001 model = process_model() model.dt = 0.01 @@ -156,16 +181,35 @@ def add_quaternion_noise(q, noise_std): model.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) model.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) - model_ukf = model + model_ukf = process_model() + model_ukf.dt = 0.01 + model_ukf.mass_interia_matrix = np.array([ + [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] + ]) + model_ukf.m = 30.0 + model_ukf.r_b_bg = np.array([0.01, 0.0, 0.02]) + model_ukf.inertia = np.diag([0.68, 3.32, 3.34]) + model_ukf.damping_linear = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) + model_ukf.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) + model_ukf.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) # Simulation parameters - simulation_time = 40 # seconds + simulation_time = 20 # seconds num_steps = int(simulation_time / dt) # Initialize a dummy StateQuat. - test_state = StateQuat() - test_state.fill_states(x0) - test_state.covariance = P0 + new_state = StateQuat() + new_state.fill_states(x0) + new_state.covariance = P0 + + test_state_x = StateQuat() + test_state_x.fill_states(x0) + test_state_x.covariance = P0 # Initialize a estimated state estimated_state = StateQuat() @@ -196,18 +240,15 @@ def add_quaternion_noise(q, noise_std): # Initialize the okid params okid_params = np.zeros((num_steps, 21)) - model.state_vector_prev = test_state - model.state_vector = test_state + model.state_vector_prev = new_state + model.state_vector = new_state - model_ukf.state_vector_prev = test_state - model_ukf.state_vector = test_state + model_ukf.state_vector_prev = test_state_x + model_ukf.state_vector = test_state_x # initialize the ukf ukf = UKF(model_ukf, x0, P0, Q, R) - # Test - ukf.unscented_transform(test_state) - elapsed_times = [] u = lambda t: np.array([2 * np.sin(1 * t), 2 * np.sin(1 * t), 2 * np.sin(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t)]) @@ -219,22 +260,22 @@ def add_quaternion_noise(q, noise_std): model_ukf.Control_input = u(step * dt) # Perform the unscented transform - model.model_prediction(test_state) + model.model_prediction(new_state) new_state = model.euler_forward() # Adding noise in the state vector - noisy_state.position = new_state.position + np.random.normal(0, 0.1, 3) - noisy_state.orientation = add_quaternion_noise(new_state.orientation, 0.1) - noisy_state.velocity = new_state.velocity + np.random.normal(0, 0.1, 3) - noisy_state.angular_velocity = new_state.angular_velocity + np.random.normal(0, 0.1, 3) + estimated_state.position = estimated_state.position # + np.random.normal(0, 0.01, 3) + estimated_state.orientation = estimated_state.orientation #add_quaternion_noise(estimated_state.orientation, 0.01) + estimated_state.velocity = estimated_state.velocity # + np.random.normal(0, 0.01, 3) + estimated_state.angular_velocity = estimated_state.angular_velocity # + np.random.normal(0, 0.01, 3) start_time = time.time() - estimated_state = ukf.unscented_transform(noisy_state) + estimated_state = ukf.unscented_transform(estimated_state) elapsed_time = time.time() - start_time elapsed_times.append(elapsed_time) - if step % 20 == 0: - measurment_model.measurement = new_state.velocity + np.random.normal(0, 0.2, 3) + if step % 10 == 0: + measurment_model.measurement = new_state.velocity # + np.random.normal(0, 0.01, 3) meas_update, covariance_matrix = ukf.measurement_update(estimated_state, measurment_model) estimated_state = ukf.posteriori_estimate(estimated_state, covariance_matrix, measurment_model, meas_update) From 007c2403925f35cf49571cc733f41c06e55f20f4 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Fri, 14 Mar 2025 23:17:19 +0100 Subject: [PATCH 07/30] added test script --- .../eskf_python/eskf_python/eskf_test.py | 235 ++++++++++++++++++ 1 file changed, 235 insertions(+) create mode 100644 navigation/eskf_python/eskf_python/eskf_test.py diff --git a/navigation/eskf_python/eskf_python/eskf_test.py b/navigation/eskf_python/eskf_python/eskf_test.py new file mode 100644 index 000000000..4623b7b86 --- /dev/null +++ b/navigation/eskf_python/eskf_python/eskf_test.py @@ -0,0 +1,235 @@ + +from eskf_python_class import StateEuler, StateQuat, MeasurementModel, Measurement +import numpy as np +from eskf_python_utils import skew_matrix, quaternion_product, R_from_angle_axis, angle_axis_to_quaternion +from ukf_okid_class import process_model, quat_to_euler, euler_to_quat +from ukf_okid_class import StateQuat as StateQuatmodel +from scipy.linalg import block_diag +import matplotlib.pyplot as plt +from eskf_python_filter import ESKF + + +def fancy_print_state_quat(state: StateQuat) -> None: + print("Nominal State (Quaternion):") + print(f" Position : {np.array2string(state.position, precision=3, separator=', ')}") + print(f" Velocity : {np.array2string(state.velocity, precision=3, separator=', ')}") + print(f" Orientation (Quat): {np.array2string(state.orientation, precision=3, separator=', ')}") + print(f" Acceleration Bias : {np.array2string(state.acceleration_bias, precision=3, separator=', ')}") + print(f" Gyro Bias : {np.array2string(state.gyro_bias, precision=3, separator=', ')}") + print(f" Gravity : {np.array2string(state.g, precision=3, separator=', ')}\n") + + +def fancy_print_state_euler(state: StateEuler) -> None: + print("Error State (Euler):") + print(f" Position Error : {np.array2string(state.position, precision=3, separator=', ')}") + print(f" Velocity Error : {np.array2string(state.velocity, precision=3, separator=', ')}") + print(f" Orientation Error : {np.array2string(state.orientation, precision=3, separator=', ')}") + print(f" Acceleration Bias Error: {np.array2string(state.acceleration_bias, precision=3, separator=', ')}") + print(f" Gyro Bias Error : {np.array2string(state.gyro_bias, precision=3, separator=', ')}") + print(f" Gravity Error : {np.array2string(state.g, precision=3, separator=', ')}\n") + +def fancy_print_matrix(matrix: np.ndarray) -> None: + print(f"Matrix shape: {matrix.shape}") + print("========== Matrix ==========") + for row in matrix: + print(" ".join(f"{value:8.3f}" for value in row)) + print("======== End Matrix ========") + +if __name__ == "__main__": + + # Simulation parameters + simulation_time = 20.0 # seconds + dt = 0.01 + num_steps = int(simulation_time / dt) + time = np.linspace(0, simulation_time, num_steps) + + # ----------------------- Setup Initial States, Filter & Model ----------------------- + # True initial state + true_state_init = StateQuat() + true_state_init.position = np.array([0.1, 0.0, 0.0]) + true_state_init.velocity = np.array([0.1, 0.0, 0.0]) + P0 = np.diag([ + 1.0, 1.0, 1.0, # Position + 0.2, 0.2, 0.2, # Velocity + 0.01, 0.01, 0.01, # Orientation + 0.00001, 0.00001, 0.00001, # Acceleration bias + 0.00001, 0.00001, 0.00001, # Gyro bias + 0.00001, 0.00001, 0.00001 # Gravity + ]) + + # Estimated initial state (for filter) + est_state_init = StateQuat() + est_state_init.position = np.array([0.1, 0.0, 0.0]) + est_state_init.velocity = np.array([0.1, 0.0, 0.0]) + + # Noise parameters + Q = np.diag([ + (0.02**2) / dt, (0.02**2) / dt, (0.02**2) / dt, # Accelerometer noise + (0.001**2) / dt, (0.001**2) / dt, (0.001**2) / dt, # Gyroscope noise + 0.0001, 0.0001, 0.0001, # Acceleration bias random walk + 0.00001, 0.00001, 0.00001 # Gyro bias random walk + ]) + + Hx = np.zeros((3, 19)) + Hx[0:3, 6:9] = np.eye(3) + + # Create filter object + eskf = ESKF(Q, P0, Hx, true_state_init, 1e-13, 1e-13, dt) + + imu_data = Measurement() + dvl_data = Measurement() + dvl_data.aiding_covariance = np.eye(3) * 0.2 + + # Setup the process model + model = process_model() + model.dt = dt + model.mass_interia_matrix = np.array([ + [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] + ]) + model.m = 30.0 + model.r_b_bg = np.array([0.01, 0.0, 0.02]) + model.inertia = np.diag([0.68, 3.32, 3.34]) + model.damping_linear = np.diag([0.03, 0.03, 0.03, 0.03, 0.03, 0.03]) + + # Initialize a dummy state for simulation dynamics. + new_state = StateQuatmodel() + new_state.position = np.array([0.1, 0.0, 0.0]) + new_state.velocity = np.array([0.1, 0.0, 0.0]) + new_state_prev = StateQuatmodel() + new_state_prev.position = np.array([0.1, 0.0, 0.0]) + new_state_prev.velocity = np.array([0.1, 0.0, 0.0]) + + model.state_vector = new_state + model.state_vector_prev = new_state_prev + + # ----------------------- Data Storage Arrays ----------------------- + true_positions = np.zeros((num_steps, 3)) + true_orientations = np.zeros((num_steps, 3)) + true_velocities = np.zeros((num_steps, 3)) + + est_positions = np.zeros((num_steps, 3)) + est_orientations = np.zeros((num_steps, 3)) + est_velocities = np.zeros((num_steps, 3)) + + # We'll record the filter’s covariance diagonal for each state component. + pos_cov = np.zeros((num_steps, 3)) # covariance for position (indices 0:3) + vel_cov = np.zeros((num_steps, 3)) # covariance for velocity (indices 3:6) + ori_cov = np.zeros((num_steps, 3)) # covariance for orientation (indices 6:9) + + prev_velocity = np.zeros(3) + u = lambda t: np.array([ + 0.5 * np.sin(0.1 * t), + 0.5 * np.sin(0.1 * t + 0.3), + 0.5 * np.sin(0.1 * t + 0.6), + 0.05 * np.cos(0.1 * t), + 0.05 * np.cos(0.1 * t + 0.3), + 0.05 * np.cos(0.1 * t + 0.6) + ]) + + # ----------------------- Simulation Loop ----------------------- + for step in range(num_steps): + t = step * dt + + model.Control_input = u(t) + model.model_prediction(new_state) + new_state = model.euler_forward() + + # Simulate IMU measurements (with noise) + imu_data.acceleration = ((new_state.velocity - prev_velocity) / dt) + np.random.normal(0, 0.13, 3) + imu_data.angular_velocity = new_state.angular_velocity + np.random.normal(0, 0.13, 3) + + eskf.imu_update(imu_data) + + # DVL update every 20 time-steps + if step % 20 == 0: + dvl_data.aiding = new_state.velocity + np.random.normal(0, 0.01, 3) + eskf.dvl_update(dvl_data) + + # Store True data (from the simulated dynamics) + true_positions[step, :] = np.copy(new_state.position) + true_orientations[step, :] = quat_to_euler(np.copy(new_state.orientation)) + true_velocities[step, :] = np.copy(new_state.velocity) + + # Store estimated state (from the filter) + est_positions[step, :] = np.copy(eskf.nom_state.position) + est_orientations[step, :] = quat_to_euler(np.copy(eskf.nom_state.orientation)) + est_velocities[step, :] = np.copy(eskf.nom_state.velocity) + + # Record covariance diagonal (assumed ordering: pos (0:3), vel (3:6), orientation (6:9)) + P_diag = np.diag(eskf.error_state.covariance) + pos_cov[step, :] = P_diag[0:3] + vel_cov[step, :] = P_diag[3:6] + ori_cov[step, :] = P_diag[6:9] + + prev_velocity = new_state.velocity + model.state_vector_prev = new_state + + # ----------------------- New Plotting Scheme ----------------------- + # Create 3 separate figures, each corresponding to one degree of freedom: + # For position and velocity: X, Y, Z. + # For orientation: Roll, Pitch, Yaw. + axis_labels_pos = ["X", "Y", "Z"] + axis_labels_vel = ["X", "Y", "Z"] + axis_labels_ori = ["Roll", "Pitch", "Yaw"] + + # Plot Position + fig_pos, axs_pos = plt.subplots(3, 1, figsize=(10, 12)) + fig_pos.suptitle("True Data vs Filter Estimates for Position") + for i in range(3): + ax_pos = axs_pos[i] + ax_pos.plot(time, true_positions[:, i], label=f"True Pos {axis_labels_pos[i]}", color=f"C{i}", linestyle='-') + ax_pos.plot(time, est_positions[:, i], label=f"Est Pos {axis_labels_pos[i]}", color=f"C{i}", linestyle='--') + sigma_pos = np.sqrt(pos_cov[:, i]) + ax_pos.fill_between(time, est_positions[:, i] - sigma_pos, est_positions[:, i] + sigma_pos, + color=f"C{i}", alpha=0.2) + ax_pos.set_title(f"Position [{axis_labels_pos[i]}] [m]") + ax_pos.set_xlabel("Time [s]") + ax_pos.set_ylabel("Position") + ax_pos.grid(True) + ax_pos.legend() + + plt.tight_layout(rect=[0, 0, 1, 0.96]) + plt.show() + + # Plot Velocity + fig_vel, axs_vel = plt.subplots(3, 1, figsize=(10, 12)) + fig_vel.suptitle("True Data vs Filter Estimates for Velocity") + for i in range(3): + ax_vel = axs_vel[i] + ax_vel.plot(time, true_velocities[:, i], label=f"True Vel {axis_labels_vel[i]}", color=f"C{i}", linestyle='-') + ax_vel.plot(time, est_velocities[:, i], label=f"Est Vel {axis_labels_vel[i]}", color=f"C{i}", linestyle='--') + sigma_vel = np.sqrt(vel_cov[:, i]) + ax_vel.fill_between(time, est_velocities[:, i] - sigma_vel, est_velocities[:, i] + sigma_vel, + color=f"C{i}", alpha=0.2) + ax_vel.set_title(f"Velocity [{axis_labels_vel[i]}] [m/s]") + ax_vel.set_xlabel("Time [s]") + ax_vel.set_ylabel("Velocity") + ax_vel.grid(True) + ax_vel.legend() + + plt.tight_layout(rect=[0, 0, 1, 0.96]) + plt.show() + + # Plot Orientation + fig_ori, axs_ori = plt.subplots(3, 1, figsize=(10, 12)) + fig_ori.suptitle("True Data vs Filter Estimates for Orientation") + for i in range(3): + ax_ori = axs_ori[i] + ax_ori.plot(time, true_orientations[:, i], label=f"True Ori {axis_labels_ori[i]}", color=f"C{i}", linestyle='-') + ax_ori.plot(time, est_orientations[:, i], label=f"Est Ori {axis_labels_ori[i]}", color=f"C{i}", linestyle='--') + sigma_ori = np.sqrt(ori_cov[:, i]) + ax_ori.fill_between(time, est_orientations[:, i] - sigma_ori, est_orientations[:, i] + sigma_ori, + color=f"C{i}", alpha=0.2) + ax_ori.set_title(f"Orientation [{axis_labels_ori[i]}] [rad]") + ax_ori.set_xlabel("Time [s]") + ax_ori.set_ylabel("Orientation") + ax_ori.grid(True) + ax_ori.legend() + + plt.tight_layout(rect=[0, 0, 1, 0.96]) + plt.show() From 1fb496b0b80852a750b6ffe69367493184033ab4 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Sat, 15 Mar 2025 00:02:45 +0100 Subject: [PATCH 08/30] fixed some errors, code runs from eskf_test now --- .../eskf_python/eskf_python_class.py | 28 -- .../eskf_python/eskf_python_filter.py | 22 +- .../eskf_python/eskf_python_utils.py | 53 ++ .../eskf_python/eskf_python/eskf_test.py | 83 +--- .../eskf_python/eskf_test_utils.py | 184 +++++++ .../eskf_python/eskf_python/ukf_okid_class.py | 464 ------------------ 6 files changed, 272 insertions(+), 562 deletions(-) create mode 100644 navigation/eskf_python/eskf_python/eskf_test_utils.py delete mode 100644 navigation/eskf_python/eskf_python/ukf_okid_class.py diff --git a/navigation/eskf_python/eskf_python/eskf_python_class.py b/navigation/eskf_python/eskf_python/eskf_python_class.py index 949ab996d..c2ffc8e02 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_class.py +++ b/navigation/eskf_python/eskf_python/eskf_python_class.py @@ -1,8 +1,5 @@ from dataclasses import dataclass, field -from typing import Tuple, List -from scipy.linalg import expm import numpy as np -from eskf_python_utils import skew_matrix, quaternion_product @dataclass @@ -85,31 +82,6 @@ def R_q(self) -> np.ndarray: return R - # def inject(self, EulerState: 'StateEuler') -> 'StateQuat': - # inj_state = StateQuat() - - # # Injecting the error state - # inj_state.position = self.position + EulerState.position - # inj_state.velocity = self.velocity + EulerState.velocity - # inj_state.orientation = quaternion_product( - # self.orientation, - # 0.5 - # * np.array( - # [ - # 2, - # EulerState.orientation[0], - # EulerState.orientation[1], - # EulerState.orientation[2], - # ] - # ), - # ) - # inj_state.acceleration_bias = self.acceleration_bias + EulerState.acceleration_bias - # inj_state.gyro_bias = self.gyro_bias + EulerState.gyro_bias - - # return inj_state - - - @dataclass class StateEuler: position: np.ndarray = field( diff --git a/navigation/eskf_python/eskf_python/eskf_python_filter.py b/navigation/eskf_python/eskf_python/eskf_python_filter.py index a9c772e47..b1efeb0a9 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_filter.py +++ b/navigation/eskf_python/eskf_python/eskf_python_filter.py @@ -4,9 +4,9 @@ import numpy as np from scipy.linalg import expm from eskf_python_class import StateEuler, StateQuat, Measurement -from eskf_python_utils import skew_matrix, quaternion_product, R_from_angle_axis, angle_axis_to_quaternion -from ukf_okid_class import euler_to_quat +from eskf_python_utils import skew_matrix, quaternion_product, R_from_angle_axis, angle_axis_to_quaternion, euler_to_quat from scipy.linalg import block_diag +from scipy.spatial.transform import Rotation as R_scipy class ESKF: def __init__(self, Q: np.ndarray, P0, Hx, nom_state: StateQuat, p_accBias, p_gyroBias, dt): @@ -103,8 +103,6 @@ def h(self) -> np.ndarray: """ return self.nom_state.velocity - - def nominal_state_discrete(self, imu_data: Measurement) -> None: """ Calculates the next nominal state using the discrete-time process model defined in: @@ -196,13 +194,18 @@ def measurement_update(self, dvl_measurement:Measurement) -> None: Args: dvl_measurement (np.ndarray): The DVL measurement. """ - + H = self.H() P = self.error_state.covariance - R= dvl_measurement.aiding_covariance - K = P @ H.T @ np.linalg.inv(H @ P @ H.T + R) - self.error_state.fill_states(K @ (dvl_measurement.aiding - self.h())) - self.error_state.covariance = (np.eye(18) - K @ H) @ P + R = dvl_measurement.aiding_covariance + + S = H @ P @ H.T + R + K = P @ H.T @ np.linalg.inv(S) + innovation = dvl_measurement.aiding - self.h() + self.error_state.fill_states(K @ innovation) + + I_KH = np.eye(18) - K @ H + self.error_state.covariance = I_KH @ P @ I_KH.T + K @ R @ K.T # Joseph form for more stability def injection(self) -> None: """ @@ -211,7 +214,6 @@ def injection(self) -> None: Chapter 6.2 eq. 282-283 """ - self.nom_state.position = self.nom_state.position + self.error_state.position self.nom_state.velocity = self.nom_state.velocity + self.error_state.velocity self.nom_state.orientation = quaternion_product(self.nom_state.orientation, euler_to_quat(self.error_state.orientation)) diff --git a/navigation/eskf_python/eskf_python/eskf_python_utils.py b/navigation/eskf_python/eskf_python/eskf_python_utils.py index 9ea439982..aaef5f8d6 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_utils.py +++ b/navigation/eskf_python/eskf_python/eskf_python_utils.py @@ -12,6 +12,14 @@ def skew_matrix(vector: np.ndarray) -> np.ndarray: ] ) +def quat_norm(quat: np.ndarray) -> np.ndarray: + """ + Function that normalizes a quaternion + """ + quat = quat / np.linalg.norm(quat) + + return quat + def quaternion_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: """Calculates the quaternion super product of two quaternions. @@ -37,6 +45,17 @@ def quaternion_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: return q_new +def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: + """ + Calculates the error between two quaternions + """ + + quat_2_inv = np.array([quat_2[0], -quat_2[1], -quat_2[2], -quat_2[3]]) + + error_quat = quaternion_product(quat_1, quat_2_inv) + + return error_quat + def angle_axis_to_quaternion(vector: np.ndarray) -> np.ndarray: """Converts an angle-axis representation to a quaternion. @@ -93,3 +112,37 @@ def R_from_angle_axis(vector: np.ndarray) -> np.ndarray: ) return R + +def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: + """ + Converts Euler angles to a quaternion + """ + psi, theta, phi = euler_angles + c_psi = np.cos(psi / 2) + s_psi = np.sin(psi / 2) + c_theta = np.cos(theta / 2) + s_theta = np.sin(theta / 2) + c_phi = np.cos(phi / 2) + s_phi = np.sin(phi / 2) + + quat = np.array([ + c_psi * c_theta * c_phi + s_psi * s_theta * s_phi, + c_psi * c_theta * s_phi - s_psi * s_theta * c_phi, + s_psi * c_theta * s_phi + c_psi * s_theta * c_phi, + s_psi * c_theta * c_phi - c_psi * s_theta * s_phi + ]) + + return quat + +def quat_to_euler(quat: np.ndarray) -> np.ndarray: + """ + Converts a quaternion to Euler angles + """ + nu, eta_1, eta_2, eta_3 = quat + + phi = np.arctan2(2*(eta_2 * eta_3 + nu * eta_1), 1 - 2 * (eta_1 ** 2 + eta_2 ** 2)) + theta = -np.arcsin(2 * (eta_1 * eta_3 - nu * eta_2)) + psi = np.arctan2(2 * (nu * eta_3 + eta_1 * eta_2), 1 - 2 * (eta_2 ** 2 + eta_3 ** 2)) + + return np.array([phi, theta, psi]) + diff --git a/navigation/eskf_python/eskf_python/eskf_test.py b/navigation/eskf_python/eskf_python/eskf_test.py index 4623b7b86..bf4cc8f8b 100644 --- a/navigation/eskf_python/eskf_python/eskf_test.py +++ b/navigation/eskf_python/eskf_python/eskf_test.py @@ -1,40 +1,11 @@ from eskf_python_class import StateEuler, StateQuat, MeasurementModel, Measurement +from eskf_python_utils import quat_to_euler +from eskf_test_utils import process_model, StateQuatModel import numpy as np -from eskf_python_utils import skew_matrix, quaternion_product, R_from_angle_axis, angle_axis_to_quaternion -from ukf_okid_class import process_model, quat_to_euler, euler_to_quat -from ukf_okid_class import StateQuat as StateQuatmodel -from scipy.linalg import block_diag import matplotlib.pyplot as plt from eskf_python_filter import ESKF - -def fancy_print_state_quat(state: StateQuat) -> None: - print("Nominal State (Quaternion):") - print(f" Position : {np.array2string(state.position, precision=3, separator=', ')}") - print(f" Velocity : {np.array2string(state.velocity, precision=3, separator=', ')}") - print(f" Orientation (Quat): {np.array2string(state.orientation, precision=3, separator=', ')}") - print(f" Acceleration Bias : {np.array2string(state.acceleration_bias, precision=3, separator=', ')}") - print(f" Gyro Bias : {np.array2string(state.gyro_bias, precision=3, separator=', ')}") - print(f" Gravity : {np.array2string(state.g, precision=3, separator=', ')}\n") - - -def fancy_print_state_euler(state: StateEuler) -> None: - print("Error State (Euler):") - print(f" Position Error : {np.array2string(state.position, precision=3, separator=', ')}") - print(f" Velocity Error : {np.array2string(state.velocity, precision=3, separator=', ')}") - print(f" Orientation Error : {np.array2string(state.orientation, precision=3, separator=', ')}") - print(f" Acceleration Bias Error: {np.array2string(state.acceleration_bias, precision=3, separator=', ')}") - print(f" Gyro Bias Error : {np.array2string(state.gyro_bias, precision=3, separator=', ')}") - print(f" Gravity Error : {np.array2string(state.g, precision=3, separator=', ')}\n") - -def fancy_print_matrix(matrix: np.ndarray) -> None: - print(f"Matrix shape: {matrix.shape}") - print("========== Matrix ==========") - for row in matrix: - print(" ".join(f"{value:8.3f}" for value in row)) - print("======== End Matrix ========") - if __name__ == "__main__": # Simulation parameters @@ -51,23 +22,18 @@ def fancy_print_matrix(matrix: np.ndarray) -> None: P0 = np.diag([ 1.0, 1.0, 1.0, # Position 0.2, 0.2, 0.2, # Velocity - 0.01, 0.01, 0.01, # Orientation + 0.2, 0.2, 0.2, # Orientation 0.00001, 0.00001, 0.00001, # Acceleration bias 0.00001, 0.00001, 0.00001, # Gyro bias 0.00001, 0.00001, 0.00001 # Gravity ]) - # Estimated initial state (for filter) - est_state_init = StateQuat() - est_state_init.position = np.array([0.1, 0.0, 0.0]) - est_state_init.velocity = np.array([0.1, 0.0, 0.0]) - # Noise parameters Q = np.diag([ - (0.02**2) / dt, (0.02**2) / dt, (0.02**2) / dt, # Accelerometer noise - (0.001**2) / dt, (0.001**2) / dt, (0.001**2) / dt, # Gyroscope noise - 0.0001, 0.0001, 0.0001, # Acceleration bias random walk - 0.00001, 0.00001, 0.00001 # Gyro bias random walk + (0.05**2) / dt, (0.05**2) / dt, (0.05**2) / dt, # Accelerometer noise + (0.004**2) / dt, (0.004**2) / dt, (0.004**2) / dt, # Gyroscope noise + 0.0002, 0.0002, 0.0002, # Acceleration bias random walk + 0.0001, 0.0001, 0.0001 # Gyro bias random walk ]) Hx = np.zeros((3, 19)) @@ -76,11 +42,14 @@ def fancy_print_matrix(matrix: np.ndarray) -> None: # Create filter object eskf = ESKF(Q, P0, Hx, true_state_init, 1e-13, 1e-13, dt) + # Create measurement objects imu_data = Measurement() dvl_data = Measurement() - dvl_data.aiding_covariance = np.eye(3) * 0.2 - # Setup the process model + # R matrix for DVL aiding + dvl_data.aiding_covariance = np.diag([(0.5)**2, (0.5)**2, (0.5)**2]) + + # Setup the process model for simulation of AUV model = process_model() model.dt = dt model.mass_interia_matrix = np.array([ @@ -97,17 +66,19 @@ def fancy_print_matrix(matrix: np.ndarray) -> None: model.damping_linear = np.diag([0.03, 0.03, 0.03, 0.03, 0.03, 0.03]) # Initialize a dummy state for simulation dynamics. - new_state = StateQuatmodel() + # Two where made since there seems to be an issue with declaring two identical objects. + new_state = StateQuatModel() new_state.position = np.array([0.1, 0.0, 0.0]) new_state.velocity = np.array([0.1, 0.0, 0.0]) - new_state_prev = StateQuatmodel() + + new_state_prev = StateQuatModel() new_state_prev.position = np.array([0.1, 0.0, 0.0]) new_state_prev.velocity = np.array([0.1, 0.0, 0.0]) model.state_vector = new_state model.state_vector_prev = new_state_prev - # ----------------------- Data Storage Arrays ----------------------- + # Initialize arrays to store true and estimated states true_positions = np.zeros((num_steps, 3)) true_orientations = np.zeros((num_steps, 3)) true_velocities = np.zeros((num_steps, 3)) @@ -116,10 +87,10 @@ def fancy_print_matrix(matrix: np.ndarray) -> None: est_orientations = np.zeros((num_steps, 3)) est_velocities = np.zeros((num_steps, 3)) - # We'll record the filter’s covariance diagonal for each state component. - pos_cov = np.zeros((num_steps, 3)) # covariance for position (indices 0:3) - vel_cov = np.zeros((num_steps, 3)) # covariance for velocity (indices 3:6) - ori_cov = np.zeros((num_steps, 3)) # covariance for orientation (indices 6:9) + # covariance arrays + pos_cov = np.zeros((num_steps, 3)) + vel_cov = np.zeros((num_steps, 3)) + ori_cov = np.zeros((num_steps, 3)) prev_velocity = np.zeros(3) u = lambda t: np.array([ @@ -131,7 +102,7 @@ def fancy_print_matrix(matrix: np.ndarray) -> None: 0.05 * np.cos(0.1 * t + 0.6) ]) - # ----------------------- Simulation Loop ----------------------- + # Sim for step in range(num_steps): t = step * dt @@ -139,28 +110,23 @@ def fancy_print_matrix(matrix: np.ndarray) -> None: model.model_prediction(new_state) new_state = model.euler_forward() - # Simulate IMU measurements (with noise) imu_data.acceleration = ((new_state.velocity - prev_velocity) / dt) + np.random.normal(0, 0.13, 3) imu_data.angular_velocity = new_state.angular_velocity + np.random.normal(0, 0.13, 3) eskf.imu_update(imu_data) - # DVL update every 20 time-steps if step % 20 == 0: dvl_data.aiding = new_state.velocity + np.random.normal(0, 0.01, 3) eskf.dvl_update(dvl_data) - # Store True data (from the simulated dynamics) true_positions[step, :] = np.copy(new_state.position) true_orientations[step, :] = quat_to_euler(np.copy(new_state.orientation)) true_velocities[step, :] = np.copy(new_state.velocity) - # Store estimated state (from the filter) est_positions[step, :] = np.copy(eskf.nom_state.position) est_orientations[step, :] = quat_to_euler(np.copy(eskf.nom_state.orientation)) est_velocities[step, :] = np.copy(eskf.nom_state.velocity) - # Record covariance diagonal (assumed ordering: pos (0:3), vel (3:6), orientation (6:9)) P_diag = np.diag(eskf.error_state.covariance) pos_cov[step, :] = P_diag[0:3] vel_cov[step, :] = P_diag[3:6] @@ -169,10 +135,7 @@ def fancy_print_matrix(matrix: np.ndarray) -> None: prev_velocity = new_state.velocity model.state_vector_prev = new_state - # ----------------------- New Plotting Scheme ----------------------- - # Create 3 separate figures, each corresponding to one degree of freedom: - # For position and velocity: X, Y, Z. - # For orientation: Roll, Pitch, Yaw. + # Plotting axis_labels_pos = ["X", "Y", "Z"] axis_labels_vel = ["X", "Y", "Z"] axis_labels_ori = ["Roll", "Pitch", "Yaw"] diff --git a/navigation/eskf_python/eskf_python/eskf_test_utils.py b/navigation/eskf_python/eskf_python/eskf_test_utils.py new file mode 100644 index 000000000..34abe8eda --- /dev/null +++ b/navigation/eskf_python/eskf_python/eskf_test_utils.py @@ -0,0 +1,184 @@ +import numpy as np +from dataclasses import dataclass, field +from typing import Tuple +from eskf_python_utils import quaternion_product, euler_to_quat, quat_to_euler, quaternion_error, quat_norm, skew_matrix + +# This was the original code from the ukf_okid.py file + +@dataclass +class StateQuatModel: + """ + A class to represent the state to be estimated by the UKF. + """ + position: np.ndarray = field(default_factory=lambda: np.zeros(3)) + orientation: np.ndarray = field(default_factory=lambda: np.array([1, 0, 0, 0])) + velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) + angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) + covariance: np.ndarray = field(default_factory=lambda: np.zeros((12, 12))) + + def as_vector(self) -> np.ndarray: + """Returns the StateVector as a numpy array.""" + return np.concatenate([self.position, self.orientation, self.velocity, self.angular_velocity]) + + def nu(self) -> np.ndarray: + """Calculates the nu vector.""" + return np.concatenate([self.velocity, self.angular_velocity]) + + def R_q(self) -> np.ndarray: + """Calculates the rotation matrix from the orientation quaternion.""" + q0, q1, q2, q3 = self.orientation + R = np.array([ + [1 - 2 * q2**2 - 2 * q3**2, 2 * (q1 * q2 - q0 * q3), 2 * (q0 * q2 + q1 * q3)], + [2 * (q1 * q2 + q0 * q3), 1 - 2 * q1**2 - 2 * q3**2, 2 * (q2 * q3 - q0 * q1)], + [2 * (q1 * q3 - q0 * q2), 2 * (q0 * q1 + q2 * q3), 1 - 2 * q1**2 - 2 * q2**2] + ]) + return R + + def fill_states(self, state: np.ndarray) -> None: + """Fills the state vector with the values from a numpy array.""" + self.position = state[0:3] + self.orientation = state[3:7] + self.velocity = state[7:10] + self.angular_velocity = state[10:13] + + def fill_states_different_dim(self, state: np.ndarray, state_euler: np.ndarray) -> None: + """Fills states when the state vector has different dimensions than the default state vector.""" + self.position = state[0:3] + state_euler[0:3] + self.orientation = quaternion_product(state[3:7], euler_to_quat(state_euler[3:6])) + self.velocity = state[7:10] + state_euler[6:9] + self.angular_velocity = state[10:13] + state_euler[9:12] + + def subtract(self, other: 'StateQuatModel') -> np.ndarray: + """Subtracts two StateQuatModel objects, returning the difference with Euler angles.""" + new_array = np.zeros(len(self.as_vector()) - 1) + new_array[:3] = self.position - other.position + new_array[3:6] = quat_to_euler(quaternion_error(self.orientation, other.orientation)) + new_array[6:9] = self.velocity - other.velocity + new_array[9:12] = self.angular_velocity - other.angular_velocity + + return new_array + + def __add__(self, other: 'StateQuatModel') -> 'StateQuatModel': + """Adds two StateQuatModel objects.""" + new_state = StateQuatModel() + new_state.position = self.position + other.position + new_state.orientation = quaternion_product(self.orientation, other.orientation) + new_state.velocity = self.velocity + other.velocity + new_state.angular_velocity = self.angular_velocity + other.angular_velocity + + return new_state + + def __sub__(self, other: 'StateQuatModel') -> 'StateQuatModel': + """Subtracts two StateQuatModel objects.""" + new_state = StateQuatModel() + new_state.position = self.position - other.position + new_state.orientation = quaternion_error(self.orientation, other.orientation) + new_state.velocity = self.velocity - other.velocity + new_state.angular_velocity = self.angular_velocity - other.angular_velocity + + return new_state.as_vector() + + def __rmul__(self, scalar: float) -> 'StateQuatModel': + """Multiplies the StateQuatModel object by a scalar.""" + new_state = StateQuatModel() + new_state.position = scalar * self.position + new_state.orientation = quat_norm(scalar * self.orientation) + new_state.velocity = scalar * self.velocity + new_state.angular_velocity = scalar * self.angular_velocity + + return new_state + + def insert_weights(self, weights: np.ndarray) -> np.ndarray: + """Inserts the weights into the covariance matrix.""" + new_state = StateQuatModel() + new_state.position = self.position - weights[:3] + new_state.orientation = quaternion_error(self.orientation, euler_to_quat(weights[3:6])) + new_state.velocity = self.velocity - weights[6:9] + new_state.angular_velocity = self.angular_velocity - weights[9:12] + + return new_state.as_vector() + + def add_without_quaternions(self, other: 'StateQuatModel') -> None: + """Adds elements into the state vector without considering the quaternions.""" + self.position += other.position + self.velocity += other.velocity + self.angular_velocity += other.angular_velocity + + +@dataclass +class process_model: + """ + A class defined for a general process model. + """ + state_vector: StateQuatModel = field(default_factory=StateQuatModel) + state_vector_dot: StateQuatModel = field(default_factory=StateQuatModel) + state_vector_prev: StateQuatModel = field(default_factory=StateQuatModel) + Control_input: np.ndarray = field(default_factory=lambda: np.zeros(6)) + mass_interia_matrix: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) + added_mass: np.ndarray = field(default_factory=lambda: np.zeros(6)) + damping_linear: np.ndarray = field(default_factory=lambda: np.zeros(6)) + damping_nonlinear: np.ndarray = field(default_factory=lambda: np.zeros(6)) + m: float = 0.0 + inertia: np.ndarray = field(default_factory=lambda: np.zeros((3,3))) + r_b_bg: np.ndarray = field(default_factory=lambda: np.zeros(3)) + dt: float = 0.0 + integral_error_position: np.ndarray = field(default_factory=lambda: np.zeros(3)) + integral_error_orientation: np.ndarray = field(default_factory=lambda: np.zeros(4)) + prev_position_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) + prev_orientation_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) + + def R(self) -> np.ndarray: + """Calculates the rotation matrix.""" + nu, e_1, e_2, e_3 = self.state_vector.orientation + R = np.array([ + [1 - 2 * e_2 ** 2 - 2 * e_3 ** 2, 2 * e_1 * e_2 - 2 * nu * e_3, 2 * e_1 * e_3 + 2 * nu * e_2], + [2 * e_1 * e_2 + 2 * nu * e_3, 1 - 2 * e_1 ** 2 - 2 * e_3 ** 2, 2 * e_2 * e_3 - 2 * nu * e_1], + [2 * e_1 * e_3 - 2 * nu * e_2, 2 * e_2 * e_3 + 2 * nu * e_1, 1 - 2 * e_1 ** 2 - 2 * e_2 ** 2] + ]) + return R + + def T(self) -> np.ndarray: + """Calculates the transformation matrix.""" + nu, e_1, e_2, e_3 = self.state_vector.orientation + T = 0.5 * np.array([ + [-e_1, -e_2, -e_3], + [nu, -e_3, e_2], + [e_3, nu, -e_1], + [-e_2, e_1, nu] + ]) + return T + + def Crb(self) -> np.ndarray: + """Calculates the Coriolis matrix.""" + ang_vel = self.state_vector.angular_velocity + ang_vel_skew = skew_matrix(ang_vel) + lever_arm_skew = skew_matrix(self.r_b_bg) + Crb = np.zeros((6, 6)) + Crb[0:3, 0:3] = self.m * ang_vel_skew + Crb[3:6, 3:6] = -skew_matrix(np.dot(self.inertia, ang_vel)) + Crb[0:3, 3:6] = -self.m * np.dot(ang_vel_skew, lever_arm_skew) + Crb[3:6, 0:3] = self.m * np.dot(lever_arm_skew, ang_vel_skew) + return Crb + + def D(self) -> np.ndarray: + """Calculates the damping matrix.""" + D_l = -np.diag(self.damping_linear) + D_nl = -np.diag(self.damping_nonlinear) * np.abs(self.state_vector.nu()) + return D_l + D_nl + + def model_prediction(self, state: StateQuatModel) -> None: + """Calculates the model of the system.""" + self.state_vector = state + self.state_vector_dot.position = np.dot(self.R(), self.state_vector.velocity) + self.state_vector_dot.orientation = np.dot(self.T(), self.state_vector.angular_velocity) + Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ (self.Control_input - np.dot(self.Crb(), self.state_vector.nu()) - np.dot(self.D(), self.state_vector.nu())) + self.state_vector_dot.velocity = Nu[:3] + self.state_vector_dot.angular_velocity = Nu[3:] + + def euler_forward(self) -> StateQuatModel: + """Calculates the forward Euler integration.""" + self.state_vector.position = self.state_vector_prev.position + self.state_vector_dot.position * self.dt + self.state_vector.orientation = quat_norm(self.state_vector_prev.orientation + self.state_vector_dot.orientation * self.dt) + self.state_vector.velocity = self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt + self.state_vector.angular_velocity = self.state_vector_prev.angular_velocity + self.state_vector_dot.angular_velocity * self.dt + return self.state_vector \ No newline at end of file diff --git a/navigation/eskf_python/eskf_python/ukf_okid_class.py b/navigation/eskf_python/eskf_python/ukf_okid_class.py deleted file mode 100644 index 8444fd82e..000000000 --- a/navigation/eskf_python/eskf_python/ukf_okid_class.py +++ /dev/null @@ -1,464 +0,0 @@ -from dataclasses import dataclass, field -import numpy as np - - -from dataclasses import dataclass, field -import numpy as np - -@dataclass -class StateQuat: - """ - A class to represent the state to be estimated by the UKF. - """ - position: np.ndarray = field(default_factory=lambda: np.zeros(3)) - orientation: np.ndarray = field(default_factory=lambda: np.array([1, 0, 0, 0])) - velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) - angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) - covariance: np.ndarray = field(default_factory=lambda: np.zeros((12, 12))) - - def as_vector(self) -> np.ndarray: - """Returns the StateVector as a numpy array.""" - return np.concatenate([self.position, self.orientation, self.velocity, self.angular_velocity]) - - def nu(self) -> np.ndarray: - """Calculates the nu vector.""" - return np.concatenate([self.velocity, self.angular_velocity]) - - def R_q(self) -> np.ndarray: - """Calculates the rotation matrix from the orientation quaternion.""" - q0, q1, q2, q3 = self.orientation - R = np.array([ - [1 - 2 * q2**2 - 2 * q3**2, 2 * (q1 * q2 - q0 * q3), 2 * (q0 * q2 + q1 * q3)], - [2 * (q1 * q2 + q0 * q3), 1 - 2 * q1**2 - 2 * q3**2, 2 * (q2 * q3 - q0 * q1)], - [2 * (q1 * q3 - q0 * q2), 2 * (q0 * q1 + q2 * q3), 1 - 2 * q1**2 - 2 * q2**2] - ]) - return R - - def fill_states(self, state: np.ndarray) -> None: - """Fills the state vector with the values from a numpy array.""" - self.position = state[0:3] - self.orientation = state[3:7] - self.velocity = state[7:10] - self.angular_velocity = state[10:13] - - def fill_states_different_dim(self, state: np.ndarray, state_euler: np.ndarray) -> None: - """Fills states when the state vector has different dimensions than the default state vector.""" - self.position = state[0:3] + state_euler[0:3] - self.orientation = quaternion_super_product(state[3:7], euler_to_quat(state_euler[3:6])) - self.velocity = state[7:10] + state_euler[6:9] - self.angular_velocity = state[10:13] + state_euler[9:12] - - def subtract(self, other: 'StateQuat') -> np.ndarray: - """Subtracts two StateQuat objects, returning the difference with Euler angles.""" - new_array = np.zeros(len(self.as_vector()) - 1) - new_array[:3] = self.position - other.position - new_array[3:6] = quat_to_euler(quaternion_error(self.orientation, other.orientation)) - new_array[6:9] = self.velocity - other.velocity - new_array[9:12] = self.angular_velocity - other.angular_velocity - - return new_array - - def __add__(self, other: 'StateQuat') -> 'StateQuat': - """Adds two StateQuat objects.""" - new_state = StateQuat() - new_state.position = self.position + other.position - new_state.orientation = quaternion_super_product(self.orientation, other.orientation) - new_state.velocity = self.velocity + other.velocity - new_state.angular_velocity = self.angular_velocity + other.angular_velocity - - return new_state - - def __sub__(self, other: 'StateQuat') -> 'StateQuat': - """Subtracts two StateQuat objects.""" - new_state = StateQuat() - new_state.position = self.position - other.position - new_state.orientation = quaternion_error(self.orientation, other.orientation) - new_state.velocity = self.velocity - other.velocity - new_state.angular_velocity = self.angular_velocity - other.angular_velocity - - return new_state.as_vector() - - def __rmul__(self, scalar: float) -> 'StateQuat': - """Multiplies the StateQuat object by a scalar.""" - new_state = StateQuat() - new_state.position = scalar * self.position - new_state.orientation = quat_norm(scalar * self.orientation) - new_state.velocity = scalar * self.velocity - new_state.angular_velocity = scalar * self.angular_velocity - - return new_state - - def insert_weights(self, weights: np.ndarray) -> np.ndarray: - """Inserts the weights into the covariance matrix.""" - new_state = StateQuat() - new_state.position = self.position - weights[:3] - new_state.orientation = quaternion_error(self.orientation, euler_to_quat(weights[3:6])) - new_state.velocity = self.velocity - weights[6:9] - new_state.angular_velocity = self.angular_velocity - weights[9:12] - - return new_state.as_vector() - - def add_without_quaternions(self, other: 'StateQuat') -> None: - """Adds elements into the state vector without considering the quaternions.""" - self.position += other.position - self.velocity += other.velocity - self.angular_velocity += other.angular_velocity - -@dataclass -class MeasModel: - """ - A class defined for a general measurement model. - """ - measurement: np.ndarray = field(default_factory=lambda: np.zeros(3)) - covariance: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) - - def H(self, state: StateQuat) -> 'MeasModel': - """Calculates the measurement matrix.""" - H = np.zeros((3, 13)) - H[:, 7:10] = np.eye(3) - z_i = MeasModel() - z_i.measurement = np.dot(H, state.as_vector()) - return z_i - - def __add__(self, other: 'MeasModel') -> 'MeasModel': - """Defines the addition operation between two MeasModel objects.""" - result = MeasModel() - result.measurement = self.measurement + other.measurement - return result - - def __rmul__(self, scalar: float) -> 'MeasModel': - """Defines multiplication between scalar value and MeasModel object.""" - result = MeasModel() - result.measurement = scalar * self.measurement - return result - - def __sub__(self, other: 'MeasModel') -> 'MeasModel': - """Defines the subtraction between two MeasModel objects.""" - result = MeasModel() - result.measurement = self.measurement - other.measurement - return result - -@dataclass -class process_model: - """ - A class defined for a general process model. - """ - state_vector: StateQuat = field(default_factory=StateQuat) - state_vector_dot: StateQuat = field(default_factory=StateQuat) - state_vector_prev: StateQuat = field(default_factory=StateQuat) - Control_input: np.ndarray = field(default_factory=lambda: np.zeros(6)) - mass_interia_matrix: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) - added_mass: np.ndarray = field(default_factory=lambda: np.zeros(6)) - damping_linear: np.ndarray = field(default_factory=lambda: np.zeros(6)) - damping_nonlinear: np.ndarray = field(default_factory=lambda: np.zeros(6)) - m: float = 0.0 - inertia: np.ndarray = field(default_factory=lambda: np.zeros((3,3))) - r_b_bg: np.ndarray = field(default_factory=lambda: np.zeros(3)) - dt: float = 0.0 - integral_error_position: np.ndarray = field(default_factory=lambda: np.zeros(3)) - integral_error_orientation: np.ndarray = field(default_factory=lambda: np.zeros(4)) - prev_position_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) - prev_orientation_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) - - def R(self) -> np.ndarray: - """Calculates the rotation matrix.""" - nu, e_1, e_2, e_3 = self.state_vector.orientation - R = np.array([ - [1 - 2 * e_2 ** 2 - 2 * e_3 ** 2, 2 * e_1 * e_2 - 2 * nu * e_3, 2 * e_1 * e_3 + 2 * nu * e_2], - [2 * e_1 * e_2 + 2 * nu * e_3, 1 - 2 * e_1 ** 2 - 2 * e_3 ** 2, 2 * e_2 * e_3 - 2 * nu * e_1], - [2 * e_1 * e_3 - 2 * nu * e_2, 2 * e_2 * e_3 + 2 * nu * e_1, 1 - 2 * e_1 ** 2 - 2 * e_2 ** 2] - ]) - return R - - def T(self) -> np.ndarray: - """Calculates the transformation matrix.""" - nu, e_1, e_2, e_3 = self.state_vector.orientation - T = 0.5 * np.array([ - [-e_1, -e_2, -e_3], - [nu, -e_3, e_2], - [e_3, nu, -e_1], - [-e_2, e_1, nu] - ]) - return T - - def Crb(self) -> np.ndarray: - """Calculates the Coriolis matrix.""" - ang_vel = self.state_vector.angular_velocity - ang_vel_skew = skew_symmetric(ang_vel) - lever_arm_skew = skew_symmetric(self.r_b_bg) - Crb = np.zeros((6, 6)) - Crb[0:3, 0:3] = self.m * ang_vel_skew - Crb[3:6, 3:6] = -skew_symmetric(np.dot(self.inertia, ang_vel)) - Crb[0:3, 3:6] = -self.m * np.dot(ang_vel_skew, lever_arm_skew) - Crb[3:6, 0:3] = self.m * np.dot(lever_arm_skew, ang_vel_skew) - return Crb - - def D(self) -> np.ndarray: - """Calculates the damping matrix.""" - D_l = -np.diag(self.damping_linear) - D_nl = -np.diag(self.damping_nonlinear) * np.abs(self.state_vector.nu()) - return D_l + D_nl - - def model_prediction(self, state: StateQuat) -> None: - """Calculates the model of the system.""" - self.state_vector = state - self.state_vector_dot.position = np.dot(self.R(), self.state_vector.velocity) - self.state_vector_dot.orientation = np.dot(self.T(), self.state_vector.angular_velocity) - Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ (self.Control_input - np.dot(self.Crb(), self.state_vector.nu()) - np.dot(self.D(), self.state_vector.nu())) - self.state_vector_dot.velocity = Nu[:3] - self.state_vector_dot.angular_velocity = Nu[3:] - - def euler_forward(self) -> StateQuat: - """Calculates the forward Euler integration.""" - self.state_vector.position = self.state_vector_prev.position + self.state_vector_dot.position * self.dt - self.state_vector.orientation = quat_norm(self.state_vector_prev.orientation + self.state_vector_dot.orientation * self.dt) - self.state_vector.velocity = self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt - self.state_vector.angular_velocity = self.state_vector_prev.angular_velocity + self.state_vector_dot.angular_velocity * self.dt - return self.state_vector - -def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: - """ - Converts Euler angles to a quaternion - """ - psi, theta, phi = euler_angles - c_psi = np.cos(psi / 2) - s_psi = np.sin(psi / 2) - c_theta = np.cos(theta / 2) - s_theta = np.sin(theta / 2) - c_phi = np.cos(phi / 2) - s_phi = np.sin(phi / 2) - - quat = np.array([ - c_psi * c_theta * c_phi + s_psi * s_theta * s_phi, - c_psi * c_theta * s_phi - s_psi * s_theta * c_phi, - s_psi * c_theta * s_phi + c_psi * s_theta * c_phi, - s_psi * c_theta * c_phi - c_psi * s_theta * s_phi - ]) - - return quat - -def quat_to_euler(quat: np.ndarray) -> np.ndarray: - """ - Converts a quaternion to Euler angles - """ - nu, eta_1, eta_2, eta_3 = quat - - phi = np.arctan2(2*(eta_2 * eta_3 + nu * eta_1), 1 - 2 * (eta_1 ** 2 + eta_2 ** 2)) - theta = -np.arcsin(2 * (eta_1 * eta_3 - nu * eta_2)) - psi = np.arctan2(2 * (nu * eta_3 + eta_1 * eta_2), 1 - 2 * (eta_2 ** 2 + eta_3 ** 2)) - - return np.array([phi, theta, psi]) - -def quat_norm(quat: np.ndarray) -> np.ndarray: - """ - Function that normalizes a quaternion - """ - - quat = quat / np.linalg.norm(quat) - - return quat - -def skew_symmetric(vector: np.ndarray) -> np.ndarray: - """Calculates the skew symmetric matrix of a vector. - - Args: - vector (np.ndarray): The vector. - - Returns: - np.ndarray: The skew symmetric matrix. - """ - return np.array( - [ - [0, -vector[2], vector[1]], - [vector[2], 0, -vector[0]], - [-vector[1], vector[0], 0], - ] - ) - -def quaternion_super_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: - """Calculates the quaternion super product of two quaternions. - - Args: - q1 (np.ndarray): The first quaternion. - q2 (np.ndarray): The second quaternion. - - Returns: - np.ndarray: The quaternion super product. - """ - eta_0, e_0_x, e_0_y, e_0_z = q1 - eta_1, e_1_x, e_1_y, e_1_z = q2 - - e_0 = np.array([e_0_x, e_0_y, e_0_z]) - e_1 = np.array([e_1_x, e_1_y, e_1_z]) - - eta_new = eta_0 * eta_1 - (e_0_x * e_1_x + e_0_y * e_1_y + e_0_z * e_1_z) - nu_new = e_1 * eta_0 + e_0 * eta_1 + np.dot(skew_symmetric(e_0), e_1) - - q_new = quat_norm(np.array([eta_new, nu_new[0], nu_new[1], nu_new[2]])) - - return q_new - -def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: - """ - Calculates the error between two quaternions - """ - - quat_2_inv = np.array([quat_2[0], -quat_2[1], -quat_2[2], -quat_2[3]]) - - error_quat = quaternion_super_product(quat_1, quat_2_inv) - - return error_quat - -def iterative_quaternion_mean_statequat(state_list: list[StateQuat], weights: np.ndarray, tol: float = 1e-6, max_iter: int = 100) -> np.ndarray: - """ - Computes the weighted mean of the quaternion orientations from a list of StateQuat objects - using an iterative approach, without requiring the caller to manually extract the quaternion. - - Parameters: - state_list (list[StateQuat]): List of StateQuat objects. - weights (np.ndarray): Weights for each state. - tol (float): Convergence tolerance. - max_iter (int): Maximum number of iterations. - - Returns: - np.ndarray: The averaged quaternion as a 4-element numpy array. - """ - # Internally extract the quaternion from each state - sigma_quats = [state.orientation for state in state_list] - - # Initialize the mean quaternion with the first quaternion - mean_q = sigma_quats[0].copy() - - for _ in range(max_iter): - weighted_error_vectors = [] - for i, q in enumerate(sigma_quats): - # Compute the error quaternion: e = q * inv(mean_q) - # For unit quaternions, the inverse is the conjugate. - mean_q_conj = np.array([mean_q[0], -mean_q[1], -mean_q[2], -mean_q[3]]) - e = quaternion_super_product(q, mean_q_conj) - - # Clip to avoid numerical issues - e0_clipped = np.clip(e[0], -1.0, 1.0) - angle = 2 * np.arccos(e0_clipped) - if np.abs(angle) < 1e-8: - error_vec = np.zeros(3) - else: - # Compute the full rotation vector (angle * axis) - error_vec = (angle / np.sin(angle / 2)) * e[1:4] - weighted_error_vectors.append(weights[i] * error_vec) - - error_avg = np.sum(weighted_error_vectors, axis=0) - if np.linalg.norm(error_avg) < tol: - break - - error_norm = np.linalg.norm(error_avg) - delta_q = (np.array([np.cos(error_norm / 2), - *(np.sin(error_norm / 2) * (error_avg / error_norm))]) - if error_norm > 0 else np.array([1.0, 0.0, 0.0, 0.0])) - mean_q = quaternion_super_product(delta_q, mean_q) - mean_q = quat_norm(mean_q) - - return mean_q - - - -def mean_set(set_points: list[StateQuat], weights: np.ndarray = None) -> np.ndarray: - """ - Function that calculates the mean of a set of points - """ - n = len(set_points[0].as_vector()) - 1 - mean_value = StateQuat() - - if weights is None: - for i in range(2 * n + 1): - weight_temp_list = (1/ (2 * n + 1)) * np.ones(2 * n + 1) - mean_value.add_without_quaternions(weight_temp_list[i] * set_points[i]) - - mean_value.orientation = iterative_quaternion_mean_statequat(set_points, weight_temp_list) - - else: - for i in range(2 * n + 1): - mean_value.add_without_quaternions(weights[i] * set_points[i]) - - mean_value.orientation = iterative_quaternion_mean_statequat(set_points, weights) - - return mean_value.as_vector() - -def mean_measurement(set_points: list[MeasModel], weights: np.ndarray = None) -> np.ndarray: - """ - Function that calculates the mean of a set of points - """ - n = len(set_points) - mean_value = MeasModel() - - if weights is None: - for i in range(n): - mean_value = mean_value + set_points[i] - else: - for i in range(n): - mean_value = mean_value + (weights[i] * set_points[i]) - - return mean_value.measurement - -def covariance_set(set_points: list[StateQuat], mean: np.ndarray, weights: np.ndarray = None) -> np.ndarray: - """ - Function that calculates the covariance of a set of points - """ - n = len(set_points[0].as_vector()) - 1 - covariance = np.zeros((n, n)) - mean_quat = StateQuat() - mean_quat.fill_states(mean) - - if weights is None: - for i in range(2 * n + 1): - covariance += np.outer(set_points[i].subtract(mean_quat), set_points[i].subtract(mean_quat)) - - covariance = (1 / (2 * n + 1)) * covariance - - else: - for i in range(2 * n + 1): - covariance += weights[i] * np.outer(set_points[i].subtract(mean_quat), set_points[i].subtract(mean_quat)) - - return covariance - -def covariance_measurement(set_points: list[MeasModel], mean: np.ndarray, weights: np.ndarray = None) -> np.ndarray: - """ - Function that calculates the covariance of a set of points - """ - n = len(set_points) - co_size = len(set_points[0].measurement) - covariance = np.zeros((co_size, co_size)) - mean_meas = MeasModel() - mean_meas.measurement = mean - - if weights is None: - for i in range(n): - temp_model = set_points[i] - mean_meas - covariance += np.outer(temp_model.measurement, temp_model.measurement) - - covariance = (1 / (n)) * covariance - - else: - for i in range(n): - temp_model = set_points[i] - mean_meas - covariance += weights[i] * np.outer(temp_model.measurement, temp_model.measurement) - - return covariance - -def cross_covariance(set_y: list[StateQuat], mean_y: np.ndarray, set_z: list[MeasModel], mean_z: np.ndarray, weights: np.ndarray) -> np.ndarray: - """ - Calculates the cross covariance between the measurement and state prediction - """ - - n = len(mean_y) - 1 - m = len(mean_z) - cross_covariance = np.zeros((n,m)) - mean_quat = StateQuat() - mean_quat.fill_states(mean_y) - - for i in range(n): - cross_covariance += np.outer(set_y[i].subtract(mean_quat), set_z[i].measurement - mean_z) - - cross_covariance = (1 / len(set_y)) * cross_covariance - - return cross_covariance From e110152d818afe8592c7a715b18c92071aff0ca3 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Thu, 20 Mar 2025 16:29:42 +0100 Subject: [PATCH 09/30] added changes to ukf --- .../eskf_python/eskf_python_class.py | 23 +- .../eskf_python/eskf_python_filter.py | 28 +- .../eskf_python/eskf_python/eskf_test.py | 185 ++++++---- navigation/ukf_okid/ukf_python/rest.py | 37 ++ navigation/ukf_okid/ukf_python/ukf_okid.py | 324 +----------------- .../ukf_okid/ukf_python/ukf_okid_class.py | 143 ++++---- navigation/ukf_okid/ukf_python/ukf_test.py | 323 +++++++++++++++++ navigation/ukf_okid/ukf_python/ukf_utils.py | 2 +- 8 files changed, 614 insertions(+), 451 deletions(-) create mode 100644 navigation/ukf_okid/ukf_python/rest.py create mode 100644 navigation/ukf_okid/ukf_python/ukf_test.py diff --git a/navigation/eskf_python/eskf_python/eskf_python_class.py b/navigation/eskf_python/eskf_python/eskf_python_class.py index c2ffc8e02..0ba96ba1f 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_class.py +++ b/navigation/eskf_python/eskf_python/eskf_python_class.py @@ -1,6 +1,6 @@ from dataclasses import dataclass, field import numpy as np - +from eskf_python_utils import quaternion_error @dataclass class StateQuat: @@ -82,6 +82,27 @@ def R_q(self) -> np.ndarray: return R + def __sub__(self, other: 'StateQuat') -> 'StateQuat': + """Subtracts the values of two state vectors. + + Args: + other (StateQuat): The state vector to subtract. + + Returns: + np.ndarray: The difference between the two state vectors. + """ + result = StateQuat() + result.position = self.position - other.position + result.velocity = self.velocity - other.velocity + result.orientation = quaternion_error(self.orientation, other.orientation) + result.acceleration_bias = self.acceleration_bias - other.acceleration_bias + result.gyro_bias = self.gyro_bias - other.gyro_bias + result.g = self.g - other.g + + return result + + + @dataclass class StateEuler: position: np.ndarray = field( diff --git a/navigation/eskf_python/eskf_python/eskf_python_filter.py b/navigation/eskf_python/eskf_python/eskf_python_filter.py index b1efeb0a9..8c4b01963 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_filter.py +++ b/navigation/eskf_python/eskf_python/eskf_python_filter.py @@ -185,7 +185,7 @@ def error_state_prediction(self, imu_data: Measurement) -> None: self.error_state.covariance = (A_d @ self.error_state.covariance @ A_d.T + GQG_d) - def measurement_update(self, dvl_measurement:Measurement) -> None: + def measurement_update(self, dvl_measurement:Measurement) -> float: """ Updates the error state using the DVL measurement. Joan Solà. Quaternion kinematics for the error-state Kalman filter. @@ -202,11 +202,16 @@ def measurement_update(self, dvl_measurement:Measurement) -> None: S = H @ P @ H.T + R K = P @ H.T @ np.linalg.inv(S) innovation = dvl_measurement.aiding - self.h() + + NIS_value = self.NIS(S, innovation) + self.error_state.fill_states(K @ innovation) I_KH = np.eye(18) - K @ H self.error_state.covariance = I_KH @ P @ I_KH.T + K @ R @ K.T # Joseph form for more stability + return NIS_value + def injection(self) -> None: """ Injects the error state into the nominal state to produce the estimated state. @@ -241,11 +246,26 @@ def imu_update(self, imu_data: Measurement) -> None: self.nominal_state_discrete(imu_data) self.error_state_prediction(imu_data) - def dvl_update(self, dvl_measurement: Measurement) -> None: + def dvl_update(self, dvl_measurement: Measurement) -> float: """ Updates the state using the DVL measurement. """ - self.measurement_update(dvl_measurement) + NIS = self.measurement_update(dvl_measurement) self.injection() - self.reset_error_state() \ No newline at end of file + self.reset_error_state() + + return NIS + + # functions for tuning the filter + def NIS(self, S: np.ndarray, innovation: np.ndarray) -> float: + """ + Calculates the Normalized Innovation Squared (NIS) value. + """ + return innovation.T @ np.linalg.inv(S) @ innovation + + def NEES(self, P: np.ndarray, true_state: StateQuat, estimate_state: StateQuat) -> float: + """ + Calculates the Normalized Estimation Error Squared (NEES) value. + """ + return (true_state - estimate_state).as_vector().T @ np.linalg.inv(P) @ (true_state - estimate_state).as_vector() \ No newline at end of file diff --git a/navigation/eskf_python/eskf_python/eskf_test.py b/navigation/eskf_python/eskf_python/eskf_test.py index bf4cc8f8b..95f5e996b 100644 --- a/navigation/eskf_python/eskf_python/eskf_test.py +++ b/navigation/eskf_python/eskf_python/eskf_test.py @@ -5,8 +5,9 @@ import numpy as np import matplotlib.pyplot as plt from eskf_python_filter import ESKF +from scipy.stats import chi2 -if __name__ == "__main__": +def simulate_eskf(): # Simulation parameters simulation_time = 20.0 # seconds @@ -20,7 +21,7 @@ true_state_init.position = np.array([0.1, 0.0, 0.0]) true_state_init.velocity = np.array([0.1, 0.0, 0.0]) P0 = np.diag([ - 1.0, 1.0, 1.0, # Position + 0.5, 0.5, 0.5, # Position 0.2, 0.2, 0.2, # Velocity 0.2, 0.2, 0.2, # Orientation 0.00001, 0.00001, 0.00001, # Acceleration bias @@ -30,14 +31,14 @@ # Noise parameters Q = np.diag([ - (0.05**2) / dt, (0.05**2) / dt, (0.05**2) / dt, # Accelerometer noise - (0.004**2) / dt, (0.004**2) / dt, (0.004**2) / dt, # Gyroscope noise - 0.0002, 0.0002, 0.0002, # Acceleration bias random walk - 0.0001, 0.0001, 0.0001 # Gyro bias random walk + (0.034**2) / dt, (0.034**2) / dt, (0.034**2) / dt, # Accelerometer noise + (0.002**2) / dt, (0.002**2) / dt, (0.002**2) / dt, # Gyroscope noise + 0.00001, 0.00001, 0.00001, # Acceleration bias random walk + 0.00001, 0.00001, 0.00001 # Gyro bias random walk ]) Hx = np.zeros((3, 19)) - Hx[0:3, 6:9] = np.eye(3) + Hx[0:3, 3:6] = np.eye(3) # Create filter object eskf = ESKF(Q, P0, Hx, true_state_init, 1e-13, 1e-13, dt) @@ -47,7 +48,7 @@ dvl_data = Measurement() # R matrix for DVL aiding - dvl_data.aiding_covariance = np.diag([(0.5)**2, (0.5)**2, (0.5)**2]) + dvl_data.aiding_covariance = np.diag([(0.01)**2, (0.01)**2, (0.01)**2]) # Setup the process model for simulation of AUV model = process_model() @@ -102,6 +103,9 @@ 0.05 * np.cos(0.1 * t + 0.6) ]) + NIS_list = [] + NIS_value = 0.0 + # Sim for step in range(num_steps): t = step * dt @@ -117,7 +121,8 @@ if step % 20 == 0: dvl_data.aiding = new_state.velocity + np.random.normal(0, 0.01, 3) - eskf.dvl_update(dvl_data) + NIS_value = eskf.dvl_update(dvl_data) + NIS_list.append(NIS_value) true_positions[step, :] = np.copy(new_state.position) true_orientations[step, :] = quat_to_euler(np.copy(new_state.orientation)) @@ -135,64 +140,104 @@ prev_velocity = new_state.velocity model.state_vector_prev = new_state - # Plotting - axis_labels_pos = ["X", "Y", "Z"] - axis_labels_vel = ["X", "Y", "Z"] - axis_labels_ori = ["Roll", "Pitch", "Yaw"] - - # Plot Position - fig_pos, axs_pos = plt.subplots(3, 1, figsize=(10, 12)) - fig_pos.suptitle("True Data vs Filter Estimates for Position") - for i in range(3): - ax_pos = axs_pos[i] - ax_pos.plot(time, true_positions[:, i], label=f"True Pos {axis_labels_pos[i]}", color=f"C{i}", linestyle='-') - ax_pos.plot(time, est_positions[:, i], label=f"Est Pos {axis_labels_pos[i]}", color=f"C{i}", linestyle='--') - sigma_pos = np.sqrt(pos_cov[:, i]) - ax_pos.fill_between(time, est_positions[:, i] - sigma_pos, est_positions[:, i] + sigma_pos, - color=f"C{i}", alpha=0.2) - ax_pos.set_title(f"Position [{axis_labels_pos[i]}] [m]") - ax_pos.set_xlabel("Time [s]") - ax_pos.set_ylabel("Position") - ax_pos.grid(True) - ax_pos.legend() - - plt.tight_layout(rect=[0, 0, 1, 0.96]) - plt.show() - - # Plot Velocity - fig_vel, axs_vel = plt.subplots(3, 1, figsize=(10, 12)) - fig_vel.suptitle("True Data vs Filter Estimates for Velocity") - for i in range(3): - ax_vel = axs_vel[i] - ax_vel.plot(time, true_velocities[:, i], label=f"True Vel {axis_labels_vel[i]}", color=f"C{i}", linestyle='-') - ax_vel.plot(time, est_velocities[:, i], label=f"Est Vel {axis_labels_vel[i]}", color=f"C{i}", linestyle='--') - sigma_vel = np.sqrt(vel_cov[:, i]) - ax_vel.fill_between(time, est_velocities[:, i] - sigma_vel, est_velocities[:, i] + sigma_vel, - color=f"C{i}", alpha=0.2) - ax_vel.set_title(f"Velocity [{axis_labels_vel[i]}] [m/s]") - ax_vel.set_xlabel("Time [s]") - ax_vel.set_ylabel("Velocity") - ax_vel.grid(True) - ax_vel.legend() - - plt.tight_layout(rect=[0, 0, 1, 0.96]) - plt.show() - - # Plot Orientation - fig_ori, axs_ori = plt.subplots(3, 1, figsize=(10, 12)) - fig_ori.suptitle("True Data vs Filter Estimates for Orientation") - for i in range(3): - ax_ori = axs_ori[i] - ax_ori.plot(time, true_orientations[:, i], label=f"True Ori {axis_labels_ori[i]}", color=f"C{i}", linestyle='-') - ax_ori.plot(time, est_orientations[:, i], label=f"Est Ori {axis_labels_ori[i]}", color=f"C{i}", linestyle='--') - sigma_ori = np.sqrt(ori_cov[:, i]) - ax_ori.fill_between(time, est_orientations[:, i] - sigma_ori, est_orientations[:, i] + sigma_ori, - color=f"C{i}", alpha=0.2) - ax_ori.set_title(f"Orientation [{axis_labels_ori[i]}] [rad]") - ax_ori.set_xlabel("Time [s]") - ax_ori.set_ylabel("Orientation") - ax_ori.grid(True) - ax_ori.legend() - - plt.tight_layout(rect=[0, 0, 1, 0.96]) - plt.show() + return time, true_positions, true_orientations, true_velocities, est_positions, est_orientations, est_velocities, pos_cov, vel_cov, ori_cov, NIS_list + +time, true_positions, true_orientations, true_velocities, est_positions, est_orientations, est_velocities, pos_cov, vel_cov, ori_cov, _ = simulate_eskf() + +# Plotting +axis_labels_pos = ["X", "Y", "Z"] +axis_labels_vel = ["X", "Y", "Z"] +axis_labels_ori = ["Roll", "Pitch", "Yaw"] + +# Plot Position +fig_pos, axs_pos = plt.subplots(3, 1, figsize=(10, 12)) +fig_pos.suptitle("True Data vs Filter Estimates for Position") +for i in range(3): + ax_pos = axs_pos[i] + ax_pos.plot(time, true_positions[:, i], label=f"True Pos {axis_labels_pos[i]}", color=f"C{i}", linestyle='-') + ax_pos.plot(time, est_positions[:, i], label=f"Est Pos {axis_labels_pos[i]}", color=f"C{i}", linestyle='--') + sigma_pos = np.sqrt(pos_cov[:, i]) + ax_pos.fill_between(time, est_positions[:, i] - sigma_pos, est_positions[:, i] + sigma_pos, + color=f"C{i}", alpha=0.2) + ax_pos.set_title(f"Position [{axis_labels_pos[i]}] [m]") + ax_pos.set_xlabel("Time [s]") + ax_pos.set_ylabel("Position") + ax_pos.grid(True) + ax_pos.legend() + +plt.tight_layout(rect=[0, 0, 1, 0.96]) +plt.show() + +# Plot Velocity +fig_vel, axs_vel = plt.subplots(3, 1, figsize=(10, 12)) +fig_vel.suptitle("True Data vs Filter Estimates for Velocity") +for i in range(3): + ax_vel = axs_vel[i] + ax_vel.plot(time, true_velocities[:, i], label=f"True Vel {axis_labels_vel[i]}", color=f"C{i}", linestyle='-') + ax_vel.plot(time, est_velocities[:, i], label=f"Est Vel {axis_labels_vel[i]}", color=f"C{i}", linestyle='--') + sigma_vel = np.sqrt(vel_cov[:, i]) + ax_vel.fill_between(time, est_velocities[:, i] - sigma_vel, est_velocities[:, i] + sigma_vel, + color=f"C{i}", alpha=0.2) + ax_vel.set_title(f"Velocity [{axis_labels_vel[i]}] [m/s]") + ax_vel.set_xlabel("Time [s]") + ax_vel.set_ylabel("Velocity") + ax_vel.grid(True) + ax_vel.legend() + +plt.tight_layout(rect=[0, 0, 1, 0.96]) +plt.show() + +# Plot Orientation +fig_ori, axs_ori = plt.subplots(3, 1, figsize=(10, 12)) +fig_ori.suptitle("True Data vs Filter Estimates for Orientation") +for i in range(3): + ax_ori = axs_ori[i] + ax_ori.plot(time, true_orientations[:, i], label=f"True Ori {axis_labels_ori[i]}", color=f"C{i}", linestyle='-') + ax_ori.plot(time, est_orientations[:, i], label=f"Est Ori {axis_labels_ori[i]}", color=f"C{i}", linestyle='--') + sigma_ori = np.sqrt(ori_cov[:, i]) + ax_ori.fill_between(time, est_orientations[:, i] - sigma_ori, est_orientations[:, i] + sigma_ori, + color=f"C{i}", alpha=0.2) + ax_ori.set_title(f"Orientation [{axis_labels_ori[i]}] [rad]") + ax_ori.set_xlabel("Time [s]") + ax_ori.set_ylabel("Orientation") + ax_ori.grid(True) + ax_ori.legend() + +plt.tight_layout(rect=[0, 0, 1, 0.96]) +plt.show() + + +### _______ NIS AND NEES _______ + +num_simulations = 10 +NIS_runs = [] + +for sim in range(num_simulations): + time, true_positions, true_orientations, true_velocities, \ + est_positions, est_orientations, est_velocities, \ + pos_cov, vel_cov, ori_cov, NIS_list = simulate_eskf() + + NIS_runs.append(np.array(NIS_list)) + +NIS_runs = np.vstack(NIS_runs) +ANIS = np.mean(NIS_runs, axis=0) + +measurement_dimension = 3 + +chi2_lower = chi2.ppf(0.025, measurement_dimension) / num_simulations +chi2_upper = chi2.ppf(0.975, measurement_dimension) / num_simulations + +time_steps = np.arange(len(ANIS)) * 0.01 * 20 + +fig, ax = plt.subplots(figsize=(10, 6)) +ax.plot(time_steps, ANIS, label="ANIS", color="C0") +ax.axhline(chi2_lower, color="C1", linestyle="--", label="95% CI Lower") +ax.axhline(chi2_upper, color="C2", linestyle="--", label="95% CI Upper") +ax.set_title("Average Normalized Innovation Squared (ANIS)") +ax.set_xlabel("Time [s]") +ax.set_ylabel("ANIS") +ax.grid(True) +ax.legend() + +plt.tight_layout() +plt.show() \ No newline at end of file diff --git a/navigation/ukf_okid/ukf_python/rest.py b/navigation/ukf_okid/ukf_python/rest.py new file mode 100644 index 000000000..df7392bd4 --- /dev/null +++ b/navigation/ukf_okid/ukf_python/rest.py @@ -0,0 +1,37 @@ +def mean_set(set_points: list[StateQuat], weights: np.ndarray = None) -> np.ndarray: + """ + Function that calculates the mean of a set of points + """ + n = len(set_points[0].as_vector()) - 1 + mean_value = StateQuat() + + if weights is None: + for i in range(2 * n + 1): + weight_temp_list = (1/ (2 * n + 1)) * np.ones(2 * n + 1) + mean_value.add_without_quaternions(weight_temp_list[i] * set_points[i]) + + mean_value.orientation = iterative_quaternion_mean_statequat(set_points, weight_temp_list) + + else: + for i in range(2 * n + 1): + mean_value.add_without_quaternions(weights[i] * set_points[i]) + + mean_value.orientation = iterative_quaternion_mean_statequat(set_points, weights) + + return mean_value.as_vector() + +def mean_measurement(set_points: list[MeasModel], weights: np.ndarray = None) -> np.ndarray: + """ + Function that calculates the mean of a set of points + """ + n = len(set_points) + mean_value = MeasModel() + + if weights is None: + for i in range(n): + mean_value = mean_value + set_points[i] + else: + for i in range(n): + mean_value = mean_value + (weights[i] * set_points[i]) + + return mean_value.measurement \ No newline at end of file diff --git a/navigation/ukf_okid/ukf_python/ukf_okid.py b/navigation/ukf_okid/ukf_python/ukf_okid.py index dd52c6589..1ede3f22b 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid.py @@ -14,9 +14,9 @@ def __init__(self, process_model: process_model, x_0, P_0, Q, R): self.sigma_points_list = None self.y_i = None self.weight = None - # self.T = self.generate_T_matrix(len(P_0)) + self.T = self.generate_T_matrix(len(P_0)) - def generate_T_matrix(n): + def generate_T_matrix(n: float) -> np.ndarray: """ Generates the orthonormal transformation matrix T used in the TUKF sigma point generation. @@ -28,42 +28,36 @@ def generate_T_matrix(n): """ T = np.zeros((n, 2 * n)) - for i in range(1, 2 * n + 1): # indexing matches equation (1, ..., 2n) + for i in range(1, 2 * n + 1): for j in range(1, (n // 2) + 1): T[2 * j - 2, i - 1] = np.sqrt(2) * np.cos(((2 * j - 1) * i * np.pi) / n) T[2 * j - 1, i - 1] = np.sqrt(2) * np.sin(((2 * j - 1) * i * np.pi) / n) - if n % 2 == 1: # if n is odd, add the last term as described in the paper + if n % 2 == 1: # if n is odd T[n - 1, i - 1] = (-1) ** i - T = T / np.sqrt(2) # Normalize matrix for orthonormality (unit scaling) + T = T / np.sqrt(2) return T - def sigma_points(self, current_state: StateQuat) -> tuple[list[StateQuat], np.ndarray]: + def sigma_points(self, current_state: StateQuat) -> list[StateQuat]: """ Functions that generate the sigma points for the UKF """ n = len(current_state.covariance) - kappa = 3 - n - S = np.linalg.cholesky(current_state.covariance + self.Q) - S_scaled = np.sqrt(n + kappa) * S - - weighted_points = np.concatenate([S_scaled, -S_scaled], axis=1) + I = np.hstack([np.eye(n), -np.eye(n)]) + my = np.sqrt(n) * I + delta = self.T @ my - self.sigma_points_list = [StateQuat() for _ in range(2 * n + 1)] - W = np.zeros(2 * n + 1) - - self.sigma_points_list [0].fill_states(current_state.as_vector()) - W[0] = kappa / (n + kappa) - for i in range(2 * n): - self.sigma_points_list [i + 1].fill_states(current_state.insert_weights(weighted_points[:, i])) - W[i + 1] = 1 / (2 * (n + kappa)) + S = np.linalg.cholesky(current_state.covariance + self.Q) - self.weight = W + self.sigma_points_list = [StateQuat() for _ in range(2 * n)] + + for state in self.sigma_points_list: + state.fill_states_different_dim(current_state.as_vector(), delta[:, self.sigma_points_list.index - return self.sigma_points_list , self.weight + return self.sigma_points_list def unscented_transform(self, current_state: StateQuat) -> StateQuat: @@ -128,290 +122,4 @@ def posteriori_estimate(self, current_state: StateQuat, cross_correlation: np.nd self.process_model.state_vector_prev = posteriori_estimate - return posteriori_estimate - -def add_quaternion_noise(q, noise_std): - - noise = np.random.normal(0, noise_std, 3) - - theta = np.linalg.norm(noise) - - if theta > 0: - - axis = noise / theta - - q_noise = np.hstack((np.cos(theta/2), np.sin(theta/2) * axis)) - - else: - - q_noise = np.array([1.0, 0.0, 0.0, 0.0]) - - q_new = quaternion_super_product(q, q_noise) - - return q_new / np.linalg.norm(q_new) - - -if __name__ == '__main__': - - # Create initial state vector and covariance matrix. - x0 = np.zeros(13) - x0[0:3] = [0.3, 0.3, 0.3] - x0[3] = 1 - x0[7:10] = [0.2, 0.2, 0.2] - dt = 0.01 - R = (0.01) * np.eye(3) - - Q = 0.00015 * np.eye(12) - P0 = np.eye(12) * 0.0001 - - model = process_model() - model.dt = 0.01 - model.mass_interia_matrix = np.array([ - [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] - ]) - model.m = 30.0 - model.r_b_bg = np.array([0.01, 0.0, 0.02]) - model.inertia = np.diag([0.68, 3.32, 3.34]) - model.damping_linear = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) - model.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) - model.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) - - model_ukf = process_model() - model_ukf.dt = 0.01 - model_ukf.mass_interia_matrix = np.array([ - [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] - ]) - model_ukf.m = 30.0 - model_ukf.r_b_bg = np.array([0.01, 0.0, 0.02]) - model_ukf.inertia = np.diag([0.68, 3.32, 3.34]) - model_ukf.damping_linear = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) - model_ukf.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) - model_ukf.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) - - # Simulation parameters - simulation_time = 20 # seconds - num_steps = int(simulation_time / dt) - - # Initialize a dummy StateQuat. - new_state = StateQuat() - new_state.fill_states(x0) - new_state.covariance = P0 - - test_state_x = StateQuat() - test_state_x.fill_states(x0) - test_state_x.covariance = P0 - - # Initialize a estimated state - estimated_state = StateQuat() - estimated_state.fill_states(x0) - estimated_state.covariance = P0 - - # Initialize a estimated state - noisy_state = StateQuat() - noisy_state.fill_states(x0) - noisy_state.covariance = P0 - - measurment_model = MeasModel() - measurment_model.measurement = np.array([0.0, 0.0, 0.0]) - measurment_model.covariance = R - - # Initialize arrays to store the results - positions = np.zeros((num_steps, 3)) - orientations = np.zeros((num_steps, 3)) - velocities = np.zeros((num_steps, 3)) - angular_velocities = np.zeros((num_steps, 3)) - - # Initialize arrays to store the estimates - positions_est = np.zeros((num_steps, 3)) - orientations_est = np.zeros((num_steps, 3)) - velocities_est = np.zeros((num_steps, 3)) - angular_velocities_est = np.zeros((num_steps, 3)) - - # Initialize the okid params - okid_params = np.zeros((num_steps, 21)) - - model.state_vector_prev = new_state - model.state_vector = new_state - - model_ukf.state_vector_prev = test_state_x - model_ukf.state_vector = test_state_x - - # initialize the ukf - ukf = UKF(model_ukf, x0, P0, Q, R) - - elapsed_times = [] - - u = lambda t: np.array([2 * np.sin(1 * t), 2 * np.sin(1 * t), 2 * np.sin(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t)]) - - # Run the simulation - for step in range(num_steps): - # Insert control input - model.Control_input = u(step * dt) - model_ukf.Control_input = u(step * dt) - - # Perform the unscented transform - model.model_prediction(new_state) - new_state = model.euler_forward() - - # Adding noise in the state vector - estimated_state.position = estimated_state.position # + np.random.normal(0, 0.01, 3) - estimated_state.orientation = estimated_state.orientation #add_quaternion_noise(estimated_state.orientation, 0.01) - estimated_state.velocity = estimated_state.velocity # + np.random.normal(0, 0.01, 3) - estimated_state.angular_velocity = estimated_state.angular_velocity # + np.random.normal(0, 0.01, 3) - - start_time = time.time() - estimated_state = ukf.unscented_transform(estimated_state) - elapsed_time = time.time() - start_time - elapsed_times.append(elapsed_time) - - if step % 10 == 0: - measurment_model.measurement = new_state.velocity # + np.random.normal(0, 0.01, 3) - meas_update, covariance_matrix = ukf.measurement_update(estimated_state, measurment_model) - estimated_state = ukf.posteriori_estimate(estimated_state, covariance_matrix, measurment_model, meas_update) - - - positions[step, :] = new_state.position - orientations[step, :] = quat_to_euler(new_state.orientation) - velocities[step, :] = new_state.velocity - angular_velocities[step, :] = new_state.angular_velocity - - positions_est[step, :] = estimated_state.position - orientations_est[step, :] = quat_to_euler(estimated_state.orientation) - velocities_est[step, :] = estimated_state.velocity - angular_velocities_est[step, :] = estimated_state.angular_velocity - - # Update the state for the next iteration - model.state_vector_prev = new_state - - print('Average elapsed time: ', np.mean(elapsed_times)) - print('Max elapsed time: ', np.max(elapsed_times)) - print('Min elapsed time: ', np.min(elapsed_times)) - print('median elapsed time: ', np.median(elapsed_times)) - # Plot the results - time = np.linspace(0, simulation_time, num_steps) - - # Plot positions - plt.figure() - plt.subplot(3, 1, 1) - plt.plot(time, positions[:, 0], label='True') - plt.plot(time, positions_est[:, 0], label='Estimated') - plt.title('Position X') - plt.xlabel('Time [s]') - plt.ylabel('Position X [m]') - plt.legend() - - plt.subplot(3, 1, 2) - plt.plot(time, positions[:, 1], label='True') - plt.plot(time, positions_est[:, 1], label='Estimated') - plt.title('Position Y') - plt.xlabel('Time [s]') - plt.ylabel('Position Y [m]') - plt.legend() - - plt.subplot(3, 1, 3) - plt.plot(time, positions[:, 2], label='True') - plt.plot(time, positions_est[:, 2], label='Estimated') - plt.title('Position Z') - plt.xlabel('Time [s]') - plt.ylabel('Position Z [m]') - plt.legend() - - plt.tight_layout() - plt.show() - - # Plot orientations (Euler angles) - plt.figure() - plt.subplot(3, 1, 1) - plt.plot(time, orientations[:, 0], label='True') - plt.plot(time, orientations_est[:, 0], label='Estimated') - plt.title('Orientation Roll') - plt.xlabel('Time [s]') - plt.ylabel('Roll [rad]') - plt.legend() - - plt.subplot(3, 1, 2) - plt.plot(time, orientations[:, 1], label='True') - plt.plot(time, orientations_est[:, 1], label='Estimated') - plt.title('Orientation Pitch') - plt.xlabel('Time [s]') - plt.ylabel('Pitch [rad]') - plt.legend() - - plt.subplot(3, 1, 3) - plt.plot(time, orientations[:, 2], label='True') - plt.plot(time, orientations_est[:, 2], label='Estimated') - plt.title('Orientation Yaw') - plt.xlabel('Time [s]') - plt.ylabel('Yaw [rad]') - plt.legend() - - plt.tight_layout() - plt.show() - - # Plot velocities - plt.figure() - plt.subplot(3, 1, 1) - plt.plot(time, velocities[:, 0], label='True') - plt.plot(time, velocities_est[:, 0], label='Estimated') - plt.title('Velocity X') - plt.xlabel('Time [s]') - plt.ylabel('Velocity X [m/s]') - plt.legend() - - plt.subplot(3, 1, 2) - plt.plot(time, velocities[:, 1], label='True') - plt.plot(time, velocities_est[:, 1], label='Estimated') - plt.title('Velocity Y') - plt.xlabel('Time [s]') - plt.ylabel('Velocity Y [m/s]') - plt.legend() - - plt.subplot(3, 1, 3) - plt.plot(time, velocities[:, 2], label='True') - plt.plot(time, velocities_est[:, 2], label='Estimated') - plt.title('Velocity Z') - plt.xlabel('Time [s]') - plt.ylabel('Velocity Z [m/s]') - plt.legend() - - plt.tight_layout() - plt.show() - - # Plot angular velocities - plt.figure() - plt.subplot(3, 1, 1) - plt.plot(time, angular_velocities[:, 0], label='True') - plt.plot(time, angular_velocities_est[:, 0], label='Estimated') - plt.title('Angular Velocity X') - plt.xlabel('Time [s]') - plt.ylabel('Angular Velocity X [rad/s]') - plt.legend() - - plt.subplot(3, 1, 2) - plt.plot(time, angular_velocities[:, 1], label='True') - plt.plot(time, angular_velocities_est[:, 1], label='Estimated') - plt.title('Angular Velocity Y') - plt.xlabel('Time [s]') - plt.ylabel('Angular Velocity Y [rad/s]') - plt.legend() - - plt.subplot(3, 1, 3) - plt.plot(time, angular_velocities[:, 2], label='True') - plt.plot(time, angular_velocities_est[:, 2], label='Estimated') - plt.title('Angular Velocity Z') - plt.xlabel('Time [s]') - plt.ylabel('Angular Velocity Z [rad/s]') - plt.legend() - - plt.tight_layout() - plt.show() \ No newline at end of file + return posteriori_estimate \ No newline at end of file diff --git a/navigation/ukf_okid/ukf_python/ukf_okid_class.py b/navigation/ukf_okid/ukf_python/ukf_okid_class.py index 8444fd82e..50f1988b4 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid_class.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid_class.py @@ -48,11 +48,11 @@ def fill_states_different_dim(self, state: np.ndarray, state_euler: np.ndarray) self.velocity = state[7:10] + state_euler[6:9] self.angular_velocity = state[10:13] + state_euler[9:12] - def subtract(self, other: 'StateQuat') -> np.ndarray: + def subtract(self, other: 'StateQuat', error_ori: 'np.ndarray') -> np.ndarray: """Subtracts two StateQuat objects, returning the difference with Euler angles.""" new_array = np.zeros(len(self.as_vector()) - 1) new_array[:3] = self.position - other.position - new_array[3:6] = quat_to_euler(quaternion_error(self.orientation, other.orientation)) + new_array[3:6] = error_ori new_array[6:9] = self.velocity - other.velocity new_array[9:12] = self.angular_velocity - other.angular_velocity @@ -115,7 +115,7 @@ class MeasModel: def H(self, state: StateQuat) -> 'MeasModel': """Calculates the measurement matrix.""" H = np.zeros((3, 13)) - H[:, 7:10] = np.eye(3) + H[0:3, 7:10] = np.eye(3) z_i = MeasModel() z_i.measurement = np.dot(H, state.as_vector()) return z_i @@ -309,7 +309,7 @@ def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: return error_quat -def iterative_quaternion_mean_statequat(state_list: list[StateQuat], weights: np.ndarray, tol: float = 1e-6, max_iter: int = 100) -> np.ndarray: +def iterative_quaternion_mean_statequat(state_list: list[StateQuat], tol: float = 1e-6, max_iter: int = 100) -> np.ndarray: """ Computes the weighted mean of the quaternion orientations from a list of StateQuat objects using an iterative approach, without requiring the caller to manually extract the quaternion. @@ -323,142 +323,151 @@ def iterative_quaternion_mean_statequat(state_list: list[StateQuat], weights: np Returns: np.ndarray: The averaged quaternion as a 4-element numpy array. """ - # Internally extract the quaternion from each state + sigma_quats = [state.orientation for state in state_list] - - # Initialize the mean quaternion with the first quaternion + n = len(state_list) + mean_q = sigma_quats[0].copy() for _ in range(max_iter): weighted_error_vectors = [] for i, q in enumerate(sigma_quats): - # Compute the error quaternion: e = q * inv(mean_q) - # For unit quaternions, the inverse is the conjugate. mean_q_conj = np.array([mean_q[0], -mean_q[1], -mean_q[2], -mean_q[3]]) e = quaternion_super_product(q, mean_q_conj) - # Clip to avoid numerical issues e0_clipped = np.clip(e[0], -1.0, 1.0) angle = 2 * np.arccos(e0_clipped) if np.abs(angle) < 1e-8: error_vec = np.zeros(3) else: - # Compute the full rotation vector (angle * axis) error_vec = (angle / np.sin(angle / 2)) * e[1:4] - weighted_error_vectors.append(weights[i] * error_vec) + weighted_error_vectors.append(error_vec) - error_avg = np.sum(weighted_error_vectors, axis=0) + error_avg = (1 / n) * np.sum(weighted_error_vectors, axis=0) if np.linalg.norm(error_avg) < tol: break error_norm = np.linalg.norm(error_avg) - delta_q = (np.array([np.cos(error_norm / 2), - *(np.sin(error_norm / 2) * (error_avg / error_norm))]) - if error_norm > 0 else np.array([1.0, 0.0, 0.0, 0.0])) + if error_norm > 0: + delta_q = np.array([np.cos(error_norm / 2), + *(np.sin(error_norm / 2) * (error_avg / error_norm))]) + else: + delta_q = np.array([1.0, 0.0, 0.0, 0.0]) + mean_q = quaternion_super_product(delta_q, mean_q) mean_q = quat_norm(mean_q) return mean_q - - -def mean_set(set_points: list[StateQuat], weights: np.ndarray = None) -> np.ndarray: +def mean_set(set_points: list[StateQuat]) -> np.ndarray: """ - Function that calculates the mean of a set of points + Functio calculates the mean vector of a set of points + + Args: + set_points (list[StateQuat]): List of StateQuat objects + + Returns: + np.ndarray: The mean vector """ - n = len(set_points[0].as_vector()) - 1 + n = len(set_points) mean_value = StateQuat() - if weights is None: - for i in range(2 * n + 1): - weight_temp_list = (1/ (2 * n + 1)) * np.ones(2 * n + 1) - mean_value.add_without_quaternions(weight_temp_list[i] * set_points[i]) - - mean_value.orientation = iterative_quaternion_mean_statequat(set_points, weight_temp_list) + for state in set_points: + mean_value.add_without_quaternions(state) - else: - for i in range(2 * n + 1): - mean_value.add_without_quaternions(weights[i] * set_points[i]) + mean_value = (1 / (n)) * mean_value + + mean_value.orientation = iterative_quaternion_mean_statequat(set_points) - mean_value.orientation = iterative_quaternion_mean_statequat(set_points, weights) - return mean_value.as_vector() -def mean_measurement(set_points: list[MeasModel], weights: np.ndarray = None) -> np.ndarray: +def mean_measurement(set_points: list[MeasModel]) -> np.ndarray: """ Function that calculates the mean of a set of points """ n = len(set_points) mean_value = MeasModel() - if weights is None: - for i in range(n): - mean_value = mean_value + set_points[i] - else: - for i in range(n): - mean_value = mean_value + (weights[i] * set_points[i]) + for state in set_points: + mean_value = mean_value + state + mean_value = (1 / n) * mean_value + return mean_value.measurement -def covariance_set(set_points: list[StateQuat], mean: np.ndarray, weights: np.ndarray = None) -> np.ndarray: +def covariance_set(set_points: list[StateQuat], mean: StateQuat) -> np.ndarray: """ Function that calculates the covariance of a set of points """ - n = len(set_points[0].as_vector()) - 1 - covariance = np.zeros((n, n)) + n = len(set_points) + covariance = np.zeros(set_points[0].covariance.shape) + mean_quat = StateQuat() - mean_quat.fill_states(mean) + mean_quat.fill_states(mean.as_vector()) - if weights is None: - for i in range(2 * n + 1): - covariance += np.outer(set_points[i].subtract(mean_quat), set_points[i].subtract(mean_quat)) + mean_q = mean.orientation - covariance = (1 / (2 * n + 1)) * covariance + for state in set_points: + q = state.orientation + diff_q = quaternion_error(q, mean_q) + + e0_clipped = np.clip(diff_q[0], -1.0, 1.0) + angle = 2.0 * np.arccos(e0_clipped) + if abs(angle) < 1e-8: + e_vec = np.zeros(3) + else: + e_vec = (angle / np.sin(angle/2)) * diff_q[1:4] - else: - for i in range(2 * n + 1): - covariance += weights[i] * np.outer(set_points[i].subtract(mean_quat), set_points[i].subtract(mean_quat)) + covariance += np.outer(state.subtract(mean_quat, e_vec), state.subtract(mean_quat, e_vec)) + + covariance = (1 / (n)) * covariance return covariance -def covariance_measurement(set_points: list[MeasModel], mean: np.ndarray, weights: np.ndarray = None) -> np.ndarray: +def covariance_measurement(set_points: list[MeasModel], mean: np.ndarray) -> np.ndarray: """ Function that calculates the covariance of a set of points """ n = len(set_points) co_size = len(set_points[0].measurement) covariance = np.zeros((co_size, co_size)) + mean_meas = MeasModel() mean_meas.measurement = mean - if weights is None: - for i in range(n): - temp_model = set_points[i] - mean_meas - covariance += np.outer(temp_model.measurement, temp_model.measurement) - - covariance = (1 / (n)) * covariance + for state in set_points: + temp_state = state - mean_meas + covariance += np.outer(temp_state.measurement, temp_state.measurement) - else: - for i in range(n): - temp_model = set_points[i] - mean_meas - covariance += weights[i] * np.outer(temp_model.measurement, temp_model.measurement) + covariance = (1 / n) * covariance return covariance -def cross_covariance(set_y: list[StateQuat], mean_y: np.ndarray, set_z: list[MeasModel], mean_z: np.ndarray, weights: np.ndarray) -> np.ndarray: +def cross_covariance(set_y: list[StateQuat], mean_y: np.ndarray, set_z: list[MeasModel], mean_z: np.ndarray) -> np.ndarray: """ Calculates the cross covariance between the measurement and state prediction """ + n = len(set_y) - n = len(mean_y) - 1 - m = len(mean_z) - cross_covariance = np.zeros((n,m)) + cross_covariance = np.zeros((len(mean_y) - 1, len(mean_z))) mean_quat = StateQuat() mean_quat.fill_states(mean_y) + mean_q = mean_quat.orientation + for i in range(n): - cross_covariance += np.outer(set_y[i].subtract(mean_quat), set_z[i].measurement - mean_z) + q = set_y[i].orientation + diff_q = quaternion_error(q, mean_q) + + e0_clipped = np.clip(diff_q[0], -1.0, 1.0) + angle = 2.0 * np.arccos(e0_clipped) + if abs(angle) < 1e-8: + e_vec = np.zeros(3) + else: + e_vec = (angle / np.sin(angle/2)) * diff_q[1:4] + + cross_covariance += np.outer(set_y[i].subtract(mean_quat, e_vec), set_z[i].measurement - mean_z) - cross_covariance = (1 / len(set_y)) * cross_covariance + cross_covariance = (1 / n) * cross_covariance return cross_covariance diff --git a/navigation/ukf_okid/ukf_python/ukf_test.py b/navigation/ukf_okid/ukf_python/ukf_test.py new file mode 100644 index 000000000..5a7e9eaba --- /dev/null +++ b/navigation/ukf_okid/ukf_python/ukf_test.py @@ -0,0 +1,323 @@ +from ukf_okid import UKF +from ukf_okid_class import StateQuat, process_model, MeasModel +import numpy as np +import time +import matplotlib.pyplot as plt +from ukf_utils import print_StateQuat_list, print_StateQuat +from ukf_okid_class import quaternion_super_product, quat_to_euler, mean_set, covariance_set + + + +def add_quaternion_noise(q, noise_std): + + noise = np.random.normal(0, noise_std, 3) + + theta = np.linalg.norm(noise) + + if theta > 0: + + axis = noise / theta + + q_noise = np.hstack((np.cos(theta/2), np.sin(theta/2) * axis)) + + else: + + q_noise = np.array([1.0, 0.0, 0.0, 0.0]) + + q_new = quaternion_super_product(q, q_noise) + + return q_new / np.linalg.norm(q_new) + + +if __name__ == '__main__': + + # Define a mean StateQuat + mean_state = StateQuat() + mean_state.position = np.array([1.0, 2.0, 3.0]) + mean_state.orientation = np.array([1.0, 0.0, 0.0, 0.0]) # Quaternion + mean_state.velocity = np.array([0.5, 0.5, 0.5]) + mean_state.angular_velocity = np.array([0.1, 0.1, 0.1]) + + test_state = StateQuat() + test_state.position = np.array([1.0, 1.0, 1.0]) + test_state.orientation = np.array([0.0, 1.0, 0.0, 0.0]) # Quaternion + test_state.velocity = np.array([0.2, 0.2, 0.2]) + test_state.angular_velocity = np.array([0.2, 0.2, 0.2]) + + # Create a set with only one element + state_set = list() + state_set.append(test_state) + print(len(state_set)) + + # Compute the mean + mean = mean_set(state_set) + + # Compute the covariance + mean_state.covariance = covariance_set(state_set, mean_state) + + # Print the results + print("Mean State:") + print_StateQuat(mean_state) + + # # Create initial state vector and covariance matrix. + # x0 = np.zeros(13) + # x0[0:3] = [0.3, 0.3, 0.3] + # x0[3] = 1 + # x0[7:10] = [0.2, 0.2, 0.2] + # dt = 0.01 + # R = (0.01) * np.eye(3) + + # Q = 0.00015 * np.eye(12) + # P0 = np.eye(12) * 0.0001 + + # model = process_model() + # model.dt = 0.01 + # model.mass_interia_matrix = np.array([ + # [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + # [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + # [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + # [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + # [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + # [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] + # ]) + # model.m = 30.0 + # model.r_b_bg = np.array([0.01, 0.0, 0.02]) + # model.inertia = np.diag([0.68, 3.32, 3.34]) + # model.damping_linear = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) + # model.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) + # model.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) + + # model_ukf = process_model() + # model_ukf.dt = 0.01 + # model_ukf.mass_interia_matrix = np.array([ + # [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + # [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + # [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + # [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + # [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + # [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] + # ]) + # model_ukf.m = 30.0 + # model_ukf.r_b_bg = np.array([0.01, 0.0, 0.02]) + # model_ukf.inertia = np.diag([0.68, 3.32, 3.34]) + # model_ukf.damping_linear = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) + # model_ukf.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) + # model_ukf.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) + + # # Simulation parameters + # simulation_time = 20 # seconds + # num_steps = int(simulation_time / dt) + + # # Initialize a dummy StateQuat. + # new_state = StateQuat() + # new_state.fill_states(x0) + # new_state.covariance = P0 + + # test_state_x = StateQuat() + # test_state_x.fill_states(x0) + # test_state_x.covariance = P0 + + # # Initialize a estimated state + # estimated_state = StateQuat() + # estimated_state.fill_states(x0) + # estimated_state.covariance = P0 + + # # Initialize a estimated state + # noisy_state = StateQuat() + # noisy_state.fill_states(x0) + # noisy_state.covariance = P0 + + # measurment_model = MeasModel() + # measurment_model.measurement = np.array([0.0, 0.0, 0.0]) + # measurment_model.covariance = R + + # # Initialize arrays to store the results + # positions = np.zeros((num_steps, 3)) + # orientations = np.zeros((num_steps, 3)) + # velocities = np.zeros((num_steps, 3)) + # angular_velocities = np.zeros((num_steps, 3)) + + # # Initialize arrays to store the estimates + # positions_est = np.zeros((num_steps, 3)) + # orientations_est = np.zeros((num_steps, 3)) + # velocities_est = np.zeros((num_steps, 3)) + # angular_velocities_est = np.zeros((num_steps, 3)) + + # # Initialize the okid params + # okid_params = np.zeros((num_steps, 21)) + + # model.state_vector_prev = new_state + # model.state_vector = new_state + + # model_ukf.state_vector_prev = test_state_x + # model_ukf.state_vector = test_state_x + + # # initialize the ukf + # ukf = UKF(model_ukf, x0, P0, Q, R) + + # elapsed_times = [] + + # u = lambda t: np.array([2 * np.sin(1 * t), 2 * np.sin(1 * t), 2 * np.sin(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t)]) + + # # Run the simulation + # for step in range(num_steps): + # # Insert control input + # model.Control_input = u(step * dt) + # model_ukf.Control_input = u(step * dt) + + # # Perform the unscented transform + # model.model_prediction(new_state) + # new_state = model.euler_forward() + + # # Adding noise in the state vector + # estimated_state.position = estimated_state.position # + np.random.normal(0, 0.01, 3) + # estimated_state.orientation = estimated_state.orientation #add_quaternion_noise(estimated_state.orientation, 0.01) + # estimated_state.velocity = estimated_state.velocity # + np.random.normal(0, 0.01, 3) + # estimated_state.angular_velocity = estimated_state.angular_velocity # + np.random.normal(0, 0.01, 3) + + # start_time = time.time() + # estimated_state = ukf.unscented_transform(estimated_state) + # elapsed_time = time.time() - start_time + # elapsed_times.append(elapsed_time) + + # if step % 10 == 0: + # measurment_model.measurement = new_state.velocity # + np.random.normal(0, 0.01, 3) + # meas_update, covariance_matrix = ukf.measurement_update(estimated_state, measurment_model) + # estimated_state = ukf.posteriori_estimate(estimated_state, covariance_matrix, measurment_model, meas_update) + + + # positions[step, :] = new_state.position + # orientations[step, :] = quat_to_euler(new_state.orientation) + # velocities[step, :] = new_state.velocity + # angular_velocities[step, :] = new_state.angular_velocity + + # positions_est[step, :] = estimated_state.position + # orientations_est[step, :] = quat_to_euler(estimated_state.orientation) + # velocities_est[step, :] = estimated_state.velocity + # angular_velocities_est[step, :] = estimated_state.angular_velocity + + # # Update the state for the next iteration + # model.state_vector_prev = new_state + + # print('Average elapsed time: ', np.mean(elapsed_times)) + # print('Max elapsed time: ', np.max(elapsed_times)) + # print('Min elapsed time: ', np.min(elapsed_times)) + # print('median elapsed time: ', np.median(elapsed_times)) + # # Plot the results + # time = np.linspace(0, simulation_time, num_steps) + + # # Plot positions + # plt.figure() + # plt.subplot(3, 1, 1) + # plt.plot(time, positions[:, 0], label='True') + # plt.plot(time, positions_est[:, 0], label='Estimated') + # plt.title('Position X') + # plt.xlabel('Time [s]') + # plt.ylabel('Position X [m]') + # plt.legend() + + # plt.subplot(3, 1, 2) + # plt.plot(time, positions[:, 1], label='True') + # plt.plot(time, positions_est[:, 1], label='Estimated') + # plt.title('Position Y') + # plt.xlabel('Time [s]') + # plt.ylabel('Position Y [m]') + # plt.legend() + + # plt.subplot(3, 1, 3) + # plt.plot(time, positions[:, 2], label='True') + # plt.plot(time, positions_est[:, 2], label='Estimated') + # plt.title('Position Z') + # plt.xlabel('Time [s]') + # plt.ylabel('Position Z [m]') + # plt.legend() + + # plt.tight_layout() + # plt.show() + + # # Plot orientations (Euler angles) + # plt.figure() + # plt.subplot(3, 1, 1) + # plt.plot(time, orientations[:, 0], label='True') + # plt.plot(time, orientations_est[:, 0], label='Estimated') + # plt.title('Orientation Roll') + # plt.xlabel('Time [s]') + # plt.ylabel('Roll [rad]') + # plt.legend() + + # plt.subplot(3, 1, 2) + # plt.plot(time, orientations[:, 1], label='True') + # plt.plot(time, orientations_est[:, 1], label='Estimated') + # plt.title('Orientation Pitch') + # plt.xlabel('Time [s]') + # plt.ylabel('Pitch [rad]') + # plt.legend() + + # plt.subplot(3, 1, 3) + # plt.plot(time, orientations[:, 2], label='True') + # plt.plot(time, orientations_est[:, 2], label='Estimated') + # plt.title('Orientation Yaw') + # plt.xlabel('Time [s]') + # plt.ylabel('Yaw [rad]') + # plt.legend() + + # plt.tight_layout() + # plt.show() + + # # Plot velocities + # plt.figure() + # plt.subplot(3, 1, 1) + # plt.plot(time, velocities[:, 0], label='True') + # plt.plot(time, velocities_est[:, 0], label='Estimated') + # plt.title('Velocity X') + # plt.xlabel('Time [s]') + # plt.ylabel('Velocity X [m/s]') + # plt.legend() + + # plt.subplot(3, 1, 2) + # plt.plot(time, velocities[:, 1], label='True') + # plt.plot(time, velocities_est[:, 1], label='Estimated') + # plt.title('Velocity Y') + # plt.xlabel('Time [s]') + # plt.ylabel('Velocity Y [m/s]') + # plt.legend() + + # plt.subplot(3, 1, 3) + # plt.plot(time, velocities[:, 2], label='True') + # plt.plot(time, velocities_est[:, 2], label='Estimated') + # plt.title('Velocity Z') + # plt.xlabel('Time [s]') + # plt.ylabel('Velocity Z [m/s]') + # plt.legend() + + # plt.tight_layout() + # plt.show() + + # # Plot angular velocities + # plt.figure() + # plt.subplot(3, 1, 1) + # plt.plot(time, angular_velocities[:, 0], label='True') + # plt.plot(time, angular_velocities_est[:, 0], label='Estimated') + # plt.title('Angular Velocity X') + # plt.xlabel('Time [s]') + # plt.ylabel('Angular Velocity X [rad/s]') + # plt.legend() + + # plt.subplot(3, 1, 2) + # plt.plot(time, angular_velocities[:, 1], label='True') + # plt.plot(time, angular_velocities_est[:, 1], label='Estimated') + # plt.title('Angular Velocity Y') + # plt.xlabel('Time [s]') + # plt.ylabel('Angular Velocity Y [rad/s]') + # plt.legend() + + # plt.subplot(3, 1, 3) + # plt.plot(time, angular_velocities[:, 2], label='True') + # plt.plot(time, angular_velocities_est[:, 2], label='Estimated') + # plt.title('Angular Velocity Z') + # plt.xlabel('Time [s]') + # plt.ylabel('Angular Velocity Z [rad/s]') + # plt.legend() + + # plt.tight_layout() + # plt.show() \ No newline at end of file diff --git a/navigation/ukf_okid/ukf_python/ukf_utils.py b/navigation/ukf_okid/ukf_python/ukf_utils.py index f52f2eb62..ad5871567 100644 --- a/navigation/ukf_okid/ukf_python/ukf_utils.py +++ b/navigation/ukf_okid/ukf_python/ukf_utils.py @@ -20,7 +20,7 @@ def print_StateQuat(state: StateQuat, name="StateQuat", print_covariance=True): print(f" Orientation: {state.orientation}") print(f" Velocity: {state.velocity}") print(f" Angular Velocity: {state.angular_velocity}") - print(f" okid_params: {state.okid_params}") + # print(f" okid_params: {state.okid_params}") if print_covariance: print_matrix(state.covariance, "Covariance") From 1e02ea23e98cec18a8f6f81b3e970d1162a21261 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Fri, 28 Mar 2025 21:41:33 +0100 Subject: [PATCH 10/30] feat: Added ESKF in cpp using .hpp and .cpp, current implementation uses msg imu/data_raw and /orca/pose as the dvl info --- navigation/eskf/CMakeLists.txt | 53 ++++ navigation/eskf/config/eskf_params.yaml | 5 + navigation/eskf/include/eskf/eskf.hpp | 92 +++++++ navigation/eskf/include/eskf/eskf_ros.hpp | 69 +++++ navigation/eskf/include/eskf/eskf_utils.hpp | 11 + navigation/eskf/include/eskf/typedefs.hpp | 100 +++++++ navigation/eskf/launch/eskf.launch.py | 22 ++ navigation/eskf/package.xml | 22 ++ navigation/eskf/src/eskf.cpp | 240 ++++++++++++++++ navigation/eskf/src/eskf_node.cpp | 9 + navigation/eskf/src/eskf_ros.cpp | 118 ++++++++ navigation/eskf/src/eskf_utils.cpp | 13 + .../eskf_python/eskf_python_filter.py | 193 +++++++------ .../eskf_python/eskf_python/eskf_test.py | 257 +++++++++++++----- navigation/ukf_okid/ukf_python/ukf_okid.py | 22 +- 15 files changed, 1067 insertions(+), 159 deletions(-) create mode 100644 navigation/eskf/CMakeLists.txt create mode 100644 navigation/eskf/config/eskf_params.yaml create mode 100644 navigation/eskf/include/eskf/eskf.hpp create mode 100644 navigation/eskf/include/eskf/eskf_ros.hpp create mode 100644 navigation/eskf/include/eskf/eskf_utils.hpp create mode 100644 navigation/eskf/include/eskf/typedefs.hpp create mode 100644 navigation/eskf/launch/eskf.launch.py create mode 100644 navigation/eskf/package.xml create mode 100644 navigation/eskf/src/eskf.cpp create mode 100644 navigation/eskf/src/eskf_node.cpp create mode 100644 navigation/eskf/src/eskf_ros.cpp create mode 100644 navigation/eskf/src/eskf_utils.cpp diff --git a/navigation/eskf/CMakeLists.txt b/navigation/eskf/CMakeLists.txt new file mode 100644 index 000000000..2809f9ed9 --- /dev/null +++ b/navigation/eskf/CMakeLists.txt @@ -0,0 +1,53 @@ +cmake_minimum_required(VERSION 3.8) +project(eskf) + +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(Eigen3 REQUIRED) +find_package(tf2 REQUIRED) +find_package(vortex_msgs REQUIRED) + +if(NOT DEFINED EIGEN3_INCLUDE_DIR) + set(EIGEN3_INCLUDE_DIR ${EIGEN3_INCLUDE_DIRS}) +endif() +include_directories(${EIGEN3_INCLUDE_DIR}) + +include_directories(include) + +add_executable(eskf_node + src/eskf.cpp + src/eskf_ros.cpp + src/eskf_node.cpp + src/eskf_utils.cpp +) + +ament_target_dependencies(eskf_node + rclcpp + geometry_msgs + nav_msgs + Eigen3 + tf2 + vortex_msgs +) + +install(TARGETS + eskf_node + DESTINATION lib/${PROJECT_NAME}) + +install(DIRECTORY + config + launch + DESTINATION share/${PROJECT_NAME}/ +) + +ament_package() diff --git a/navigation/eskf/config/eskf_params.yaml b/navigation/eskf/config/eskf_params.yaml new file mode 100644 index 000000000..f3402f4a9 --- /dev/null +++ b/navigation/eskf/config/eskf_params.yaml @@ -0,0 +1,5 @@ +eskf_node: + ros__parameters: + imu_topic: imu/date_raw + dvl_twist: /orca/twist + odom_topic: odom diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp new file mode 100644 index 000000000..ee47277ea --- /dev/null +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -0,0 +1,92 @@ +#ifndef ESKF_HPP +#define ESKF_HPP + +#include +#include +#include "eskf/typedefs.hpp" +#include "typedefs.hpp" + +class ESKF { + public: + ESKF(const eskf_params& params); + + std::pair imu_update( + const state_quat& nom_state, + const state_euler& error_state, + const imu_measurement& imu_meas, + const double dt); + + std::pair dvl_update( + const state_quat& nom_state, + const state_euler& error_state, + const dvl_measurement& dvl_meas); + + private: + // @brief Predict the nominal state + // @param nom_state: Nominal state + // @param imu_meas: IMU measurement + // @return Predicted nominal state + state_quat nominal_state_discrete(const state_quat& nom_state, + const imu_measurement& imu_meas, + const double dt); + + // @brief Predict the error state + // @param error_state: Error state + // @param nom_state: Nominal state + // @param imu_meas: IMU measurement + // @return Predicted error state + state_euler error_state_prediction(const state_euler& error_state, + const state_quat& nom_state, + const imu_measurement& imu_meas, + const double dt); + + // @brief Update the error state + // @param error_state: Error state + // @param dvl_meas: DVL measurement + // @return Updated error state + state_euler measurement_update(const state_quat& nom_state, + const state_euler& error_state, + const dvl_measurement& dvl_meas); + + // @brief Inject the error state into the nominal state and reset the error + // state + // @param nom_state: Nominal state + // @param error_state: Error state + // @return Injected and reset state + std::pair injection_and_reset( + const state_quat& nom_state, + const state_euler& error_state); + + // @brief Van Loan discretization + // @param A_c: Continuous state transition matrix + // @param G_c: Continuous input matrix + // @return Discrete state transition matrix and discrete input matrix + std::pair van_loan_discretization( + const Eigen::Matrix18d& A_c, + const Eigen::Matrix18x12d& G_c, + const double dt); + + // @brief Calculate the delta quaternion matrix + // @param nom_state: Nominal state + // @return Delta quaternion matrix + Eigen::Matrix4x3d calculate_Q_delta(const state_quat& nom_state); + + // @brief Calculate the measurement matrix jakobian + // @param nom_state: Nominal state + // @return Measurement matrix + Eigen::Matrix3x19d calculate_Hx(const state_quat& nom_state); + + // @brief Calculate the full measurement matrix + // @param nom_state: Nominal state + // @return Measurement matrix + Eigen::Matrix3x18d calculate_H(const state_quat& nom_state); + + // @brief Calculate the measurement + // @param nom_state: Nominal state + // @return Measurement + Eigen::Vector3d calculate_h(const state_quat& nom_state); + + Eigen::Matrix12d Q_; +}; + +#endif // ESKF_HPP diff --git a/navigation/eskf/include/eskf/eskf_ros.hpp b/navigation/eskf/include/eskf/eskf_ros.hpp new file mode 100644 index 000000000..88f97459f --- /dev/null +++ b/navigation/eskf/include/eskf/eskf_ros.hpp @@ -0,0 +1,69 @@ +#ifndef ESKF_ROS_HPP +#define ESKF_ROS_HPP + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "eskf/eskf.hpp" +#include "eskf/typedefs.hpp" +#include "typedefs.hpp" + +class ESKFNode : public rclcpp::Node { + public: + explicit ESKFNode(); + + private: + // @brief Callback function for the imu topic + // @param msg: Imu message containing the imu data + void imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg); + + // @brief Callback function for the dvl topic + // @param msg: TwistWithCovarianceStamped message containing the dvl data + void dvl_callback( + const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); + + // @brief Publish the odometry message + void publish_odom(); + + // @brief Set the subscriber and publisher for the node + void set_subscribers_and_publisher(); + + // @brief Set the parameters for the eskf + void set_parameters(); + + rclcpp::Subscription::SharedPtr imu_sub_; + + rclcpp::Subscription< + geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr dvl_sub_; + + rclcpp::Publisher::SharedPtr odom_pub_; + + std::chrono::milliseconds time_step; + + rclcpp::TimerBase::SharedPtr odom_pub_timer_; + + state_quat nom_state_; + + state_euler error_state_; + + imu_measurement imu_meas_; + + dvl_measurement dvl_meas_; + + eskf_params eskf_params_; + + std::unique_ptr eskf_; + + rclcpp::Time last_imu_time_; + + bool first_imu_msg_received_ = false; +}; + +#endif // ESKF_ROS_HPP diff --git a/navigation/eskf/include/eskf/eskf_utils.hpp b/navigation/eskf/include/eskf/eskf_utils.hpp new file mode 100644 index 000000000..afd871772 --- /dev/null +++ b/navigation/eskf/include/eskf/eskf_utils.hpp @@ -0,0 +1,11 @@ +#ifndef ESKF_UTILS_HPP +#define ESKF_UTILS_HPP + +#include "eigen3/Eigen/Dense" +#include "eskf/typedefs.hpp" + +Eigen::Matrix3d skew(const Eigen::Vector3d& v); + +double sq(const double& value); + +#endif // ESKF_UTILS_HPP diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp new file mode 100644 index 000000000..c93c92402 --- /dev/null +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -0,0 +1,100 @@ +/** + * @file typedefs.hpp + * @brief Contains the typedef and structs for the eskf. + */ +#ifndef ESKF_TYPEDEFS_H +#define ESKF_TYPEDEFS_H + +#include +#include + +namespace Eigen { +typedef Eigen::Matrix Vector19d; +typedef Eigen::Matrix Vector18d; +typedef Eigen::Matrix Matrix18d; +typedef Eigen::Matrix Matrix19d; +typedef Eigen::Matrix Matrix18x12d; +typedef Eigen::Matrix Matrix4x3d; +typedef Eigen::Matrix Matrix3x19d; +typedef Eigen::Matrix Matrix3x18d; +typedef Eigen::Matrix Matrix12d; +typedef Eigen::Matrix Matrix18d; +typedef Eigen::Matrix Matrix3x1d; +typedef Eigen::Matrix Matrix19x18d; +typedef Eigen::Matrix Matrix18x3d; +typedef Eigen::Matrix Matrix36d; +typedef Eigen::Matrix Matrix6d; +typedef Eigen::Matrix Matrix9d; +} // namespace Eigen + +struct state_quat { + Eigen::Vector3d pos = Eigen::Vector3d::Zero(); + Eigen::Vector3d vel = Eigen::Vector3d::Zero(); + Eigen::Quaterniond quat = Eigen::Quaterniond::Identity(); + Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero(); + Eigen::Vector3d accel_bias = Eigen::Vector3d::Zero(); + Eigen::Vector3d gravity = Eigen::Vector3d(0, 0, 9.81); + + Eigen::Vector19d as_vector() const { + Eigen::Vector19d vec; + vec << pos, vel, quat.w(), quat.x(), quat.y(), quat.z(), gyro_bias, + accel_bias; + return vec; + } + + state_quat operator-(const state_quat& other) const { + state_quat diff; + diff.pos = pos - other.pos; + diff.vel = vel - other.vel; + diff.quat = quat * other.quat.inverse(); + diff.gyro_bias = gyro_bias - other.gyro_bias; + diff.accel_bias = accel_bias - other.accel_bias; + return diff; + } + + Eigen::Matrix3d get_R() const { return quat.toRotationMatrix(); } +}; + +struct state_euler { + Eigen::Vector3d pos = Eigen::Vector3d::Zero(); + Eigen::Vector3d vel = Eigen::Vector3d::Zero(); + Eigen::Vector3d euler = Eigen::Vector3d::Zero(); + Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero(); + Eigen::Vector3d accel_bias = Eigen::Vector3d::Zero(); + Eigen::Vector3d gravity = Eigen::Vector3d(0, 0, 9.81); + + Eigen::Matrix18d covariance = Eigen::Matrix18d::Zero(); + + Eigen::Vector18d as_vector() const { + Eigen::Vector18d vec; + vec << pos, vel, euler, gyro_bias, accel_bias, gravity; + return vec; + } + + void set_from_vector(const Eigen::Vector18d& vec) { + pos = vec.block<3, 1>(0, 0); + vel = vec.block<3, 1>(3, 0); + euler = vec.block<3, 1>(6, 0); + gyro_bias = vec.block<3, 1>(9, 0); + accel_bias = vec.block<3, 1>(12, 0); + gravity = vec.block<3, 1>(15, 0); + } +}; + +struct imu_measurement { + Eigen::Vector3d accel = Eigen::Vector3d::Zero(); + Eigen::Vector3d gyro = Eigen::Vector3d::Zero(); +}; + +struct dvl_measurement { + Eigen::Vector3d vel = Eigen::Vector3d::Zero(); + Eigen::Matrix3d cov = Eigen::Matrix3d::Zero(); +}; + +struct eskf_params { + double temp = 0.0; + Eigen::Matrix12d Q = Eigen::Matrix12d::Zero(); + double dt = 0.0; +}; + +#endif // ESKF_TYPEDEFS_H diff --git a/navigation/eskf/launch/eskf.launch.py b/navigation/eskf/launch/eskf.launch.py new file mode 100644 index 000000000..84284f804 --- /dev/null +++ b/navigation/eskf/launch/eskf.launch.py @@ -0,0 +1,22 @@ +from os import path + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch_ros.actions import Node + +eskf_params = path.join( + get_package_share_directory("eskf"), "config", "eskf_params.yaml" +) + + +def generate_launch_description(): + eskf_node = Node( + package="eskf", + executable="eskf_node", + name="eskf_node", + parameters=[ + eskf_params, + ], + output="screen", + ) + return LaunchDescription([eskf_node]) diff --git a/navigation/eskf/package.xml b/navigation/eskf/package.xml new file mode 100644 index 000000000..d3d8dc416 --- /dev/null +++ b/navigation/eskf/package.xml @@ -0,0 +1,22 @@ + + + + eskf + 1.0.0 + Error-state Kalman filter + talhanc + MIT + + ament_cmake + + rclcpp + geometry_msgs + nav_msgs + eigen + tf2 + vortex_msgs + + + ament_cmake + + diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp new file mode 100644 index 000000000..8218bf8d0 --- /dev/null +++ b/navigation/eskf/src/eskf.cpp @@ -0,0 +1,240 @@ +#include "eskf/eskf.hpp" +#include +#include +#include +#include +#include "eskf/eskf_utils.hpp" +#include "eskf/typedefs.hpp" + +ESKF::ESKF(const eskf_params& params) : Q_(params.Q) {} + +std::pair ESKF::van_loan_discretization( + const Eigen::Matrix18d& A_c, + const Eigen::Matrix18x12d& G_c, + const double dt) { + Eigen::Matrix18d GQG_T = G_c * Q_ * G_c.transpose(); + Eigen::Matrix36d vanLoanMat = Eigen::Matrix36d::Zero(); + + vanLoanMat.topLeftCorner<18, 18>() = -A_c; + vanLoanMat.topRightCorner<18, 18>() = GQG_T; + vanLoanMat.bottomRightCorner<18, 18>() = A_c.transpose(); + + Eigen::Matrix36d vanLoanExp = (vanLoanMat * dt).exp(); + + Eigen::Matrix18d V1 = vanLoanExp.bottomRightCorner<18, 18>().transpose(); + Eigen::Matrix18d V2 = vanLoanExp.topRightCorner<18, 18>(); + + Eigen::Matrix18d A_d = V1; + Eigen::Matrix18d GQG_d = A_d * V2; + + return {A_d, GQG_d}; +} + +Eigen::Matrix4x3d ESKF::calculate_Q_delta(const state_quat& nom_state) { + Eigen::Matrix4x3d Q_delta_theta = Eigen::Matrix4x3d::Zero(); + double qw = nom_state.quat.w(); + double qx = nom_state.quat.x(); + double qy = nom_state.quat.y(); + double qz = nom_state.quat.z(); + + Q_delta_theta << -qx, -qy, -qz, qw, -qz, qy, qz, qw, -qx, -qy, qx, qw; + + Q_delta_theta *= 0.5; + return Q_delta_theta; +} + +Eigen::Matrix3x19d ESKF::calculate_Hx(const state_quat& nom_state) { + Eigen::Matrix3x19d Hx = Eigen::Matrix3x19d::Zero(); + + Eigen::Matrix3d R_bn = + nom_state.quat.normalized().toRotationMatrix().transpose(); + + // normal measurement of the velocity + Hx.block<3, 3>(0, 3) = R_bn; + + Eigen::Vector3d v_n = nom_state.vel; + + Eigen::Matrix dR_dq; + Eigen::Quaterniond q = nom_state.quat.normalized(); + double qw = q.w(); + double qx = q.x(); + double qy = q.y(); + double qz = q.z(); + + dR_dq.col(0) = + 2 * Eigen::Vector3d(qw * v_n.x() - qz * v_n.y() + qy * v_n.z(), + qz * v_n.x() + qw * v_n.y() - qx * v_n.z(), + -qy * v_n.x() + qx * v_n.y() + qw * v_n.z()); + + dR_dq.col(1) = + 2 * Eigen::Vector3d(qx * v_n.x() + qy * v_n.y() + qz * v_n.z(), + qy * v_n.x() - qx * v_n.y() - qw * v_n.z(), + qz * v_n.x() + qw * v_n.y() - qx * v_n.z()); + + dR_dq.col(2) = + 2 * Eigen::Vector3d(-qy * v_n.x() + qx * v_n.y() + qw * v_n.z(), + qx * v_n.x() + qy * v_n.y() + qz * v_n.z(), + -qw * v_n.x() + qz * v_n.y() - qy * v_n.z()); + + dR_dq.col(3) = + 2 * Eigen::Vector3d(-qz * v_n.x() - qw * v_n.y() + qx * v_n.z(), + qw * v_n.x() - qz * v_n.y() + qy * v_n.z(), + qx * v_n.x() + qy * v_n.y() + qz * v_n.z()); + + Hx.block<3, 4>(0, 6) = dR_dq; + + return Hx; +} + +Eigen::Matrix3x18d ESKF::calculate_H(const state_quat& nom_state) { + Eigen::Matrix19x18d X_delta = Eigen::Matrix19x18d::Zero(); + X_delta.block<6, 6>(0, 0) = Eigen::Matrix6d::Identity(); + X_delta.block<4, 3>(6, 6) = calculate_Q_delta(nom_state); + X_delta.block<9, 9>(10, 9) = Eigen::Matrix9d::Identity(); + + Eigen::Matrix3x18d H = calculate_Hx(nom_state) * X_delta; + return H; +} + +Eigen::Matrix3x1d ESKF::calculate_h(const state_quat& nom_state) { + Eigen::Matrix3x1d h; + Eigen::Matrix3d R_bn = + nom_state.quat.normalized().toRotationMatrix().transpose(); + + h = R_bn * nom_state.vel; + + return h; +} + +state_quat ESKF::nominal_state_discrete(const state_quat& nom_state, + const imu_measurement& imu_meas, + const double dt) { + Eigen::Vector3d acc = + nom_state.get_R() * (imu_meas.accel - nom_state.accel_bias) + + nom_state.gravity; + Eigen::Vector3d gyro = (imu_meas.gyro - nom_state.gyro_bias) * dt; + + state_quat next_nom_state; + next_nom_state.pos = + nom_state.pos + nom_state.vel * dt + 0.5 * sq(dt) * acc; + next_nom_state.vel = nom_state.vel + dt * acc; + next_nom_state.quat = + (nom_state.quat * + Eigen::Quaterniond(0, 0.5 * gyro.x(), 0.5 * gyro.y(), 0.5 * gyro.z())); + next_nom_state.quat.normalize(); + next_nom_state.gyro_bias = nom_state.gyro_bias; + next_nom_state.accel_bias = nom_state.accel_bias; + next_nom_state.gravity = nom_state.gravity; + + return next_nom_state; +} + +state_euler ESKF::error_state_prediction(const state_euler& error_state, + const state_quat& nom_state, + const imu_measurement& imu_meas, + const double dt) { + Eigen::Matrix3d R = nom_state.get_R(); + Eigen::Vector3d acc = (imu_meas.accel - nom_state.accel_bias); + Eigen::Vector3d gyro = imu_meas.gyro - nom_state.gyro_bias; + + Eigen::Matrix18d A_c = Eigen::Matrix18d::Zero(); + A_c.block<3, 3>(0, 3) = Eigen::Matrix3d::Identity(); + A_c.block<3, 3>(3, 6) = -R * skew(acc); + A_c.block<3, 3>(6, 6) = -skew(gyro); + A_c.block<3, 3>(3, 9) = -R; + A_c.block<3, 3>(9, 9) = -Eigen::Matrix3d::Identity(); + A_c.block<3, 3>(12, 12) = -Eigen::Matrix3d::Identity(); + A_c.block<3, 3>(6, 12) = -Eigen::Matrix3d::Identity(); + A_c.block<3, 3>(3, 15) = Eigen::Matrix3d::Identity(); + + Eigen::Matrix18x12d G_c = Eigen::Matrix18x12d::Zero(); + G_c.block<3, 3>(3, 0) = -R; + G_c.block<3, 3>(6, 3) = -Eigen::Matrix3d::Identity(); + G_c.block<3, 3>(9, 6) = Eigen::Matrix3d::Identity(); + G_c.block<3, 3>(12, 9) = Eigen::Matrix3d::Identity(); + + auto [A_d, GQG_d] = van_loan_discretization(A_c, G_c, dt); + + state_euler next_error_state; + next_error_state.covariance = + A_d * error_state.covariance * A_d.transpose() + GQG_d; + + return next_error_state; +} + +state_euler ESKF::measurement_update(const state_quat& nom_state, + const state_euler& error_state, + const dvl_measurement& dvl_meas) { + state_euler new_error_state; + + Eigen::Matrix3x18d H = calculate_H(nom_state); + Eigen::Matrix18d P = error_state.covariance; + Eigen::Matrix3d R = dvl_meas.cov; + + Eigen::Matrix3d S = H * P * H.transpose() + R; + Eigen::Matrix18x3d K = P * H.transpose() * S.inverse(); + Eigen::Vector3d innovation = dvl_meas.vel - calculate_h(nom_state); + new_error_state.set_from_vector(K * innovation); + + Eigen::Matrix18d I_KH = Eigen::Matrix18d::Identity() - K * H; + new_error_state.covariance = + I_KH * P * I_KH.transpose() + + K * R * K.transpose(); // Used joseph form for more stable calculations + + return new_error_state; +} + +std::pair ESKF::injection_and_reset( + const state_quat& nom_state, + const state_euler& error_state) { + state_quat next_nom_state; + + next_nom_state.pos = nom_state.pos + error_state.pos; + next_nom_state.vel = nom_state.vel + error_state.vel; + next_nom_state.quat = + nom_state.quat * Eigen::Quaterniond(1, 0.5 * error_state.euler.x(), + 0.5 * error_state.euler.y(), + 0.5 * error_state.euler.z()); + next_nom_state.quat.normalize(); + next_nom_state.gyro_bias = nom_state.gyro_bias + error_state.gyro_bias; + next_nom_state.accel_bias = nom_state.accel_bias + error_state.accel_bias; + next_nom_state.gravity = nom_state.gravity + error_state.gravity; + + state_euler new_error_state; + + Eigen::Matrix18d G = Eigen::Matrix18d::Identity(); + + new_error_state.covariance = G * error_state.covariance * G.transpose(); + new_error_state.pos = Eigen::Vector3d::Zero(); + new_error_state.vel = Eigen::Vector3d::Zero(); + new_error_state.euler = Eigen::Vector3d::Zero(); + new_error_state.gyro_bias = Eigen::Vector3d::Zero(); + new_error_state.accel_bias = Eigen::Vector3d::Zero(); + new_error_state.gravity = Eigen::Vector3d::Zero(); + + return {next_nom_state, new_error_state}; +} + +std::pair ESKF::imu_update( + const state_quat& nom_state, + const state_euler& error_state, + const imu_measurement& imu_meas, + const double dt) { + state_quat next_nom_state = nominal_state_discrete(nom_state, imu_meas, dt); + state_euler next_error_state = + error_state_prediction(error_state, nom_state, imu_meas, dt); + + return {next_nom_state, next_error_state}; +} + +std::pair ESKF::dvl_update( + const state_quat& nom_state, + const state_euler& error_state, + const dvl_measurement& dvl_meas) { + state_euler new_error_state = + measurement_update(nom_state, error_state, dvl_meas); + auto [updated_nom_state, updated_error_state] = + injection_and_reset(nom_state, new_error_state); + + return {updated_nom_state, updated_error_state}; +} diff --git a/navigation/eskf/src/eskf_node.cpp b/navigation/eskf/src/eskf_node.cpp new file mode 100644 index 000000000..e90cebde3 --- /dev/null +++ b/navigation/eskf/src/eskf_node.cpp @@ -0,0 +1,9 @@ +#include "eskf/eskf_ros.hpp" + +int main(int argc, char** argv) { + rclcpp::init(argc, argv); + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Started ESKF Node"); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp new file mode 100644 index 000000000..a3b9c5cf3 --- /dev/null +++ b/navigation/eskf/src/eskf_ros.cpp @@ -0,0 +1,118 @@ +#include "eskf/eskf_ros.hpp" +#include +#include +#include "eskf/eskf_utils.hpp" +#include "eskf/typedefs.hpp" + +ESKFNode::ESKFNode() : Node("eskf_node") { + time_step = std::chrono::milliseconds(1); + odom_pub_timer_ = this->create_wall_timer( + time_step, std::bind(&ESKFNode::publish_odom, this)); + + set_subscribers_and_publisher(); + + set_parameters(); +} + +void ESKFNode::set_subscribers_and_publisher() { + rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; + auto qos_sensor_data = rclcpp::QoS( + rclcpp::QoSInitialization(qos_profile.history, 1), qos_profile); + + this->declare_parameter("imu_topic", "imu/data_raw"); + std::string imu_topic = this->get_parameter("imu_topic").as_string(); + imu_sub_ = this->create_subscription( + imu_topic, qos_sensor_data, + std::bind(&ESKFNode::imu_callback, this, std::placeholders::_1)); + + this->declare_parameter("dvl_topic", "/orca/twist"); + std::string dvl_topic = this->get_parameter("dvl_topic").as_string(); + dvl_sub_ = this->create_subscription< + geometry_msgs::msg::TwistWithCovarianceStamped>( + dvl_topic, qos_sensor_data, + std::bind(&ESKFNode::dvl_callback, this, std::placeholders::_1)); + + this->declare_parameter("odom_topic", "odom"); + std::string odom_topic = this->get_parameter("odom_topic").as_string(); + odom_pub_ = this->create_publisher( + odom_topic, qos_sensor_data); +} + +void ESKFNode::set_parameters() { + Eigen::Matrix12d Q; + Q.setZero(); + Q.diagonal() << sq(0.0103), sq(0.0118), sq(0.0043), // acceleration noise + sq(0.00193), sq(0.00306), sq(0.00118), // gyroscope noise + sq(0.05), sq(0.05), sq(0.05), // acceleration bias noise + sq(0.03), sq(0.03), sq(0.03); // gyroscope bias noise + + eskf_params_.Q = Q; + + eskf_ = std::make_unique(eskf_params_); + + Eigen::Matrix18d P; + P.setZero(); + P.diagonal() << 0.1, 0.1, 0.1, // position + 0.1, 0.1, 0.1, // velocity + 0.1, 0.1, 0.1, // euler angles + 0.01, 0.01, 0.01, // accel bias + 0.01, 0.01, 0.01, // gyro bias + 0.001, 0.001, 0.001; // gravity + + error_state_.covariance = P; +} + +void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { + rclcpp::Time current_time = msg->header.stamp; + + if (!first_imu_msg_received_) { + last_imu_time_ = current_time; + first_imu_msg_received_ = true; + return; + } + + double dt = (current_time - last_imu_time_).seconds(); + last_imu_time_ = current_time; + + imu_meas_.accel << msg->linear_acceleration.x, msg->linear_acceleration.y, + msg->linear_acceleration.z; + imu_meas_.gyro << msg->angular_velocity.x, msg->angular_velocity.y, + msg->angular_velocity.z; + + std::tie(nom_state_, error_state_) = + eskf_->imu_update(nom_state_, error_state_, imu_meas_, dt); +} + +void ESKFNode::dvl_callback( + const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { + dvl_meas_.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, + msg->twist.twist.linear.z; + dvl_meas_.cov << msg->twist.covariance[0], msg->twist.covariance[1], + msg->twist.covariance[2], msg->twist.covariance[6], + msg->twist.covariance[7], msg->twist.covariance[8], + msg->twist.covariance[12], msg->twist.covariance[13], + msg->twist.covariance[14]; + + std::tie(nom_state_, error_state_) = + eskf_->dvl_update(nom_state_, error_state_, dvl_meas_); +} + +void ESKFNode::publish_odom() { + nav_msgs::msg::Odometry odom_msg; + + odom_msg.pose.pose.position.x = nom_state_.pos.x(); + odom_msg.pose.pose.position.y = nom_state_.pos.y(); + odom_msg.pose.pose.position.z = nom_state_.pos.z(); + + odom_msg.pose.pose.orientation.w = nom_state_.quat.w(); + odom_msg.pose.pose.orientation.x = nom_state_.quat.x(); + odom_msg.pose.pose.orientation.y = nom_state_.quat.y(); + odom_msg.pose.pose.orientation.z = nom_state_.quat.z(); + + odom_msg.twist.twist.linear.x = nom_state_.vel.x(); + odom_msg.twist.twist.linear.y = nom_state_.vel.y(); + odom_msg.twist.twist.linear.z = nom_state_.vel.z(); + + odom_msg.header.stamp = this->now(); // Add timestamp to the message + odom_pub_->publish(odom_msg); +} diff --git a/navigation/eskf/src/eskf_utils.cpp b/navigation/eskf/src/eskf_utils.cpp new file mode 100644 index 000000000..4d33ec7ce --- /dev/null +++ b/navigation/eskf/src/eskf_utils.cpp @@ -0,0 +1,13 @@ + +#include "eskf/eskf_utils.hpp" +#include "eskf/typedefs.hpp" + +Eigen::Matrix3d skew(const Eigen::Vector3d& v) { + Eigen::Matrix3d S; + S << 0, -v.z(), v.y(), v.z(), 0, -v.x(), -v.y(), v.x(), 0; + return S; +} + +double sq(const double& value) { + return value * value; +} diff --git a/navigation/eskf_python/eskf_python/eskf_python_filter.py b/navigation/eskf_python/eskf_python/eskf_python_filter.py index 8c4b01963..245d7ece4 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_filter.py +++ b/navigation/eskf_python/eskf_python/eskf_python_filter.py @@ -2,16 +2,22 @@ from typing import Tuple import numpy as np -from scipy.linalg import expm -from eskf_python_class import StateEuler, StateQuat, Measurement -from eskf_python_utils import skew_matrix, quaternion_product, R_from_angle_axis, angle_axis_to_quaternion, euler_to_quat -from scipy.linalg import block_diag -from scipy.spatial.transform import Rotation as R_scipy +from eskf_python_class import Measurement, StateEuler, StateQuat +from eskf_python_utils import ( + R_from_angle_axis, + angle_axis_to_quaternion, + euler_to_quat, + quaternion_product, + skew_matrix, +) +from scipy.linalg import block_diag, expm + class ESKF: - def __init__(self, Q: np.ndarray, P0, Hx, nom_state: StateQuat, p_accBias, p_gyroBias, dt): + def __init__( + self, Q: np.ndarray, P0, nom_state: StateQuat, p_accBias, p_gyroBias, dt + ): self.Q = Q - self.Hx = Hx # Jacobian of the measurement model self.dt = dt self.nom_state = nom_state self.error_state = StateEuler() @@ -28,15 +34,20 @@ def Fx(self, imu_data: Measurement) -> np.ndarray: Returns: np.ndarray: The state transition matrix. """ - F_x = np.zeros((18, 18)) I = np.eye(3) F_x[0:3, 0:3] = I F_x[0:3, 3:6] = self.dt * I F_x[3:6, 3:6] = I - F_x[3:6, 6:9] = -self.nom_state.R_q() @ skew_matrix(imu_data.acceleration - self.nom_state.acceleration_bias) * self.dt - F_x[6:9, 6:9] = R_from_angle_axis((imu_data.angular_velocity - self.nom_state.gyro_bias) * self.dt).T + F_x[3:6, 6:9] = ( + -self.nom_state.R_q() + @ skew_matrix(imu_data.acceleration - self.nom_state.acceleration_bias) + * self.dt + ) + F_x[6:9, 6:9] = R_from_angle_axis( + (imu_data.angular_velocity - self.nom_state.gyro_bias) * self.dt + ).T F_x[3:6, 9:12] = -self.nom_state.R_q() * self.dt F_x[3:6, 15:18] = I * self.dt F_x[6:9, 12:15] = -I * self.dt @@ -45,14 +56,13 @@ def Fx(self, imu_data: Measurement) -> np.ndarray: F_x[15:18, 15:18] = I return F_x - + def Fi(self) -> np.ndarray: """Calculates the input matrix. Returns: np.ndarray: The input matrix. """ - F_i = np.zeros((18, 12)) I = np.eye(3) @@ -62,73 +72,99 @@ def Fi(self) -> np.ndarray: F_i[12:15, 9:12] = I return F_i - + def Q_delta_theta(self) -> np.ndarray: - """ - Calculates the Q_delta_theta matrix. + """Calculates the Q_delta_theta matrix. See Joan Solà. Quaternion kinematics for the error-state Kalman filter. chapter: 6.1.1 eq. 281 """ - qw, qx, qy, qz = self.nom_state.orientation - Q_delta_theta = 0.5 * np.array([ - [-qx, -qy, -qz], - [qw, -qz, qy], - [qz, qw, -qx], - [-qy, qx, qw], - ]) + Q_delta_theta = 0.5 * np.array( + [ + [-qx, -qy, -qz], + [qw, -qz, qy], + [qz, qw, -qx], + [-qy, qx, qw], + ] + ) return Q_delta_theta + def Hx(self) -> np.ndarray: + """Calculates the Jacobian of the measurement model. + + Returns: + np.ndarray: The Jacobian of the measurement model. + """ + Hx = np.zeros((3, 19)) + + q0, q1, q2, q3 = self.nom_state.orientation + e = np.array([q1, q2, q3]) + v = self.nom_state.velocity + + temp_nu = -2 * skew_matrix(e) @ v + temp_eps = 2 * (q0 * np.eye(3) + skew_matrix(e)) @ skew_matrix(v) + + Hx[0:3, 3:6] = self.nom_state.R_q() + Hx[0:3, 6:10] = np.vstack([temp_nu, temp_eps]).T + + Hx = np.zeros((3, 19)) + Hx[0:3, 3:6] = np.eye(3) + + return Hx + def H(self) -> np.ndarray: """Calculates the measurement matrix. Returns: np.ndarray: The measurement matrix. """ - X_deltax = block_diag(np.eye(6), self.Q_delta_theta(), np.eye(9)) - H = self.Hx @ X_deltax + H = self.Hx() @ X_deltax return H - + def h(self) -> np.ndarray: - """ - Calculates the measurement model. + """Calculates the measurement model. Returns: np.ndarray: The measurement model. """ - return self.nom_state.velocity + return self.nom_state.velocity # self.nom_state.R_q() @ self.nom_state.velocity def nominal_state_discrete(self, imu_data: Measurement) -> None: - """ - Calculates the next nominal state using the discrete-time process model defined in: + """Calculates the next nominal state using the discrete-time process model defined in: Joan Solà. Quaternion kinematics for the error-state Kalman filter. Chapter: 5.4.1 The nominal state kinematics - Args: + Args: imu_data (np.ndarray): The IMU data. """ - # Rectify measurements. acc_rect = imu_data.acceleration - self.nom_state.acceleration_bias gyro_rect = imu_data.angular_velocity - self.nom_state.gyro_bias R = self.nom_state.R_q() - self.nom_state.position = self.nom_state.position + self.nom_state.velocity * self.dt + 0.5 * (R @ acc_rect + self.nom_state.g) * self.dt**2 - self.nom_state.velocity = self.nom_state.velocity + (R @ acc_rect + self.nom_state.g) * self.dt - self.nom_state.orientation = quaternion_product(self.nom_state.orientation, angle_axis_to_quaternion(gyro_rect * self.dt)) - self.nom_state.acceleration_bias = np.exp(-self.p_accBias * self.dt) * self.nom_state.acceleration_bias - self.nom_state.gyro_bias = np.exp(-self.p_gyroBias * self.dt) * self.nom_state.gyro_bias + self.nom_state.position = ( + self.nom_state.position + + self.nom_state.velocity * self.dt + + 0.5 * (R @ acc_rect + self.nom_state.g) * self.dt**2 + ) + self.nom_state.velocity = ( + self.nom_state.velocity + (R @ acc_rect + self.nom_state.g) * self.dt + ) + self.nom_state.orientation = quaternion_product( + self.nom_state.orientation, angle_axis_to_quaternion(gyro_rect * self.dt) + ) + self.nom_state.acceleration_bias = self.nom_state.acceleration_bias + self.nom_state.gyro_bias = self.nom_state.gyro_bias self.nom_state.g = self.nom_state.g def van_loan_discretization(self, A_c, G_c) -> Tuple[np.ndarray, np.ndarray]: - """ - Calculates the Van Loan discretization of a continuous-time system. + """Calculates the Van Loan discretization of a continuous-time system. Args: A_c (np.ndarray): The A matrix. @@ -137,18 +173,22 @@ def van_loan_discretization(self, A_c, G_c) -> Tuple[np.ndarray, np.ndarray]: Returns: Tuple: The A_d and GQG_d matrices. """ - GQG_T = np.dot(np.dot(G_c, self.Q), G_c.T) matrix_exp = ( - np.block([[- A_c, GQG_T], [np.zeros((A_c.shape[0], A_c.shape[0])), np.transpose(A_c)]]) + np.block( + [ + [-A_c, GQG_T], + [np.zeros((A_c.shape[0], A_c.shape[0])), np.transpose(A_c)], + ] + ) * self.dt ) van_loan_matrix = expm(matrix_exp) - V1 = van_loan_matrix[A_c.shape[0]:, A_c.shape[0]:] - V2 = van_loan_matrix[:A_c.shape[0], A_c.shape[0]:] + V1 = van_loan_matrix[A_c.shape[0] :, A_c.shape[0] :] + V2 = van_loan_matrix[: A_c.shape[0], A_c.shape[0] :] A_d = V1.T GQG_d = A_d @ V2 @@ -156,7 +196,6 @@ def van_loan_discretization(self, A_c, G_c) -> Tuple[np.ndarray, np.ndarray]: return A_d, GQG_d def error_state_prediction(self, imu_data: Measurement) -> None: - # Rectify measurements. acc_rect = imu_data.acceleration - self.nom_state.acceleration_bias gyro_rect = imu_data.angular_velocity - self.nom_state.gyro_bias @@ -166,9 +205,9 @@ def error_state_prediction(self, imu_data: Measurement) -> None: A_c = np.zeros((18, 18)) A_c[0:3, 3:6] = np.eye(3) - A_c[3:6, 6:9] = - R @ skew_matrix(acc_rect) - A_c[6:9, 6:9] = - skew_matrix(gyro_rect) - A_c[3:6, 9:12] = - R + A_c[3:6, 6:9] = -R @ skew_matrix(acc_rect) + A_c[6:9, 6:9] = -skew_matrix(gyro_rect) + A_c[3:6, 9:12] = -R A_c[9:12, 9:12] = -self.p_accBias * np.eye(3) A_c[12:15, 12:15] = -self.p_gyroBias * np.eye(3) A_c[6:9, 12:15] = -np.eye(3) @@ -183,18 +222,16 @@ def error_state_prediction(self, imu_data: Measurement) -> None: A_d, GQG_d = self.van_loan_discretization(A_c, G_c) - self.error_state.covariance = (A_d @ self.error_state.covariance @ A_d.T + GQG_d) + self.error_state.covariance = A_d @ self.error_state.covariance @ A_d.T + GQG_d - def measurement_update(self, dvl_measurement:Measurement) -> float: - """ - Updates the error state using the DVL measurement. + def measurement_update(self, dvl_measurement: Measurement) -> float: + """Updates the error state using the DVL measurement. Joan Solà. Quaternion kinematics for the error-state Kalman filter. Chapter: 6.1 eq. 274-276 Args: dvl_measurement (np.ndarray): The DVL measurement. """ - H = self.H() P = self.error_state.covariance R = dvl_measurement.aiding_covariance @@ -208,49 +245,47 @@ def measurement_update(self, dvl_measurement:Measurement) -> float: self.error_state.fill_states(K @ innovation) I_KH = np.eye(18) - K @ H - self.error_state.covariance = I_KH @ P @ I_KH.T + K @ R @ K.T # Joseph form for more stability - + self.error_state.covariance = ( + I_KH @ P @ I_KH.T + K @ R @ K.T + ) # Joseph form for more stability return NIS_value def injection(self) -> None: - """ - Injects the error state into the nominal state to produce the estimated state. + """Injects the error state into the nominal state to produce the estimated state. Joan Solà. Quaternion kinematics for the error-state Kalman filter. Chapter 6.2 eq. 282-283 - + """ self.nom_state.position = self.nom_state.position + self.error_state.position self.nom_state.velocity = self.nom_state.velocity + self.error_state.velocity - self.nom_state.orientation = quaternion_product(self.nom_state.orientation, euler_to_quat(self.error_state.orientation)) - self.nom_state.acceleration_bias = self.nom_state.acceleration_bias + self.error_state.acceleration_bias + self.nom_state.orientation = quaternion_product( + self.nom_state.orientation, euler_to_quat(self.error_state.orientation) + ) + self.nom_state.acceleration_bias = ( + self.nom_state.acceleration_bias + self.error_state.acceleration_bias + ) self.nom_state.gyro_bias = self.nom_state.gyro_bias + self.error_state.gyro_bias self.nom_state.g = self.nom_state.g + self.error_state.g def reset_error_state(self) -> None: - """ - Resets the error state after injection. + """Resets the error state after injection. Joan Solà. Quaternion kinematics for the error-state Kalman filter. Chapter 6.3 eq. 284-286 """ - - G = np.eye(18) # Neglecting the delta_theta as this is most common in practice + G = np.eye(18) # Neglecting the delta_theta as this is most common in practice self.error_state.covariance = G @ self.error_state.covariance @ G.T self.error_state.fill_states(np.zeros(18)) def imu_update(self, imu_data: Measurement) -> None: + """Updates the state using the IMU data. """ - Updates the state using the IMU data. - """ - self.nominal_state_discrete(imu_data) self.error_state_prediction(imu_data) - + def dvl_update(self, dvl_measurement: Measurement) -> float: + """Updates the state using the DVL measurement. """ - Updates the state using the DVL measurement. - """ - NIS = self.measurement_update(dvl_measurement) self.injection() self.reset_error_state() @@ -259,13 +294,17 @@ def dvl_update(self, dvl_measurement: Measurement) -> float: # functions for tuning the filter def NIS(self, S: np.ndarray, innovation: np.ndarray) -> float: - """ - Calculates the Normalized Innovation Squared (NIS) value. + """Calculates the Normalized Innovation Squared (NIS) value. """ return innovation.T @ np.linalg.inv(S) @ innovation - - def NEES(self, P: np.ndarray, true_state: StateQuat, estimate_state: StateQuat) -> float: - """ - Calculates the Normalized Estimation Error Squared (NEES) value. + + def NEEDS( + self, P: np.ndarray, true_state: StateQuat, estimate_state: StateQuat + ) -> float: + """Calculates the Normalized Estimation Error Squared (NEEDS) value. """ - return (true_state - estimate_state).as_vector().T @ np.linalg.inv(P) @ (true_state - estimate_state).as_vector() \ No newline at end of file + return ( + (true_state - estimate_state).as_vector().T + @ np.linalg.inv(P) + @ (true_state - estimate_state).as_vector() + ) diff --git a/navigation/eskf_python/eskf_python/eskf_test.py b/navigation/eskf_python/eskf_python/eskf_test.py index 95f5e996b..53ad83958 100644 --- a/navigation/eskf_python/eskf_python/eskf_test.py +++ b/navigation/eskf_python/eskf_python/eskf_test.py @@ -1,14 +1,13 @@ - -from eskf_python_class import StateEuler, StateQuat, MeasurementModel, Measurement -from eskf_python_utils import quat_to_euler -from eskf_test_utils import process_model, StateQuatModel -import numpy as np import matplotlib.pyplot as plt +import numpy as np +from eskf_python_class import Measurement, StateQuat from eskf_python_filter import ESKF +from eskf_python_utils import quat_to_euler +from eskf_test_utils import StateQuatModel, process_model from scipy.stats import chi2 -def simulate_eskf(): +def simulate_eskf(): # Simulation parameters simulation_time = 20.0 # seconds dt = 0.01 @@ -20,47 +19,71 @@ def simulate_eskf(): true_state_init = StateQuat() true_state_init.position = np.array([0.1, 0.0, 0.0]) true_state_init.velocity = np.array([0.1, 0.0, 0.0]) - P0 = np.diag([ - 0.5, 0.5, 0.5, # Position - 0.2, 0.2, 0.2, # Velocity - 0.2, 0.2, 0.2, # Orientation - 0.00001, 0.00001, 0.00001, # Acceleration bias - 0.00001, 0.00001, 0.00001, # Gyro bias - 0.00001, 0.00001, 0.00001 # Gravity - ]) - + P0 = np.diag( + [ + 0.3, + 0.3, + 0.3, # Position + 0.2, + 0.2, + 0.2, # Velocity + 0.2, + 0.2, + 0.2, # Orientation + 0.0001, + 0.0001, + 0.0001, # Acceleration bias + 0.00001, + 0.00001, + 0.00001, # Gyro bias + 0.00001, + 0.00001, + 0.00001, # Gravity + ] + ) # Noise parameters - Q = np.diag([ - (0.034**2) / dt, (0.034**2) / dt, (0.034**2) / dt, # Accelerometer noise - (0.002**2) / dt, (0.002**2) / dt, (0.002**2) / dt, # Gyroscope noise - 0.00001, 0.00001, 0.00001, # Acceleration bias random walk - 0.00001, 0.00001, 0.00001 # Gyro bias random walk - ]) - - Hx = np.zeros((3, 19)) - Hx[0:3, 3:6] = np.eye(3) + Q = np.diag( + [ + (0.13**2), + (0.13**2), + (0.13**2), # Adjusted Accelerometer noise + (0.13**2), + (0.13**2), + (0.13**2), # Adjusted Gyroscope noise + 0.0001, + 0.0001, + 0.0001, # Adjusted Acceleration bias random walk + 0.0001, + 0.0001, + 0.0001, # Adjusted Gyro bias random walk + ] + ) # Create filter object - eskf = ESKF(Q, P0, Hx, true_state_init, 1e-13, 1e-13, dt) + eskf = ESKF(Q, P0, true_state_init, 1e-13, 1e-13, dt) # Create measurement objects imu_data = Measurement() dvl_data = Measurement() # R matrix for DVL aiding - dvl_data.aiding_covariance = np.diag([(0.01)**2, (0.01)**2, (0.01)**2]) + dvl_data.aiding_covariance = np.diag( + [(0.01) ** 2, (0.01) ** 2, (0.01) ** 2] + ) # Adjusted DVL aiding covariance # Setup the process model for simulation of AUV model = process_model() model.dt = dt - model.mass_interia_matrix = np.array([ - [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] - ]) + model.mass_interia_matrix = np.array( + [ + [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], + ] + ) model.m = 30.0 model.r_b_bg = np.array([0.01, 0.0, 0.02]) model.inertia = np.diag([0.68, 3.32, 3.34]) @@ -89,19 +112,21 @@ def simulate_eskf(): est_velocities = np.zeros((num_steps, 3)) # covariance arrays - pos_cov = np.zeros((num_steps, 3)) - vel_cov = np.zeros((num_steps, 3)) - ori_cov = np.zeros((num_steps, 3)) + pos_cov = np.zeros((num_steps, 3)) + vel_cov = np.zeros((num_steps, 3)) + ori_cov = np.zeros((num_steps, 3)) prev_velocity = np.zeros(3) - u = lambda t: np.array([ - 0.5 * np.sin(0.1 * t), - 0.5 * np.sin(0.1 * t + 0.3), - 0.5 * np.sin(0.1 * t + 0.6), - 0.05 * np.cos(0.1 * t), - 0.05 * np.cos(0.1 * t + 0.3), - 0.05 * np.cos(0.1 * t + 0.6) - ]) + u = lambda t: np.array( + [ + 0.5 * np.sin(0.1 * t), + 0.5 * np.sin(0.1 * t + 0.3), + 0.5 * np.sin(0.1 * t + 0.6), + 0.05 * np.cos(0.1 * t), + 0.05 * np.cos(0.1 * t + 0.3), + 0.05 * np.cos(0.1 * t + 0.6), + ] + ) NIS_list = [] NIS_value = 0.0 @@ -114,12 +139,16 @@ def simulate_eskf(): model.model_prediction(new_state) new_state = model.euler_forward() - imu_data.acceleration = ((new_state.velocity - prev_velocity) / dt) + np.random.normal(0, 0.13, 3) - imu_data.angular_velocity = new_state.angular_velocity + np.random.normal(0, 0.13, 3) + imu_data.acceleration = ( + (new_state.velocity - prev_velocity) / dt + ) + np.random.normal(0, 0.13, 3) + imu_data.angular_velocity = new_state.angular_velocity + np.random.normal( + 0, 0.13, 3 + ) eskf.imu_update(imu_data) - if step % 20 == 0: + if step % 200 == 0: dvl_data.aiding = new_state.velocity + np.random.normal(0, 0.01, 3) NIS_value = eskf.dvl_update(dvl_data) NIS_list.append(NIS_value) @@ -140,9 +169,34 @@ def simulate_eskf(): prev_velocity = new_state.velocity model.state_vector_prev = new_state - return time, true_positions, true_orientations, true_velocities, est_positions, est_orientations, est_velocities, pos_cov, vel_cov, ori_cov, NIS_list - -time, true_positions, true_orientations, true_velocities, est_positions, est_orientations, est_velocities, pos_cov, vel_cov, ori_cov, _ = simulate_eskf() + return ( + time, + true_positions, + true_orientations, + true_velocities, + est_positions, + est_orientations, + est_velocities, + pos_cov, + vel_cov, + ori_cov, + NIS_list, + ) + + +( + time, + true_positions, + true_orientations, + true_velocities, + est_positions, + est_orientations, + est_velocities, + pos_cov, + vel_cov, + ori_cov, + _, +) = simulate_eskf() # Plotting axis_labels_pos = ["X", "Y", "Z"] @@ -154,11 +208,28 @@ def simulate_eskf(): fig_pos.suptitle("True Data vs Filter Estimates for Position") for i in range(3): ax_pos = axs_pos[i] - ax_pos.plot(time, true_positions[:, i], label=f"True Pos {axis_labels_pos[i]}", color=f"C{i}", linestyle='-') - ax_pos.plot(time, est_positions[:, i], label=f"Est Pos {axis_labels_pos[i]}", color=f"C{i}", linestyle='--') + ax_pos.plot( + time, + true_positions[:, i], + label=f"True Pos {axis_labels_pos[i]}", + color=f"C{i}", + linestyle='-', + ) + ax_pos.plot( + time, + est_positions[:, i], + label=f"Est Pos {axis_labels_pos[i]}", + color=f"C{i}", + linestyle='--', + ) sigma_pos = np.sqrt(pos_cov[:, i]) - ax_pos.fill_between(time, est_positions[:, i] - sigma_pos, est_positions[:, i] + sigma_pos, - color=f"C{i}", alpha=0.2) + ax_pos.fill_between( + time, + est_positions[:, i] - sigma_pos, + est_positions[:, i] + sigma_pos, + color=f"C{i}", + alpha=0.2, + ) ax_pos.set_title(f"Position [{axis_labels_pos[i]}] [m]") ax_pos.set_xlabel("Time [s]") ax_pos.set_ylabel("Position") @@ -173,11 +244,28 @@ def simulate_eskf(): fig_vel.suptitle("True Data vs Filter Estimates for Velocity") for i in range(3): ax_vel = axs_vel[i] - ax_vel.plot(time, true_velocities[:, i], label=f"True Vel {axis_labels_vel[i]}", color=f"C{i}", linestyle='-') - ax_vel.plot(time, est_velocities[:, i], label=f"Est Vel {axis_labels_vel[i]}", color=f"C{i}", linestyle='--') + ax_vel.plot( + time, + true_velocities[:, i], + label=f"True Vel {axis_labels_vel[i]}", + color=f"C{i}", + linestyle='-', + ) + ax_vel.plot( + time, + est_velocities[:, i], + label=f"Est Vel {axis_labels_vel[i]}", + color=f"C{i}", + linestyle='--', + ) sigma_vel = np.sqrt(vel_cov[:, i]) - ax_vel.fill_between(time, est_velocities[:, i] - sigma_vel, est_velocities[:, i] + sigma_vel, - color=f"C{i}", alpha=0.2) + ax_vel.fill_between( + time, + est_velocities[:, i] - sigma_vel, + est_velocities[:, i] + sigma_vel, + color=f"C{i}", + alpha=0.2, + ) ax_vel.set_title(f"Velocity [{axis_labels_vel[i]}] [m/s]") ax_vel.set_xlabel("Time [s]") ax_vel.set_ylabel("Velocity") @@ -192,11 +280,28 @@ def simulate_eskf(): fig_ori.suptitle("True Data vs Filter Estimates for Orientation") for i in range(3): ax_ori = axs_ori[i] - ax_ori.plot(time, true_orientations[:, i], label=f"True Ori {axis_labels_ori[i]}", color=f"C{i}", linestyle='-') - ax_ori.plot(time, est_orientations[:, i], label=f"Est Ori {axis_labels_ori[i]}", color=f"C{i}", linestyle='--') + ax_ori.plot( + time, + true_orientations[:, i], + label=f"True Ori {axis_labels_ori[i]}", + color=f"C{i}", + linestyle='-', + ) + ax_ori.plot( + time, + est_orientations[:, i], + label=f"Est Ori {axis_labels_ori[i]}", + color=f"C{i}", + linestyle='--', + ) sigma_ori = np.sqrt(ori_cov[:, i]) - ax_ori.fill_between(time, est_orientations[:, i] - sigma_ori, est_orientations[:, i] + sigma_ori, - color=f"C{i}", alpha=0.2) + ax_ori.fill_between( + time, + est_orientations[:, i] - sigma_ori, + est_orientations[:, i] + sigma_ori, + color=f"C{i}", + alpha=0.2, + ) ax_ori.set_title(f"Orientation [{axis_labels_ori[i]}] [rad]") ax_ori.set_xlabel("Time [s]") ax_ori.set_ylabel("Orientation") @@ -207,19 +312,29 @@ def simulate_eskf(): plt.show() -### _______ NIS AND NEES _______ +### _______ NIS AND NEEDS _______ -num_simulations = 10 +num_simulations = 10 NIS_runs = [] for sim in range(num_simulations): - time, true_positions, true_orientations, true_velocities, \ - est_positions, est_orientations, est_velocities, \ - pos_cov, vel_cov, ori_cov, NIS_list = simulate_eskf() + ( + time, + true_positions, + true_orientations, + true_velocities, + est_positions, + est_orientations, + est_velocities, + pos_cov, + vel_cov, + ori_cov, + NIS_list, + ) = simulate_eskf() NIS_runs.append(np.array(NIS_list)) -NIS_runs = np.vstack(NIS_runs) +NIS_runs = np.vstack(NIS_runs) ANIS = np.mean(NIS_runs, axis=0) measurement_dimension = 3 @@ -227,7 +342,7 @@ def simulate_eskf(): chi2_lower = chi2.ppf(0.025, measurement_dimension) / num_simulations chi2_upper = chi2.ppf(0.975, measurement_dimension) / num_simulations -time_steps = np.arange(len(ANIS)) * 0.01 * 20 +time_steps = np.arange(len(ANIS)) * 0.01 * 20 fig, ax = plt.subplots(figsize=(10, 6)) ax.plot(time_steps, ANIS, label="ANIS", color="C0") @@ -240,4 +355,4 @@ def simulate_eskf(): ax.legend() plt.tight_layout() -plt.show() \ No newline at end of file +plt.show() diff --git a/navigation/ukf_okid/ukf_python/ukf_okid.py b/navigation/ukf_okid/ukf_python/ukf_okid.py index 1ede3f22b..f7000adb4 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid.py @@ -36,10 +36,10 @@ def generate_T_matrix(n: float) -> np.ndarray: if n % 2 == 1: # if n is odd T[n - 1, i - 1] = (-1) ** i - T = T / np.sqrt(2) + T = T / np.sqrt(2) return T - + def sigma_points(self, current_state: StateQuat) -> list[StateQuat]: """ Functions that generate the sigma points for the UKF @@ -53,12 +53,12 @@ def sigma_points(self, current_state: StateQuat) -> list[StateQuat]: S = np.linalg.cholesky(current_state.covariance + self.Q) self.sigma_points_list = [StateQuat() for _ in range(2 * n)] - + for state in self.sigma_points_list: - state.fill_states_different_dim(current_state.as_vector(), delta[:, self.sigma_points_list.index + state.fill_states_different_dim(current_state.as_vector(), return self.sigma_points_list - + def unscented_transform(self, current_state: StateQuat) -> StateQuat: """ @@ -94,18 +94,18 @@ def measurement_update(self, current_state: StateQuat, measurement: MeasModel) - z_i[i] = measurement.H(self.sigma_points_list[i]) meas_update = MeasModel() - + meas_update.measurement = mean_measurement(z_i, self.weight) - + meas_update.covariance = covariance_measurement(z_i, meas_update.measurement, self.weight) - + cross_correlation = cross_covariance(self.y_i, current_state.as_vector(), z_i, meas_update.measurement, self.weight) - + return meas_update, cross_correlation def posteriori_estimate(self, current_state: StateQuat, cross_correlation: np.ndarray, measurement: MeasModel, ex_measuremnt: MeasModel) -> StateQuat: """ - Calculates the posteriori estimate using measurment and the prior estimate + Calculates the posteriori estimate using measurement and the prior estimate """ nu_k = MeasModel() @@ -122,4 +122,4 @@ def posteriori_estimate(self, current_state: StateQuat, cross_correlation: np.nd self.process_model.state_vector_prev = posteriori_estimate - return posteriori_estimate \ No newline at end of file + return posteriori_estimate From 1ea9e56ae4b733f191cf0952eec69f71a649c1ad Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Wed, 2 Apr 2025 17:03:52 +0200 Subject: [PATCH 11/30] fix: Added correction for the IMU measurements --- navigation/eskf/CMakeLists.txt | 10 +- navigation/eskf/config/eskf_params.yaml | 3 +- navigation/eskf/include/eskf/eskf.hpp | 2 +- navigation/eskf/include/eskf/eskf_utils.hpp | 4 + navigation/eskf/include/eskf/typedefs.hpp | 48 +- navigation/eskf/src/eskf.cpp | 95 ++- navigation/eskf/src/eskf_ros.cpp | 81 ++- navigation/eskf/src/eskf_utils.cpp | 18 + .../eskf_python/eskf_python_filter.py | 116 ++-- .../eskf_python/eskf_python/eskf_test.py | 3 +- navigation/ukf_okid/ukf_python/ukf_okid.py | 33 +- .../ukf_okid/ukf_python/ukf_okid_class.py | 6 +- navigation/ukf_okid/ukf_python/ukf_test.py | 550 +++++++++--------- 13 files changed, 476 insertions(+), 493 deletions(-) diff --git a/navigation/eskf/CMakeLists.txt b/navigation/eskf/CMakeLists.txt index 2809f9ed9..6c8167609 100644 --- a/navigation/eskf/CMakeLists.txt +++ b/navigation/eskf/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.8) project(eskf) if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 17) + set(CMAKE_CXX_STANDARD 20) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") @@ -16,6 +16,8 @@ find_package(geometry_msgs REQUIRED) find_package(Eigen3 REQUIRED) find_package(tf2 REQUIRED) find_package(vortex_msgs REQUIRED) +find_package(spdlog REQUIRED) +find_package(fmt REQUIRED) if(NOT DEFINED EIGEN3_INCLUDE_DIR) set(EIGEN3_INCLUDE_DIR ${EIGEN3_INCLUDE_DIRS}) @@ -38,6 +40,12 @@ ament_target_dependencies(eskf_node Eigen3 tf2 vortex_msgs + spdlog + fmt +) + +target_link_libraries(eskf_node + fmt::fmt ) install(TARGETS diff --git a/navigation/eskf/config/eskf_params.yaml b/navigation/eskf/config/eskf_params.yaml index f3402f4a9..f89b62f79 100644 --- a/navigation/eskf/config/eskf_params.yaml +++ b/navigation/eskf/config/eskf_params.yaml @@ -1,5 +1,6 @@ eskf_node: ros__parameters: - imu_topic: imu/date_raw + imu_topic: imu/data_raw dvl_twist: /orca/twist odom_topic: odom + diag_Q_std: [0.0103, 0.0118, 0.0043, 0.00193, 0.00306, 0.00118, 0.000001, 0.000001, 0.000001, 0.000003, 0.000003, 0.000003] diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp index ee47277ea..b30dc35b0 100644 --- a/navigation/eskf/include/eskf/eskf.hpp +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -1,7 +1,7 @@ #ifndef ESKF_HPP #define ESKF_HPP -#include +#include #include #include "eskf/typedefs.hpp" #include "typedefs.hpp" diff --git a/navigation/eskf/include/eskf/eskf_utils.hpp b/navigation/eskf/include/eskf/eskf_utils.hpp index afd871772..100f7673d 100644 --- a/navigation/eskf/include/eskf/eskf_utils.hpp +++ b/navigation/eskf/include/eskf/eskf_utils.hpp @@ -8,4 +8,8 @@ Eigen::Matrix3d skew(const Eigen::Vector3d& v); double sq(const double& value); +Eigen::Quaterniond vector3d_to_quaternion(const Eigen::Vector3d& vector); + +Eigen::Quaterniond euler_to_quaternion(const Eigen::Vector3d& euler); + #endif // ESKF_UTILS_HPP diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index c93c92402..c0a1e41f9 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -5,26 +5,26 @@ #ifndef ESKF_TYPEDEFS_H #define ESKF_TYPEDEFS_H -#include +#include #include namespace Eigen { -typedef Eigen::Matrix Vector19d; -typedef Eigen::Matrix Vector18d; -typedef Eigen::Matrix Matrix18d; -typedef Eigen::Matrix Matrix19d; -typedef Eigen::Matrix Matrix18x12d; -typedef Eigen::Matrix Matrix4x3d; -typedef Eigen::Matrix Matrix3x19d; -typedef Eigen::Matrix Matrix3x18d; -typedef Eigen::Matrix Matrix12d; -typedef Eigen::Matrix Matrix18d; -typedef Eigen::Matrix Matrix3x1d; -typedef Eigen::Matrix Matrix19x18d; -typedef Eigen::Matrix Matrix18x3d; -typedef Eigen::Matrix Matrix36d; -typedef Eigen::Matrix Matrix6d; -typedef Eigen::Matrix Matrix9d; + typedef Eigen::Matrix Vector19d; + typedef Eigen::Matrix Vector18d; + typedef Eigen::Matrix Matrix18d; + typedef Eigen::Matrix Matrix19d; + typedef Eigen::Matrix Matrix18x12d; + typedef Eigen::Matrix Matrix4x3d; + typedef Eigen::Matrix Matrix3x19d; + typedef Eigen::Matrix Matrix3x18d; + typedef Eigen::Matrix Matrix12d; + typedef Eigen::Matrix Matrix18d; + typedef Eigen::Matrix Matrix3x1d; + typedef Eigen::Matrix Matrix19x18d; + typedef Eigen::Matrix Matrix18x3d; + typedef Eigen::Matrix Matrix36d; + typedef Eigen::Matrix Matrix6d; + typedef Eigen::Matrix Matrix9d; } // namespace Eigen struct state_quat { @@ -61,7 +61,7 @@ struct state_euler { Eigen::Vector3d euler = Eigen::Vector3d::Zero(); Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero(); Eigen::Vector3d accel_bias = Eigen::Vector3d::Zero(); - Eigen::Vector3d gravity = Eigen::Vector3d(0, 0, 9.81); + Eigen::Vector3d gravity = Eigen::Vector3d::Zero(); Eigen::Matrix18d covariance = Eigen::Matrix18d::Zero(); @@ -84,6 +84,18 @@ struct state_euler { struct imu_measurement { Eigen::Vector3d accel = Eigen::Vector3d::Zero(); Eigen::Vector3d gyro = Eigen::Vector3d::Zero(); + Eigen::Vector3d accel_uncorrected = Eigen::Vector3d::Zero(); + Eigen::Vector3d gyro_uncorrected = Eigen::Vector3d::Zero(); + + void correct() { + Eigen::Matrix3d R_nb; + R_nb << 0, 0, -1, + 0, -1, 0, + -1, 0, 0; + + accel = R_nb * accel_uncorrected; + gyro = R_nb * gyro_uncorrected; + } }; struct dvl_measurement { diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index 8218bf8d0..55d8516dd 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -6,7 +6,8 @@ #include "eskf/eskf_utils.hpp" #include "eskf/typedefs.hpp" -ESKF::ESKF(const eskf_params& params) : Q_(params.Q) {} +ESKF::ESKF(const eskf_params& params) : + Q_(params.Q) {} std::pair ESKF::van_loan_discretization( const Eigen::Matrix18d& A_c, @@ -42,44 +43,45 @@ Eigen::Matrix4x3d ESKF::calculate_Q_delta(const state_quat& nom_state) { Q_delta_theta *= 0.5; return Q_delta_theta; } - Eigen::Matrix3x19d ESKF::calculate_Hx(const state_quat& nom_state) { Eigen::Matrix3x19d Hx = Eigen::Matrix3x19d::Zero(); - Eigen::Matrix3d R_bn = - nom_state.quat.normalized().toRotationMatrix().transpose(); - - // normal measurement of the velocity - Hx.block<3, 3>(0, 3) = R_bn; - + Eigen::Quaterniond q = nom_state.quat.normalized(); + Eigen::Matrix3d R_bn = q.toRotationMatrix(); + Eigen::Vector3d v_n = nom_state.vel; + Hx.block<3, 3>(0, 3) = R_bn.transpose(); + Eigen::Matrix dR_dq; - Eigen::Quaterniond q = nom_state.quat.normalized(); double qw = q.w(); double qx = q.x(); double qy = q.y(); double qz = q.z(); - dR_dq.col(0) = - 2 * Eigen::Vector3d(qw * v_n.x() - qz * v_n.y() + qy * v_n.z(), - qz * v_n.x() + qw * v_n.y() - qx * v_n.z(), - -qy * v_n.x() + qx * v_n.y() + qw * v_n.z()); - - dR_dq.col(1) = - 2 * Eigen::Vector3d(qx * v_n.x() + qy * v_n.y() + qz * v_n.z(), - qy * v_n.x() - qx * v_n.y() - qw * v_n.z(), - qz * v_n.x() + qw * v_n.y() - qx * v_n.z()); - - dR_dq.col(2) = - 2 * Eigen::Vector3d(-qy * v_n.x() + qx * v_n.y() + qw * v_n.z(), - qx * v_n.x() + qy * v_n.y() + qz * v_n.z(), - -qw * v_n.x() + qz * v_n.y() - qy * v_n.z()); - - dR_dq.col(3) = - 2 * Eigen::Vector3d(-qz * v_n.x() - qw * v_n.y() + qx * v_n.z(), - qw * v_n.x() - qz * v_n.y() + qy * v_n.z(), - qx * v_n.x() + qy * v_n.y() + qz * v_n.z()); + dR_dq.col(0) = 2 * Eigen::Vector3d( + qw * v_n.x() + qz * v_n.y() - qy * v_n.z(), + -qz * v_n.x() + qw * v_n.y() + qx * v_n.z(), + qy * v_n.x() - qx * v_n.y() + qw * v_n.z() + ); + + dR_dq.col(1) = 2 * Eigen::Vector3d( + qx * v_n.x() + qy * v_n.y() + qz * v_n.z(), + qy * v_n.x() - qx * v_n.y() - qw * v_n.z(), + qz * v_n.x() + qw * v_n.y() - qx * v_n.z() + ); + + dR_dq.col(2) = 2 * Eigen::Vector3d( + -qy * v_n.x() + qx * v_n.y() + qw * v_n.z(), + qx * v_n.x() + qy * v_n.y() + qz * v_n.z(), + -qw * v_n.x() + qz * v_n.y() - qy * v_n.z() + ); + + dR_dq.col(3) = 2 * Eigen::Vector3d( + -qz * v_n.x() - qw * v_n.y() + qx * v_n.z(), + qw * v_n.x() - qz * v_n.y() + qy * v_n.z(), + qx * v_n.x() + qy * v_n.y() + qz * v_n.z() + ); Hx.block<3, 4>(0, 6) = dR_dq; @@ -98,8 +100,7 @@ Eigen::Matrix3x18d ESKF::calculate_H(const state_quat& nom_state) { Eigen::Matrix3x1d ESKF::calculate_h(const state_quat& nom_state) { Eigen::Matrix3x1d h; - Eigen::Matrix3d R_bn = - nom_state.quat.normalized().toRotationMatrix().transpose(); + Eigen::Matrix3d R_bn = nom_state.quat.normalized().toRotationMatrix().transpose(); h = R_bn * nom_state.vel; @@ -109,18 +110,14 @@ Eigen::Matrix3x1d ESKF::calculate_h(const state_quat& nom_state) { state_quat ESKF::nominal_state_discrete(const state_quat& nom_state, const imu_measurement& imu_meas, const double dt) { - Eigen::Vector3d acc = - nom_state.get_R() * (imu_meas.accel - nom_state.accel_bias) + - nom_state.gravity; + Eigen::Vector3d acc = nom_state.get_R() * (imu_meas.accel - nom_state.accel_bias) + nom_state.gravity; Eigen::Vector3d gyro = (imu_meas.gyro - nom_state.gyro_bias) * dt; state_quat next_nom_state; - next_nom_state.pos = - nom_state.pos + nom_state.vel * dt + 0.5 * sq(dt) * acc; + + next_nom_state.pos = nom_state.pos + nom_state.vel * dt + 0.5 * sq(dt) * acc; next_nom_state.vel = nom_state.vel + dt * acc; - next_nom_state.quat = - (nom_state.quat * - Eigen::Quaterniond(0, 0.5 * gyro.x(), 0.5 * gyro.y(), 0.5 * gyro.z())); + next_nom_state.quat = (nom_state.quat * vector3d_to_quaternion(gyro)); next_nom_state.quat.normalize(); next_nom_state.gyro_bias = nom_state.gyro_bias; next_nom_state.accel_bias = nom_state.accel_bias; @@ -135,7 +132,7 @@ state_euler ESKF::error_state_prediction(const state_euler& error_state, const double dt) { Eigen::Matrix3d R = nom_state.get_R(); Eigen::Vector3d acc = (imu_meas.accel - nom_state.accel_bias); - Eigen::Vector3d gyro = imu_meas.gyro - nom_state.gyro_bias; + Eigen::Vector3d gyro = (imu_meas.gyro - nom_state.gyro_bias); Eigen::Matrix18d A_c = Eigen::Matrix18d::Zero(); A_c.block<3, 3>(0, 3) = Eigen::Matrix3d::Identity(); @@ -191,10 +188,7 @@ std::pair ESKF::injection_and_reset( next_nom_state.pos = nom_state.pos + error_state.pos; next_nom_state.vel = nom_state.vel + error_state.vel; - next_nom_state.quat = - nom_state.quat * Eigen::Quaterniond(1, 0.5 * error_state.euler.x(), - 0.5 * error_state.euler.y(), - 0.5 * error_state.euler.z()); + next_nom_state.quat = nom_state.quat * vector3d_to_quaternion(error_state.euler); next_nom_state.quat.normalize(); next_nom_state.gyro_bias = nom_state.gyro_bias + error_state.gyro_bias; next_nom_state.accel_bias = nom_state.accel_bias + error_state.accel_bias; @@ -205,12 +199,6 @@ std::pair ESKF::injection_and_reset( Eigen::Matrix18d G = Eigen::Matrix18d::Identity(); new_error_state.covariance = G * error_state.covariance * G.transpose(); - new_error_state.pos = Eigen::Vector3d::Zero(); - new_error_state.vel = Eigen::Vector3d::Zero(); - new_error_state.euler = Eigen::Vector3d::Zero(); - new_error_state.gyro_bias = Eigen::Vector3d::Zero(); - new_error_state.accel_bias = Eigen::Vector3d::Zero(); - new_error_state.gravity = Eigen::Vector3d::Zero(); return {next_nom_state, new_error_state}; } @@ -221,8 +209,7 @@ std::pair ESKF::imu_update( const imu_measurement& imu_meas, const double dt) { state_quat next_nom_state = nominal_state_discrete(nom_state, imu_meas, dt); - state_euler next_error_state = - error_state_prediction(error_state, nom_state, imu_meas, dt); + state_euler next_error_state = error_state_prediction(error_state, next_nom_state, imu_meas, dt); return {next_nom_state, next_error_state}; } @@ -231,10 +218,8 @@ std::pair ESKF::dvl_update( const state_quat& nom_state, const state_euler& error_state, const dvl_measurement& dvl_meas) { - state_euler new_error_state = - measurement_update(nom_state, error_state, dvl_meas); - auto [updated_nom_state, updated_error_state] = - injection_and_reset(nom_state, new_error_state); + state_euler new_error_state = measurement_update(nom_state, error_state, dvl_meas); + auto [updated_nom_state, updated_error_state] = injection_and_reset(nom_state, new_error_state); return {updated_nom_state, updated_error_state}; } diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index a3b9c5cf3..524b48c29 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -1,63 +1,64 @@ #include "eskf/eskf_ros.hpp" -#include -#include #include "eskf/eskf_utils.hpp" #include "eskf/typedefs.hpp" +#include ESKFNode::ESKFNode() : Node("eskf_node") { time_step = std::chrono::milliseconds(1); - odom_pub_timer_ = this->create_wall_timer( - time_step, std::bind(&ESKFNode::publish_odom, this)); + odom_pub_timer_ = this->create_wall_timer(time_step, std::bind(&ESKFNode::publish_odom, this)); set_subscribers_and_publisher(); set_parameters(); + + spdlog::info("ESKF Node Initialized"); } void ESKFNode::set_subscribers_and_publisher() { rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto qos_sensor_data = rclcpp::QoS( - rclcpp::QoSInitialization(qos_profile.history, 1), qos_profile); + auto qos_sensor_data = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 1), qos_profile); this->declare_parameter("imu_topic", "imu/data_raw"); std::string imu_topic = this->get_parameter("imu_topic").as_string(); - imu_sub_ = this->create_subscription( - imu_topic, qos_sensor_data, - std::bind(&ESKFNode::imu_callback, this, std::placeholders::_1)); + imu_sub_ = this->create_subscription(imu_topic, qos_sensor_data, std::bind(&ESKFNode::imu_callback, this, std::placeholders::_1)); this->declare_parameter("dvl_topic", "/orca/twist"); std::string dvl_topic = this->get_parameter("dvl_topic").as_string(); - dvl_sub_ = this->create_subscription< - geometry_msgs::msg::TwistWithCovarianceStamped>( - dvl_topic, qos_sensor_data, - std::bind(&ESKFNode::dvl_callback, this, std::placeholders::_1)); + dvl_sub_ = this->create_subscription(dvl_topic, qos_sensor_data, std::bind(&ESKFNode::dvl_callback, this, std::placeholders::_1)); + this->declare_parameter("odom_topic", "odom"); std::string odom_topic = this->get_parameter("odom_topic").as_string(); - odom_pub_ = this->create_publisher( - odom_topic, qos_sensor_data); + odom_pub_ = this->create_publisher(odom_topic, qos_sensor_data); } void ESKFNode::set_parameters() { + + std::vector diag_Q_std; + this->declare_parameter>("diag_Q_std"); // gyroscope bias noise + + diag_Q_std = this->get_parameter("diag_Q_std").as_double_array(); + Eigen::Matrix12d Q; Q.setZero(); - Q.diagonal() << sq(0.0103), sq(0.0118), sq(0.0043), // acceleration noise - sq(0.00193), sq(0.00306), sq(0.00118), // gyroscope noise - sq(0.05), sq(0.05), sq(0.05), // acceleration bias noise - sq(0.03), sq(0.03), sq(0.03); // gyroscope bias noise - + spdlog::info("Q diagonal: {}",diag_Q_std[0]); + Q.diagonal() << + sq(diag_Q_std[0]), sq(diag_Q_std[1]), sq(diag_Q_std[2]), // acceleration noise + sq(diag_Q_std[3]), sq(diag_Q_std[4]), sq(diag_Q_std[5]), // gyroscope noise + sq(diag_Q_std[6]), sq(diag_Q_std[7]), sq(diag_Q_std[8]), // acceleration bias noise + sq(diag_Q_std[9]), sq(diag_Q_std[10]), sq(diag_Q_std[11]); // gyroscope bias noise eskf_params_.Q = Q; eskf_ = std::make_unique(eskf_params_); Eigen::Matrix18d P; P.setZero(); - P.diagonal() << 0.1, 0.1, 0.1, // position - 0.1, 0.1, 0.1, // velocity - 0.1, 0.1, 0.1, // euler angles - 0.01, 0.01, 0.01, // accel bias - 0.01, 0.01, 0.01, // gyro bias - 0.001, 0.001, 0.001; // gravity + P.diagonal() << 1.0, 1.0, 1.0, // position + 0.1, 0.1, 0.1, // velocity + 0.1, 0.1, 0.1, // euler angles + 0.001, 0.001, 0.001, // accel bias + 0.001, 0.001, 0.001, // gyro bias + 0.001, 0.001, 0.001; // gravity error_state_.covariance = P; } @@ -71,30 +72,24 @@ void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { return; } - double dt = (current_time - last_imu_time_).seconds(); + double dt = (current_time - last_imu_time_).nanoseconds() * 1e-9; last_imu_time_ = current_time; - imu_meas_.accel << msg->linear_acceleration.x, msg->linear_acceleration.y, - msg->linear_acceleration.z; - imu_meas_.gyro << msg->angular_velocity.x, msg->angular_velocity.y, - msg->angular_velocity.z; + imu_meas_.accel_uncorrected << msg->linear_acceleration.x, msg->linear_acceleration.y, msg->linear_acceleration.z; + imu_meas_.gyro_uncorrected << msg->angular_velocity.x, msg->angular_velocity.y, msg->angular_velocity.z; + imu_meas_.correct(); - std::tie(nom_state_, error_state_) = - eskf_->imu_update(nom_state_, error_state_, imu_meas_, dt); + std::tie(nom_state_, error_state_) = eskf_->imu_update(nom_state_, error_state_, imu_meas_, dt); } void ESKFNode::dvl_callback( const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { - dvl_meas_.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, - msg->twist.twist.linear.z; - dvl_meas_.cov << msg->twist.covariance[0], msg->twist.covariance[1], - msg->twist.covariance[2], msg->twist.covariance[6], - msg->twist.covariance[7], msg->twist.covariance[8], - msg->twist.covariance[12], msg->twist.covariance[13], - msg->twist.covariance[14]; - - std::tie(nom_state_, error_state_) = - eskf_->dvl_update(nom_state_, error_state_, dvl_meas_); + dvl_meas_.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, msg->twist.twist.linear.z; + dvl_meas_.cov << msg->twist.covariance[0], msg->twist.covariance[1], msg->twist.covariance[2], + msg->twist.covariance[6], msg->twist.covariance[7], msg->twist.covariance[8], + msg->twist.covariance[12], msg->twist.covariance[13], msg->twist.covariance[14]; + + std::tie(nom_state_, error_state_) = eskf_->dvl_update(nom_state_, error_state_, dvl_meas_); } void ESKFNode::publish_odom() { diff --git a/navigation/eskf/src/eskf_utils.cpp b/navigation/eskf/src/eskf_utils.cpp index 4d33ec7ce..7a668adfc 100644 --- a/navigation/eskf/src/eskf_utils.cpp +++ b/navigation/eskf/src/eskf_utils.cpp @@ -11,3 +11,21 @@ Eigen::Matrix3d skew(const Eigen::Vector3d& v) { double sq(const double& value) { return value * value; } + +Eigen::Quaterniond vector3d_to_quaternion(const Eigen::Vector3d& vector) { + double angle = vector.norm(); + if (angle < 1e-8) { + return Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0); + } else { + Eigen::Vector3d axis = vector / angle; + return Eigen::Quaterniond(Eigen::AngleAxisd(angle, axis)); + } +} + +Eigen::Quaterniond euler_to_quaternion(const Eigen::Vector3d& euler) { + Eigen::Quaterniond q; + q = Eigen::AngleAxisd(euler.z(), Eigen::Vector3d::UnitZ()) * + Eigen::AngleAxisd(euler.y(), Eigen::Vector3d::UnitY()) * + Eigen::AngleAxisd(euler.x(), Eigen::Vector3d::UnitX()); + return q; +} \ No newline at end of file diff --git a/navigation/eskf_python/eskf_python/eskf_python_filter.py b/navigation/eskf_python/eskf_python/eskf_python_filter.py index 245d7ece4..890226639 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_filter.py +++ b/navigation/eskf_python/eskf_python/eskf_python_filter.py @@ -25,54 +25,6 @@ def __init__( self.p_accBias = p_accBias self.p_gyroBias = p_gyroBias - def Fx(self, imu_data: Measurement) -> np.ndarray: - """Calculates the state transition matrix. - - Args: - imu_data (np.ndarray): The IMU data. - - Returns: - np.ndarray: The state transition matrix. - """ - F_x = np.zeros((18, 18)) - I = np.eye(3) - - F_x[0:3, 0:3] = I - F_x[0:3, 3:6] = self.dt * I - F_x[3:6, 3:6] = I - F_x[3:6, 6:9] = ( - -self.nom_state.R_q() - @ skew_matrix(imu_data.acceleration - self.nom_state.acceleration_bias) - * self.dt - ) - F_x[6:9, 6:9] = R_from_angle_axis( - (imu_data.angular_velocity - self.nom_state.gyro_bias) * self.dt - ).T - F_x[3:6, 9:12] = -self.nom_state.R_q() * self.dt - F_x[3:6, 15:18] = I * self.dt - F_x[6:9, 12:15] = -I * self.dt - F_x[9:12, 9:12] = I - F_x[12:15, 12:15] = I - F_x[15:18, 15:18] = I - - return F_x - - def Fi(self) -> np.ndarray: - """Calculates the input matrix. - - Returns: - np.ndarray: The input matrix. - """ - F_i = np.zeros((18, 12)) - I = np.eye(3) - - F_i[3:6, 0:3] = I - F_i[6:9, 3:6] = I - F_i[9:12, 6:9] = I - F_i[12:15, 9:12] = I - - return F_i - def Q_delta_theta(self) -> np.ndarray: """Calculates the Q_delta_theta matrix. See Joan Solà. Quaternion kinematics for the error-state Kalman filter. @@ -92,26 +44,58 @@ def Q_delta_theta(self) -> np.ndarray: return Q_delta_theta def Hx(self) -> np.ndarray: - """Calculates the Jacobian of the measurement model. - - Returns: - np.ndarray: The Jacobian of the measurement model. """ - Hx = np.zeros((3, 19)) - - q0, q1, q2, q3 = self.nom_state.orientation - e = np.array([q1, q2, q3]) - v = self.nom_state.velocity - - temp_nu = -2 * skew_matrix(e) @ v - temp_eps = 2 * (q0 * np.eye(3) + skew_matrix(e)) @ skew_matrix(v) - - Hx[0:3, 3:6] = self.nom_state.R_q() - Hx[0:3, 6:10] = np.vstack([temp_nu, temp_eps]).T + Computes the true-state measurement Jacobian for the measurement + h(x) = R(q) * velocity, + where: + - R(q) is the rotation matrix from the quaternion (q, q, q, q) with q as the scalar part, + - velocity is a 3-vector. + + The state is assumed to be ordered as: + [position (3), velocity (3), quaternion (4), ...] (total length 19). + + The Jacobian Hx is a 3x19 matrix with nonzero blocks: + - Columns 3:6 (velocity): R(q) + - Columns 6:10 (quaternion): + """ + q = self.nom_state.orientation # shape (4,) + v = self.nom_state.velocity # shape (3,) + q0, q1, q2, q3 = q + v1, v2, v3 = v + + R = self.nom_state.R_q().transpose() # shape (3, 3) + + dhdq0 = 2 * np.array([ + q0 * v1 - q3 * v2 + q2 * v3, + q3 * v1 + q0 * v2 - q1 * v3, + -q2 * v1 + q1 * v2 + q0 * v3 + ]) + + dhdq1 = 2 * np.array([ + q1 * v1 + q2 * v2 + q3 * v3, + q2 * v1 - q1 * v2 - q0 * v3, + q3 * v1 + q0 * v2 - q1 * v3 + ]) + + dhdq2 = 2 * np.array([ + -q2 * v1 + q1 * v2 + q0 * v3, + q1 * v1 + q2 * v2 + q3 * v3, + -q0 * v1 + q3 * v2 - q2 * v3 + ]) + + dhdq3 = 2 * np.array([ + -q3 * v1 - q0 * v2 + q1 * v3, + q0 * v1 - q3 * v2 + q2 * v3, + q1 * v1 + q2 * v2 + q3 * v3 + ]) + + dHdq = np.column_stack((dhdq0, dhdq1, dhdq2, dhdq3)) # shape (3, 4) + Hx = np.zeros((3, 19)) - Hx[0:3, 3:6] = np.eye(3) - + Hx[:, 3:6] = R + Hx[:, 6:10] = dHdq + return Hx def H(self) -> np.ndarray: @@ -132,7 +116,7 @@ def h(self) -> np.ndarray: Returns: np.ndarray: The measurement model. """ - return self.nom_state.velocity # self.nom_state.R_q() @ self.nom_state.velocity + return self.nom_state.R_q() @ self.nom_state.velocity def nominal_state_discrete(self, imu_data: Measurement) -> None: """Calculates the next nominal state using the discrete-time process model defined in: diff --git a/navigation/eskf_python/eskf_python/eskf_test.py b/navigation/eskf_python/eskf_python/eskf_test.py index 53ad83958..0930d9f6c 100644 --- a/navigation/eskf_python/eskf_python/eskf_test.py +++ b/navigation/eskf_python/eskf_python/eskf_test.py @@ -313,7 +313,7 @@ def simulate_eskf(): ### _______ NIS AND NEEDS _______ - +""" num_simulations = 10 NIS_runs = [] @@ -356,3 +356,4 @@ def simulate_eskf(): plt.tight_layout() plt.show() +""" \ No newline at end of file diff --git a/navigation/ukf_okid/ukf_python/ukf_okid.py b/navigation/ukf_okid/ukf_python/ukf_okid.py index f7000adb4..16312935a 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid.py @@ -16,7 +16,7 @@ def __init__(self, process_model: process_model, x_0, P_0, Q, R): self.weight = None self.T = self.generate_T_matrix(len(P_0)) - def generate_T_matrix(n: float) -> np.ndarray: + def generate_T_matrix(self, n: float) -> np.ndarray: """ Generates the orthonormal transformation matrix T used in the TUKF sigma point generation. @@ -26,10 +26,10 @@ def generate_T_matrix(n: float) -> np.ndarray: Returns: T (np.ndarray): An n x 2n orthonormal transformation matrix used to generate TUKF sigma points. """ - T = np.zeros((n, 2 * n)) + T = np.zeros((n, n)) - for i in range(1, 2 * n + 1): - for j in range(1, (n // 2) + 1): + for i in range(n): + for j in range(n//2): T[2 * j - 2, i - 1] = np.sqrt(2) * np.cos(((2 * j - 1) * i * np.pi) / n) T[2 * j - 1, i - 1] = np.sqrt(2) * np.sin(((2 * j - 1) * i * np.pi) / n) @@ -54,8 +54,9 @@ def sigma_points(self, current_state: StateQuat) -> list[StateQuat]: self.sigma_points_list = [StateQuat() for _ in range(2 * n)] - for state in self.sigma_points_list: - state.fill_states_different_dim(current_state.as_vector(), + for index, state in enumerate(self.sigma_points_list): + delta_x = S @ delta[:, index] + state.fill_states_different_dim(current_state.as_vector(), delta_x) return self.sigma_points_list @@ -65,20 +66,20 @@ def unscented_transform(self, current_state: StateQuat) -> StateQuat: The unscented transform function generates the priori state estimate """ - _ , _ = self.sigma_points(current_state) + _ = self.sigma_points(current_state) n = len(current_state.covariance) - self.y_i = [StateQuat() for _ in range(2 * n + 1)] + self.y_i = [StateQuat() for _ in range(2 * n)] - for i in range(2 * n + 1): + for i in range(2 * n ): self.process_model.model_prediction(self.sigma_points_list[i]) self.y_i[i] = self.process_model.euler_forward() state_estimate = StateQuat() - x = mean_set(self.y_i, self.weight) + x = mean_set(self.y_i) state_estimate.fill_states(x) - state_estimate.covariance = covariance_set(self.y_i, x, self.weight) + state_estimate.covariance = covariance_set(self.y_i, x) return state_estimate def measurement_update(self, current_state: StateQuat, measurement: MeasModel) -> tuple[MeasModel, np.ndarray]: @@ -88,18 +89,18 @@ def measurement_update(self, current_state: StateQuat, measurement: MeasModel) - """ n = len(current_state.covariance) - z_i = [MeasModel() for _ in range(2 * n + 1)] + z_i = [MeasModel() for _ in range(2 * n)] - for i in range(2 * n + 1): + for i in range(2 * n): z_i[i] = measurement.H(self.sigma_points_list[i]) meas_update = MeasModel() - meas_update.measurement = mean_measurement(z_i, self.weight) + meas_update.measurement = mean_measurement(z_i) - meas_update.covariance = covariance_measurement(z_i, meas_update.measurement, self.weight) + meas_update.covariance = covariance_measurement(z_i, meas_update.measurement) - cross_correlation = cross_covariance(self.y_i, current_state.as_vector(), z_i, meas_update.measurement, self.weight) + cross_correlation = cross_covariance(self.y_i, current_state.as_vector(), z_i, meas_update.measurement) return meas_update, cross_correlation diff --git a/navigation/ukf_okid/ukf_python/ukf_okid_class.py b/navigation/ukf_okid/ukf_python/ukf_okid_class.py index 50f1988b4..4d3281260 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid_class.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid_class.py @@ -395,7 +395,7 @@ def mean_measurement(set_points: list[MeasModel]) -> np.ndarray: return mean_value.measurement -def covariance_set(set_points: list[StateQuat], mean: StateQuat) -> np.ndarray: +def covariance_set(set_points: list[StateQuat], mean: np.ndarray) -> np.ndarray: """ Function that calculates the covariance of a set of points """ @@ -403,9 +403,9 @@ def covariance_set(set_points: list[StateQuat], mean: StateQuat) -> np.ndarray: covariance = np.zeros(set_points[0].covariance.shape) mean_quat = StateQuat() - mean_quat.fill_states(mean.as_vector()) + mean_quat.fill_states(mean) - mean_q = mean.orientation + mean_q = mean_quat.orientation for state in set_points: q = state.orientation diff --git a/navigation/ukf_okid/ukf_python/ukf_test.py b/navigation/ukf_okid/ukf_python/ukf_test.py index 5a7e9eaba..3c197ed63 100644 --- a/navigation/ukf_okid/ukf_python/ukf_test.py +++ b/navigation/ukf_okid/ukf_python/ukf_test.py @@ -31,293 +31,267 @@ def add_quaternion_noise(q, noise_std): if __name__ == '__main__': - # Define a mean StateQuat - mean_state = StateQuat() - mean_state.position = np.array([1.0, 2.0, 3.0]) - mean_state.orientation = np.array([1.0, 0.0, 0.0, 0.0]) # Quaternion - mean_state.velocity = np.array([0.5, 0.5, 0.5]) - mean_state.angular_velocity = np.array([0.1, 0.1, 0.1]) - - test_state = StateQuat() - test_state.position = np.array([1.0, 1.0, 1.0]) - test_state.orientation = np.array([0.0, 1.0, 0.0, 0.0]) # Quaternion - test_state.velocity = np.array([0.2, 0.2, 0.2]) - test_state.angular_velocity = np.array([0.2, 0.2, 0.2]) - - # Create a set with only one element - state_set = list() - state_set.append(test_state) - print(len(state_set)) - - # Compute the mean - mean = mean_set(state_set) - - # Compute the covariance - mean_state.covariance = covariance_set(state_set, mean_state) - - # Print the results - print("Mean State:") - print_StateQuat(mean_state) - - # # Create initial state vector and covariance matrix. - # x0 = np.zeros(13) - # x0[0:3] = [0.3, 0.3, 0.3] - # x0[3] = 1 - # x0[7:10] = [0.2, 0.2, 0.2] - # dt = 0.01 - # R = (0.01) * np.eye(3) + # Create initial state vector and covariance matrix. + x0 = np.zeros(13) + x0[0:3] = [0.3, 0.3, 0.3] + x0[3] = 1 + x0[7:10] = [0.2, 0.2, 0.2] + dt = 0.01 + R = (0.01) * np.eye(3) - # Q = 0.00015 * np.eye(12) - # P0 = np.eye(12) * 0.0001 - - # model = process_model() - # model.dt = 0.01 - # model.mass_interia_matrix = np.array([ - # [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - # [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - # [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - # [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - # [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - # [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] - # ]) - # model.m = 30.0 - # model.r_b_bg = np.array([0.01, 0.0, 0.02]) - # model.inertia = np.diag([0.68, 3.32, 3.34]) - # model.damping_linear = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) - # model.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) - # model.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) - - # model_ukf = process_model() - # model_ukf.dt = 0.01 - # model_ukf.mass_interia_matrix = np.array([ - # [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - # [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - # [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - # [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - # [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - # [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] - # ]) - # model_ukf.m = 30.0 - # model_ukf.r_b_bg = np.array([0.01, 0.0, 0.02]) - # model_ukf.inertia = np.diag([0.68, 3.32, 3.34]) - # model_ukf.damping_linear = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) - # model_ukf.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) - # model_ukf.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) - - # # Simulation parameters - # simulation_time = 20 # seconds - # num_steps = int(simulation_time / dt) - - # # Initialize a dummy StateQuat. - # new_state = StateQuat() - # new_state.fill_states(x0) - # new_state.covariance = P0 - - # test_state_x = StateQuat() - # test_state_x.fill_states(x0) - # test_state_x.covariance = P0 - - # # Initialize a estimated state - # estimated_state = StateQuat() - # estimated_state.fill_states(x0) - # estimated_state.covariance = P0 - - # # Initialize a estimated state - # noisy_state = StateQuat() - # noisy_state.fill_states(x0) - # noisy_state.covariance = P0 - - # measurment_model = MeasModel() - # measurment_model.measurement = np.array([0.0, 0.0, 0.0]) - # measurment_model.covariance = R - - # # Initialize arrays to store the results - # positions = np.zeros((num_steps, 3)) - # orientations = np.zeros((num_steps, 3)) - # velocities = np.zeros((num_steps, 3)) - # angular_velocities = np.zeros((num_steps, 3)) - - # # Initialize arrays to store the estimates - # positions_est = np.zeros((num_steps, 3)) - # orientations_est = np.zeros((num_steps, 3)) - # velocities_est = np.zeros((num_steps, 3)) - # angular_velocities_est = np.zeros((num_steps, 3)) - - # # Initialize the okid params - # okid_params = np.zeros((num_steps, 21)) - - # model.state_vector_prev = new_state - # model.state_vector = new_state - - # model_ukf.state_vector_prev = test_state_x - # model_ukf.state_vector = test_state_x - - # # initialize the ukf - # ukf = UKF(model_ukf, x0, P0, Q, R) - - # elapsed_times = [] - - # u = lambda t: np.array([2 * np.sin(1 * t), 2 * np.sin(1 * t), 2 * np.sin(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t)]) - - # # Run the simulation - # for step in range(num_steps): - # # Insert control input - # model.Control_input = u(step * dt) - # model_ukf.Control_input = u(step * dt) - - # # Perform the unscented transform - # model.model_prediction(new_state) - # new_state = model.euler_forward() - - # # Adding noise in the state vector - # estimated_state.position = estimated_state.position # + np.random.normal(0, 0.01, 3) - # estimated_state.orientation = estimated_state.orientation #add_quaternion_noise(estimated_state.orientation, 0.01) - # estimated_state.velocity = estimated_state.velocity # + np.random.normal(0, 0.01, 3) - # estimated_state.angular_velocity = estimated_state.angular_velocity # + np.random.normal(0, 0.01, 3) - - # start_time = time.time() - # estimated_state = ukf.unscented_transform(estimated_state) - # elapsed_time = time.time() - start_time - # elapsed_times.append(elapsed_time) - - # if step % 10 == 0: - # measurment_model.measurement = new_state.velocity # + np.random.normal(0, 0.01, 3) - # meas_update, covariance_matrix = ukf.measurement_update(estimated_state, measurment_model) - # estimated_state = ukf.posteriori_estimate(estimated_state, covariance_matrix, measurment_model, meas_update) - - - # positions[step, :] = new_state.position - # orientations[step, :] = quat_to_euler(new_state.orientation) - # velocities[step, :] = new_state.velocity - # angular_velocities[step, :] = new_state.angular_velocity - - # positions_est[step, :] = estimated_state.position - # orientations_est[step, :] = quat_to_euler(estimated_state.orientation) - # velocities_est[step, :] = estimated_state.velocity - # angular_velocities_est[step, :] = estimated_state.angular_velocity + Q = 0.00015 * np.eye(12) + P0 = np.eye(12) * 0.0001 + + model = process_model() + model.dt = 0.01 + model.mass_interia_matrix = np.array([ + [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] + ]) + model.m = 30.0 + model.r_b_bg = np.array([0.01, 0.0, 0.02]) + model.inertia = np.diag([0.68, 3.32, 3.34]) + model.damping_linear = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) + model.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) + model.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) + + model_ukf = process_model() + model_ukf.dt = 0.01 + model_ukf.mass_interia_matrix = np.array([ + [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] + ]) + model_ukf.m = 30.0 + model_ukf.r_b_bg = np.array([0.01, 0.0, 0.02]) + model_ukf.inertia = np.diag([0.68, 3.32, 3.34]) + model_ukf.damping_linear = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) + model_ukf.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) + model_ukf.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) + + # Simulation parameters + simulation_time = 5 # seconds + num_steps = int(simulation_time / dt) + + # Initialize a dummy StateQuat. + new_state = StateQuat() + new_state.fill_states(x0) + new_state.covariance = P0 + + test_state_x = StateQuat() + test_state_x.fill_states(x0) + test_state_x.covariance = P0 + + # Initialize a estimated state + estimated_state = StateQuat() + estimated_state.fill_states(x0) + estimated_state.covariance = P0 + + # Initialize a estimated state + noisy_state = StateQuat() + noisy_state.fill_states(x0) + noisy_state.covariance = P0 + + measurment_model = MeasModel() + measurment_model.measurement = np.array([0.0, 0.0, 0.0]) + measurment_model.covariance = R + + # Initialize arrays to store the results + positions = np.zeros((num_steps, 3)) + orientations = np.zeros((num_steps, 3)) + velocities = np.zeros((num_steps, 3)) + angular_velocities = np.zeros((num_steps, 3)) + + # Initialize arrays to store the estimates + positions_est = np.zeros((num_steps, 3)) + orientations_est = np.zeros((num_steps, 3)) + velocities_est = np.zeros((num_steps, 3)) + angular_velocities_est = np.zeros((num_steps, 3)) + + # Initialize the okid params + okid_params = np.zeros((num_steps, 21)) + + model.state_vector_prev = new_state + model.state_vector = new_state + + model_ukf.state_vector_prev = test_state_x + model_ukf.state_vector = test_state_x + + # initialize the ukf + ukf = UKF(model_ukf, x0, P0, Q, R) + + elapsed_times = [] + + u = lambda t: np.array([2 * np.sin(1 * t), 2 * np.sin(1 * t), 2 * np.sin(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t)]) + + # Run the simulation + for step in range(num_steps): + # Insert control input + model.Control_input = u(step * dt) + model_ukf.Control_input = u(step * dt) + + # Perform the unscented transform + model.model_prediction(new_state) + new_state = model.euler_forward() + + # Adding noise in the state vector + estimated_state.position = estimated_state.position # + np.random.normal(0, 0.01, 3) + estimated_state.orientation = estimated_state.orientation #add_quaternion_noise(estimated_state.orientation, 0.01) + estimated_state.velocity = estimated_state.velocity # + np.random.normal(0, 0.01, 3) + estimated_state.angular_velocity = estimated_state.angular_velocity # + np.random.normal(0, 0.01, 3) + + start_time = time.time() + estimated_state = ukf.unscented_transform(estimated_state) + print(estimated_state.as_vector()) + break + elapsed_time = time.time() - start_time + elapsed_times.append(elapsed_time) + + if step % 20 == 0: + measurment_model.measurement = new_state.velocity # + np.random.normal(0, 0.01, 3) + meas_update, covariance_matrix = ukf.measurement_update(estimated_state, measurment_model) + estimated_state = ukf.posteriori_estimate(estimated_state, covariance_matrix, measurment_model, meas_update) + + + positions[step, :] = new_state.position + orientations[step, :] = quat_to_euler(new_state.orientation) + velocities[step, :] = new_state.velocity + angular_velocities[step, :] = new_state.angular_velocity + + positions_est[step, :] = estimated_state.position + orientations_est[step, :] = quat_to_euler(estimated_state.orientation) + velocities_est[step, :] = estimated_state.velocity + angular_velocities_est[step, :] = estimated_state.angular_velocity - # # Update the state for the next iteration - # model.state_vector_prev = new_state - - # print('Average elapsed time: ', np.mean(elapsed_times)) - # print('Max elapsed time: ', np.max(elapsed_times)) - # print('Min elapsed time: ', np.min(elapsed_times)) - # print('median elapsed time: ', np.median(elapsed_times)) - # # Plot the results - # time = np.linspace(0, simulation_time, num_steps) - - # # Plot positions - # plt.figure() - # plt.subplot(3, 1, 1) - # plt.plot(time, positions[:, 0], label='True') - # plt.plot(time, positions_est[:, 0], label='Estimated') - # plt.title('Position X') - # plt.xlabel('Time [s]') - # plt.ylabel('Position X [m]') - # plt.legend() - - # plt.subplot(3, 1, 2) - # plt.plot(time, positions[:, 1], label='True') - # plt.plot(time, positions_est[:, 1], label='Estimated') - # plt.title('Position Y') - # plt.xlabel('Time [s]') - # plt.ylabel('Position Y [m]') - # plt.legend() - - # plt.subplot(3, 1, 3) - # plt.plot(time, positions[:, 2], label='True') - # plt.plot(time, positions_est[:, 2], label='Estimated') - # plt.title('Position Z') - # plt.xlabel('Time [s]') - # plt.ylabel('Position Z [m]') - # plt.legend() - - # plt.tight_layout() - # plt.show() - - # # Plot orientations (Euler angles) - # plt.figure() - # plt.subplot(3, 1, 1) - # plt.plot(time, orientations[:, 0], label='True') - # plt.plot(time, orientations_est[:, 0], label='Estimated') - # plt.title('Orientation Roll') - # plt.xlabel('Time [s]') - # plt.ylabel('Roll [rad]') - # plt.legend() - - # plt.subplot(3, 1, 2) - # plt.plot(time, orientations[:, 1], label='True') - # plt.plot(time, orientations_est[:, 1], label='Estimated') - # plt.title('Orientation Pitch') - # plt.xlabel('Time [s]') - # plt.ylabel('Pitch [rad]') - # plt.legend() - - # plt.subplot(3, 1, 3) - # plt.plot(time, orientations[:, 2], label='True') - # plt.plot(time, orientations_est[:, 2], label='Estimated') - # plt.title('Orientation Yaw') - # plt.xlabel('Time [s]') - # plt.ylabel('Yaw [rad]') - # plt.legend() - - # plt.tight_layout() - # plt.show() - - # # Plot velocities - # plt.figure() - # plt.subplot(3, 1, 1) - # plt.plot(time, velocities[:, 0], label='True') - # plt.plot(time, velocities_est[:, 0], label='Estimated') - # plt.title('Velocity X') - # plt.xlabel('Time [s]') - # plt.ylabel('Velocity X [m/s]') - # plt.legend() - - # plt.subplot(3, 1, 2) - # plt.plot(time, velocities[:, 1], label='True') - # plt.plot(time, velocities_est[:, 1], label='Estimated') - # plt.title('Velocity Y') - # plt.xlabel('Time [s]') - # plt.ylabel('Velocity Y [m/s]') - # plt.legend() - - # plt.subplot(3, 1, 3) - # plt.plot(time, velocities[:, 2], label='True') - # plt.plot(time, velocities_est[:, 2], label='Estimated') - # plt.title('Velocity Z') - # plt.xlabel('Time [s]') - # plt.ylabel('Velocity Z [m/s]') - # plt.legend() - - # plt.tight_layout() - # plt.show() - - # # Plot angular velocities - # plt.figure() - # plt.subplot(3, 1, 1) - # plt.plot(time, angular_velocities[:, 0], label='True') - # plt.plot(time, angular_velocities_est[:, 0], label='Estimated') - # plt.title('Angular Velocity X') - # plt.xlabel('Time [s]') - # plt.ylabel('Angular Velocity X [rad/s]') - # plt.legend() - - # plt.subplot(3, 1, 2) - # plt.plot(time, angular_velocities[:, 1], label='True') - # plt.plot(time, angular_velocities_est[:, 1], label='Estimated') - # plt.title('Angular Velocity Y') - # plt.xlabel('Time [s]') - # plt.ylabel('Angular Velocity Y [rad/s]') - # plt.legend() - - # plt.subplot(3, 1, 3) - # plt.plot(time, angular_velocities[:, 2], label='True') - # plt.plot(time, angular_velocities_est[:, 2], label='Estimated') - # plt.title('Angular Velocity Z') - # plt.xlabel('Time [s]') - # plt.ylabel('Angular Velocity Z [rad/s]') - # plt.legend() - - # plt.tight_layout() - # plt.show() \ No newline at end of file + # Update the state for the next iteration + model.state_vector_prev = new_state + + print('Average elapsed time: ', np.mean(elapsed_times)) + print('Max elapsed time: ', np.max(elapsed_times)) + print('Min elapsed time: ', np.min(elapsed_times)) + print('median elapsed time: ', np.median(elapsed_times)) + # Plot the results + time = np.linspace(0, simulation_time, num_steps) + + # Plot positions + plt.figure() + plt.subplot(3, 1, 1) + plt.plot(time, positions[:, 0], label='True') + plt.plot(time, positions_est[:, 0], label='Estimated') + plt.title('Position X') + plt.xlabel('Time [s]') + plt.ylabel('Position X [m]') + plt.legend() + + plt.subplot(3, 1, 2) + plt.plot(time, positions[:, 1], label='True') + plt.plot(time, positions_est[:, 1], label='Estimated') + plt.title('Position Y') + plt.xlabel('Time [s]') + plt.ylabel('Position Y [m]') + plt.legend() + + plt.subplot(3, 1, 3) + plt.plot(time, positions[:, 2], label='True') + plt.plot(time, positions_est[:, 2], label='Estimated') + plt.title('Position Z') + plt.xlabel('Time [s]') + plt.ylabel('Position Z [m]') + plt.legend() + + plt.tight_layout() + plt.show() + + # Plot orientations (Euler angles) + plt.figure() + plt.subplot(3, 1, 1) + plt.plot(time, orientations[:, 0], label='True') + plt.plot(time, orientations_est[:, 0], label='Estimated') + plt.title('Orientation Roll') + plt.xlabel('Time [s]') + plt.ylabel('Roll [rad]') + plt.legend() + + plt.subplot(3, 1, 2) + plt.plot(time, orientations[:, 1], label='True') + plt.plot(time, orientations_est[:, 1], label='Estimated') + plt.title('Orientation Pitch') + plt.xlabel('Time [s]') + plt.ylabel('Pitch [rad]') + plt.legend() + + plt.subplot(3, 1, 3) + plt.plot(time, orientations[:, 2], label='True') + plt.plot(time, orientations_est[:, 2], label='Estimated') + plt.title('Orientation Yaw') + plt.xlabel('Time [s]') + plt.ylabel('Yaw [rad]') + plt.legend() + + plt.tight_layout() + plt.show() + + # Plot velocities + plt.figure() + plt.subplot(3, 1, 1) + plt.plot(time, velocities[:, 0], label='True') + plt.plot(time, velocities_est[:, 0], label='Estimated') + plt.title('Velocity X') + plt.xlabel('Time [s]') + plt.ylabel('Velocity X [m/s]') + plt.legend() + + plt.subplot(3, 1, 2) + plt.plot(time, velocities[:, 1], label='True') + plt.plot(time, velocities_est[:, 1], label='Estimated') + plt.title('Velocity Y') + plt.xlabel('Time [s]') + plt.ylabel('Velocity Y [m/s]') + plt.legend() + + plt.subplot(3, 1, 3) + plt.plot(time, velocities[:, 2], label='True') + plt.plot(time, velocities_est[:, 2], label='Estimated') + plt.title('Velocity Z') + plt.xlabel('Time [s]') + plt.ylabel('Velocity Z [m/s]') + plt.legend() + + plt.tight_layout() + plt.show() + + # Plot angular velocities + plt.figure() + plt.subplot(3, 1, 1) + plt.plot(time, angular_velocities[:, 0], label='True') + plt.plot(time, angular_velocities_est[:, 0], label='Estimated') + plt.title('Angular Velocity X') + plt.xlabel('Time [s]') + plt.ylabel('Angular Velocity X [rad/s]') + plt.legend() + + plt.subplot(3, 1, 2) + plt.plot(time, angular_velocities[:, 1], label='True') + plt.plot(time, angular_velocities_est[:, 1], label='Estimated') + plt.title('Angular Velocity Y') + plt.xlabel('Time [s]') + plt.ylabel('Angular Velocity Y [rad/s]') + plt.legend() + + plt.subplot(3, 1, 3) + plt.plot(time, angular_velocities[:, 2], label='True') + plt.plot(time, angular_velocities_est[:, 2], label='Estimated') + plt.title('Angular Velocity Z') + plt.xlabel('Time [s]') + plt.ylabel('Angular Velocity Z [rad/s]') + plt.legend() + + plt.tight_layout() + plt.show() \ No newline at end of file From 4cef60db587e4c09a910748ae1ceef4dfee4f2f3 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 3 Apr 2025 17:22:08 +0000 Subject: [PATCH 12/30] [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci --- navigation/eskf/include/eskf/typedefs.hpp | 40 ++- navigation/eskf/src/eskf.cpp | 69 ++-- navigation/eskf/src/eskf_ros.cpp | 79 +++-- navigation/eskf/src/eskf_utils.cpp | 2 +- .../eskf_python/eskf_python_class.py | 38 +-- .../eskf_python/eskf_python_filter.py | 87 ++--- .../eskf_python/eskf_python_node.py | 32 +- .../eskf_python/eskf_python_utils.py | 82 ++--- .../eskf_python/eskf_python/eskf_test.py | 3 +- .../eskf_python/eskf_test_utils.py | 131 ++++++-- navigation/ukf_okid/ukf_python/rest.py | 31 +- navigation/ukf_okid/ukf_python/ukf_okid.py | 54 +-- .../ukf_okid/ukf_python/ukf_okid_class.py | 307 +++++++++++------- navigation/ukf_okid/ukf_python/ukf_test.py | 106 +++--- navigation/ukf_okid/ukf_python/ukf_utils.py | 18 +- 15 files changed, 631 insertions(+), 448 deletions(-) diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index c0a1e41f9..925d8fd72 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -5,26 +5,26 @@ #ifndef ESKF_TYPEDEFS_H #define ESKF_TYPEDEFS_H -#include #include +#include namespace Eigen { - typedef Eigen::Matrix Vector19d; - typedef Eigen::Matrix Vector18d; - typedef Eigen::Matrix Matrix18d; - typedef Eigen::Matrix Matrix19d; - typedef Eigen::Matrix Matrix18x12d; - typedef Eigen::Matrix Matrix4x3d; - typedef Eigen::Matrix Matrix3x19d; - typedef Eigen::Matrix Matrix3x18d; - typedef Eigen::Matrix Matrix12d; - typedef Eigen::Matrix Matrix18d; - typedef Eigen::Matrix Matrix3x1d; - typedef Eigen::Matrix Matrix19x18d; - typedef Eigen::Matrix Matrix18x3d; - typedef Eigen::Matrix Matrix36d; - typedef Eigen::Matrix Matrix6d; - typedef Eigen::Matrix Matrix9d; +typedef Eigen::Matrix Vector19d; +typedef Eigen::Matrix Vector18d; +typedef Eigen::Matrix Matrix18d; +typedef Eigen::Matrix Matrix19d; +typedef Eigen::Matrix Matrix18x12d; +typedef Eigen::Matrix Matrix4x3d; +typedef Eigen::Matrix Matrix3x19d; +typedef Eigen::Matrix Matrix3x18d; +typedef Eigen::Matrix Matrix12d; +typedef Eigen::Matrix Matrix18d; +typedef Eigen::Matrix Matrix3x1d; +typedef Eigen::Matrix Matrix19x18d; +typedef Eigen::Matrix Matrix18x3d; +typedef Eigen::Matrix Matrix36d; +typedef Eigen::Matrix Matrix6d; +typedef Eigen::Matrix Matrix9d; } // namespace Eigen struct state_quat { @@ -89,10 +89,8 @@ struct imu_measurement { void correct() { Eigen::Matrix3d R_nb; - R_nb << 0, 0, -1, - 0, -1, 0, - -1, 0, 0; - + R_nb << 0, 0, -1, 0, -1, 0, -1, 0, 0; + accel = R_nb * accel_uncorrected; gyro = R_nb * gyro_uncorrected; } diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index 55d8516dd..58c532afa 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -6,8 +6,7 @@ #include "eskf/eskf_utils.hpp" #include "eskf/typedefs.hpp" -ESKF::ESKF(const eskf_params& params) : - Q_(params.Q) {} +ESKF::ESKF(const eskf_params& params) : Q_(params.Q) {} std::pair ESKF::van_loan_discretization( const Eigen::Matrix18d& A_c, @@ -48,7 +47,7 @@ Eigen::Matrix3x19d ESKF::calculate_Hx(const state_quat& nom_state) { Eigen::Quaterniond q = nom_state.quat.normalized(); Eigen::Matrix3d R_bn = q.toRotationMatrix(); - + Eigen::Vector3d v_n = nom_state.vel; Hx.block<3, 3>(0, 3) = R_bn.transpose(); @@ -59,29 +58,25 @@ Eigen::Matrix3x19d ESKF::calculate_Hx(const state_quat& nom_state) { double qy = q.y(); double qz = q.z(); - dR_dq.col(0) = 2 * Eigen::Vector3d( - qw * v_n.x() + qz * v_n.y() - qy * v_n.z(), - -qz * v_n.x() + qw * v_n.y() + qx * v_n.z(), - qy * v_n.x() - qx * v_n.y() + qw * v_n.z() - ); - - dR_dq.col(1) = 2 * Eigen::Vector3d( - qx * v_n.x() + qy * v_n.y() + qz * v_n.z(), - qy * v_n.x() - qx * v_n.y() - qw * v_n.z(), - qz * v_n.x() + qw * v_n.y() - qx * v_n.z() - ); - - dR_dq.col(2) = 2 * Eigen::Vector3d( - -qy * v_n.x() + qx * v_n.y() + qw * v_n.z(), - qx * v_n.x() + qy * v_n.y() + qz * v_n.z(), - -qw * v_n.x() + qz * v_n.y() - qy * v_n.z() - ); - - dR_dq.col(3) = 2 * Eigen::Vector3d( - -qz * v_n.x() - qw * v_n.y() + qx * v_n.z(), - qw * v_n.x() - qz * v_n.y() + qy * v_n.z(), - qx * v_n.x() + qy * v_n.y() + qz * v_n.z() - ); + dR_dq.col(0) = + 2 * Eigen::Vector3d(qw * v_n.x() + qz * v_n.y() - qy * v_n.z(), + -qz * v_n.x() + qw * v_n.y() + qx * v_n.z(), + qy * v_n.x() - qx * v_n.y() + qw * v_n.z()); + + dR_dq.col(1) = + 2 * Eigen::Vector3d(qx * v_n.x() + qy * v_n.y() + qz * v_n.z(), + qy * v_n.x() - qx * v_n.y() - qw * v_n.z(), + qz * v_n.x() + qw * v_n.y() - qx * v_n.z()); + + dR_dq.col(2) = + 2 * Eigen::Vector3d(-qy * v_n.x() + qx * v_n.y() + qw * v_n.z(), + qx * v_n.x() + qy * v_n.y() + qz * v_n.z(), + -qw * v_n.x() + qz * v_n.y() - qy * v_n.z()); + + dR_dq.col(3) = + 2 * Eigen::Vector3d(-qz * v_n.x() - qw * v_n.y() + qx * v_n.z(), + qw * v_n.x() - qz * v_n.y() + qy * v_n.z(), + qx * v_n.x() + qy * v_n.y() + qz * v_n.z()); Hx.block<3, 4>(0, 6) = dR_dq; @@ -100,7 +95,8 @@ Eigen::Matrix3x18d ESKF::calculate_H(const state_quat& nom_state) { Eigen::Matrix3x1d ESKF::calculate_h(const state_quat& nom_state) { Eigen::Matrix3x1d h; - Eigen::Matrix3d R_bn = nom_state.quat.normalized().toRotationMatrix().transpose(); + Eigen::Matrix3d R_bn = + nom_state.quat.normalized().toRotationMatrix().transpose(); h = R_bn * nom_state.vel; @@ -110,12 +106,15 @@ Eigen::Matrix3x1d ESKF::calculate_h(const state_quat& nom_state) { state_quat ESKF::nominal_state_discrete(const state_quat& nom_state, const imu_measurement& imu_meas, const double dt) { - Eigen::Vector3d acc = nom_state.get_R() * (imu_meas.accel - nom_state.accel_bias) + nom_state.gravity; + Eigen::Vector3d acc = + nom_state.get_R() * (imu_meas.accel - nom_state.accel_bias) + + nom_state.gravity; Eigen::Vector3d gyro = (imu_meas.gyro - nom_state.gyro_bias) * dt; state_quat next_nom_state; - next_nom_state.pos = nom_state.pos + nom_state.vel * dt + 0.5 * sq(dt) * acc; + next_nom_state.pos = + nom_state.pos + nom_state.vel * dt + 0.5 * sq(dt) * acc; next_nom_state.vel = nom_state.vel + dt * acc; next_nom_state.quat = (nom_state.quat * vector3d_to_quaternion(gyro)); next_nom_state.quat.normalize(); @@ -188,7 +187,8 @@ std::pair ESKF::injection_and_reset( next_nom_state.pos = nom_state.pos + error_state.pos; next_nom_state.vel = nom_state.vel + error_state.vel; - next_nom_state.quat = nom_state.quat * vector3d_to_quaternion(error_state.euler); + next_nom_state.quat = + nom_state.quat * vector3d_to_quaternion(error_state.euler); next_nom_state.quat.normalize(); next_nom_state.gyro_bias = nom_state.gyro_bias + error_state.gyro_bias; next_nom_state.accel_bias = nom_state.accel_bias + error_state.accel_bias; @@ -209,7 +209,8 @@ std::pair ESKF::imu_update( const imu_measurement& imu_meas, const double dt) { state_quat next_nom_state = nominal_state_discrete(nom_state, imu_meas, dt); - state_euler next_error_state = error_state_prediction(error_state, next_nom_state, imu_meas, dt); + state_euler next_error_state = + error_state_prediction(error_state, next_nom_state, imu_meas, dt); return {next_nom_state, next_error_state}; } @@ -218,8 +219,10 @@ std::pair ESKF::dvl_update( const state_quat& nom_state, const state_euler& error_state, const dvl_measurement& dvl_meas) { - state_euler new_error_state = measurement_update(nom_state, error_state, dvl_meas); - auto [updated_nom_state, updated_error_state] = injection_and_reset(nom_state, new_error_state); + state_euler new_error_state = + measurement_update(nom_state, error_state, dvl_meas); + auto [updated_nom_state, updated_error_state] = + injection_and_reset(nom_state, new_error_state); return {updated_nom_state, updated_error_state}; } diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index 524b48c29..d679d600e 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -1,11 +1,12 @@ #include "eskf/eskf_ros.hpp" +#include #include "eskf/eskf_utils.hpp" #include "eskf/typedefs.hpp" -#include ESKFNode::ESKFNode() : Node("eskf_node") { time_step = std::chrono::milliseconds(1); - odom_pub_timer_ = this->create_wall_timer(time_step, std::bind(&ESKFNode::publish_odom, this)); + odom_pub_timer_ = this->create_wall_timer( + time_step, std::bind(&ESKFNode::publish_odom, this)); set_subscribers_and_publisher(); @@ -16,49 +17,58 @@ ESKFNode::ESKFNode() : Node("eskf_node") { void ESKFNode::set_subscribers_and_publisher() { rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto qos_sensor_data = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 1), qos_profile); + auto qos_sensor_data = rclcpp::QoS( + rclcpp::QoSInitialization(qos_profile.history, 1), qos_profile); this->declare_parameter("imu_topic", "imu/data_raw"); std::string imu_topic = this->get_parameter("imu_topic").as_string(); - imu_sub_ = this->create_subscription(imu_topic, qos_sensor_data, std::bind(&ESKFNode::imu_callback, this, std::placeholders::_1)); + imu_sub_ = this->create_subscription( + imu_topic, qos_sensor_data, + std::bind(&ESKFNode::imu_callback, this, std::placeholders::_1)); this->declare_parameter("dvl_topic", "/orca/twist"); std::string dvl_topic = this->get_parameter("dvl_topic").as_string(); - dvl_sub_ = this->create_subscription(dvl_topic, qos_sensor_data, std::bind(&ESKFNode::dvl_callback, this, std::placeholders::_1)); - + dvl_sub_ = this->create_subscription< + geometry_msgs::msg::TwistWithCovarianceStamped>( + dvl_topic, qos_sensor_data, + std::bind(&ESKFNode::dvl_callback, this, std::placeholders::_1)); this->declare_parameter("odom_topic", "odom"); std::string odom_topic = this->get_parameter("odom_topic").as_string(); - odom_pub_ = this->create_publisher(odom_topic, qos_sensor_data); + odom_pub_ = this->create_publisher( + odom_topic, qos_sensor_data); } void ESKFNode::set_parameters() { - std::vector diag_Q_std; - this->declare_parameter>("diag_Q_std"); // gyroscope bias noise + this->declare_parameter>( + "diag_Q_std"); // gyroscope bias noise diag_Q_std = this->get_parameter("diag_Q_std").as_double_array(); - + Eigen::Matrix12d Q; Q.setZero(); - spdlog::info("Q diagonal: {}",diag_Q_std[0]); - Q.diagonal() << - sq(diag_Q_std[0]), sq(diag_Q_std[1]), sq(diag_Q_std[2]), // acceleration noise - sq(diag_Q_std[3]), sq(diag_Q_std[4]), sq(diag_Q_std[5]), // gyroscope noise - sq(diag_Q_std[6]), sq(diag_Q_std[7]), sq(diag_Q_std[8]), // acceleration bias noise - sq(diag_Q_std[9]), sq(diag_Q_std[10]), sq(diag_Q_std[11]); // gyroscope bias noise + spdlog::info("Q diagonal: {}", diag_Q_std[0]); + Q.diagonal() << sq(diag_Q_std[0]), sq(diag_Q_std[1]), + sq(diag_Q_std[2]), // acceleration noise + sq(diag_Q_std[3]), sq(diag_Q_std[4]), + sq(diag_Q_std[5]), // gyroscope noise + sq(diag_Q_std[6]), sq(diag_Q_std[7]), + sq(diag_Q_std[8]), // acceleration bias noise + sq(diag_Q_std[9]), sq(diag_Q_std[10]), + sq(diag_Q_std[11]); // gyroscope bias noise eskf_params_.Q = Q; eskf_ = std::make_unique(eskf_params_); Eigen::Matrix18d P; P.setZero(); - P.diagonal() << 1.0, 1.0, 1.0, // position - 0.1, 0.1, 0.1, // velocity - 0.1, 0.1, 0.1, // euler angles - 0.001, 0.001, 0.001, // accel bias - 0.001, 0.001, 0.001, // gyro bias - 0.001, 0.001, 0.001; // gravity + P.diagonal() << 1.0, 1.0, 1.0, // position + 0.1, 0.1, 0.1, // velocity + 0.1, 0.1, 0.1, // euler angles + 0.001, 0.001, 0.001, // accel bias + 0.001, 0.001, 0.001, // gyro bias + 0.001, 0.001, 0.001; // gravity error_state_.covariance = P; } @@ -75,21 +85,28 @@ void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { double dt = (current_time - last_imu_time_).nanoseconds() * 1e-9; last_imu_time_ = current_time; - imu_meas_.accel_uncorrected << msg->linear_acceleration.x, msg->linear_acceleration.y, msg->linear_acceleration.z; - imu_meas_.gyro_uncorrected << msg->angular_velocity.x, msg->angular_velocity.y, msg->angular_velocity.z; + imu_meas_.accel_uncorrected << msg->linear_acceleration.x, + msg->linear_acceleration.y, msg->linear_acceleration.z; + imu_meas_.gyro_uncorrected << msg->angular_velocity.x, + msg->angular_velocity.y, msg->angular_velocity.z; imu_meas_.correct(); - std::tie(nom_state_, error_state_) = eskf_->imu_update(nom_state_, error_state_, imu_meas_, dt); + std::tie(nom_state_, error_state_) = + eskf_->imu_update(nom_state_, error_state_, imu_meas_, dt); } void ESKFNode::dvl_callback( const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { - dvl_meas_.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, msg->twist.twist.linear.z; - dvl_meas_.cov << msg->twist.covariance[0], msg->twist.covariance[1], msg->twist.covariance[2], - msg->twist.covariance[6], msg->twist.covariance[7], msg->twist.covariance[8], - msg->twist.covariance[12], msg->twist.covariance[13], msg->twist.covariance[14]; - - std::tie(nom_state_, error_state_) = eskf_->dvl_update(nom_state_, error_state_, dvl_meas_); + dvl_meas_.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, + msg->twist.twist.linear.z; + dvl_meas_.cov << msg->twist.covariance[0], msg->twist.covariance[1], + msg->twist.covariance[2], msg->twist.covariance[6], + msg->twist.covariance[7], msg->twist.covariance[8], + msg->twist.covariance[12], msg->twist.covariance[13], + msg->twist.covariance[14]; + + std::tie(nom_state_, error_state_) = + eskf_->dvl_update(nom_state_, error_state_, dvl_meas_); } void ESKFNode::publish_odom() { diff --git a/navigation/eskf/src/eskf_utils.cpp b/navigation/eskf/src/eskf_utils.cpp index 7a668adfc..930167eaa 100644 --- a/navigation/eskf/src/eskf_utils.cpp +++ b/navigation/eskf/src/eskf_utils.cpp @@ -28,4 +28,4 @@ Eigen::Quaterniond euler_to_quaternion(const Eigen::Vector3d& euler) { Eigen::AngleAxisd(euler.y(), Eigen::Vector3d::UnitY()) * Eigen::AngleAxisd(euler.x(), Eigen::Vector3d::UnitX()); return q; -} \ No newline at end of file +} diff --git a/navigation/eskf_python/eskf_python/eskf_python_class.py b/navigation/eskf_python/eskf_python/eskf_python_class.py index 0ba96ba1f..65d41425d 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_class.py +++ b/navigation/eskf_python/eskf_python/eskf_python_class.py @@ -1,7 +1,9 @@ from dataclasses import dataclass, field + import numpy as np from eskf_python_utils import quaternion_error + @dataclass class StateQuat: position: np.ndarray = field( @@ -19,10 +21,8 @@ class StateQuat: gyro_bias: np.ndarray = field( default_factory=lambda: np.zeros(3) ) # Gyro bias vector (b_gx, b_gy, b_gz) - g: np.ndarray = field( - default_factory=lambda: np.array([0, 0, 0]) - ) # Gravity vector - + g: np.ndarray = field(default_factory=lambda: np.array([0, 0, 0])) # Gravity vector + def as_vector(self) -> np.ndarray: """Returns the state vector as a numpy array. @@ -81,7 +81,7 @@ def R_q(self) -> np.ndarray: ) return R - + def __sub__(self, other: 'StateQuat') -> 'StateQuat': """Subtracts the values of two state vectors. @@ -102,7 +102,6 @@ def __sub__(self, other: 'StateQuat') -> 'StateQuat': return result - @dataclass class StateEuler: position: np.ndarray = field( @@ -172,12 +171,8 @@ def copy_state(self, wanted_state: 'StateEuler') -> None: @dataclass class MeasurementModel: - measurement: np.ndarray = field( - default_factory=lambda: np.zeros(6) - ) - measurement_covariance: np.ndarray = field( - default_factory=lambda: np.zeros((6, 6)) - ) + measurement: np.ndarray = field(default_factory=lambda: np.zeros(6)) + measurement_covariance: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) def H(self) -> np.ndarray: """Calculates the measurement matrix. @@ -190,19 +185,12 @@ def H(self) -> np.ndarray: H[0:3, 3:6] = np.eye(3) return H - + + @dataclass class Measurement: - acceleration: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) - angular_velocity: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) - aiding: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) + acceleration: np.ndarray = field(default_factory=lambda: np.zeros(3)) + angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) + aiding: np.ndarray = field(default_factory=lambda: np.zeros(3)) - aiding_covariance: np.ndarray = field( - default_factory=lambda: np.zeros((3, 3)) - ) \ No newline at end of file + aiding_covariance: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) diff --git a/navigation/eskf_python/eskf_python/eskf_python_filter.py b/navigation/eskf_python/eskf_python/eskf_python_filter.py index 890226639..fac3c8526 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_filter.py +++ b/navigation/eskf_python/eskf_python/eskf_python_filter.py @@ -4,7 +4,6 @@ import numpy as np from eskf_python_class import Measurement, StateEuler, StateQuat from eskf_python_utils import ( - R_from_angle_axis, angle_axis_to_quaternion, euler_to_quat, quaternion_product, @@ -44,58 +43,64 @@ def Q_delta_theta(self) -> np.ndarray: return Q_delta_theta def Hx(self) -> np.ndarray: - """ - Computes the true-state measurement Jacobian for the measurement + """Computes the true-state measurement Jacobian for the measurement h(x) = R(q) * velocity, where: - R(q) is the rotation matrix from the quaternion (q, q, q, q) with q as the scalar part, - velocity is a 3-vector. - + The state is assumed to be ordered as: [position (3), velocity (3), quaternion (4), ...] (total length 19). - + The Jacobian Hx is a 3x19 matrix with nonzero blocks: - Columns 3:6 (velocity): R(q) - - Columns 6:10 (quaternion): + - Columns 6:10 (quaternion): """ - q = self.nom_state.orientation # shape (4,) - v = self.nom_state.velocity # shape (3,) + v = self.nom_state.velocity # shape (3,) q0, q1, q2, q3 = q v1, v2, v3 = v R = self.nom_state.R_q().transpose() # shape (3, 3) - - dhdq0 = 2 * np.array([ - q0 * v1 - q3 * v2 + q2 * v3, - q3 * v1 + q0 * v2 - q1 * v3, - -q2 * v1 + q1 * v2 + q0 * v3 - ]) - - dhdq1 = 2 * np.array([ - q1 * v1 + q2 * v2 + q3 * v3, - q2 * v1 - q1 * v2 - q0 * v3, - q3 * v1 + q0 * v2 - q1 * v3 - ]) - - dhdq2 = 2 * np.array([ - -q2 * v1 + q1 * v2 + q0 * v3, - q1 * v1 + q2 * v2 + q3 * v3, - -q0 * v1 + q3 * v2 - q2 * v3 - ]) - - dhdq3 = 2 * np.array([ - -q3 * v1 - q0 * v2 + q1 * v3, - q0 * v1 - q3 * v2 + q2 * v3, - q1 * v1 + q2 * v2 + q3 * v3 - ]) - + + dhdq0 = 2 * np.array( + [ + q0 * v1 - q3 * v2 + q2 * v3, + q3 * v1 + q0 * v2 - q1 * v3, + -q2 * v1 + q1 * v2 + q0 * v3, + ] + ) + + dhdq1 = 2 * np.array( + [ + q1 * v1 + q2 * v2 + q3 * v3, + q2 * v1 - q1 * v2 - q0 * v3, + q3 * v1 + q0 * v2 - q1 * v3, + ] + ) + + dhdq2 = 2 * np.array( + [ + -q2 * v1 + q1 * v2 + q0 * v3, + q1 * v1 + q2 * v2 + q3 * v3, + -q0 * v1 + q3 * v2 - q2 * v3, + ] + ) + + dhdq3 = 2 * np.array( + [ + -q3 * v1 - q0 * v2 + q1 * v3, + q0 * v1 - q3 * v2 + q2 * v3, + q1 * v1 + q2 * v2 + q3 * v3, + ] + ) + dHdq = np.column_stack((dhdq0, dhdq1, dhdq2, dhdq3)) # shape (3, 4) - + Hx = np.zeros((3, 19)) Hx[:, 3:6] = R Hx[:, 6:10] = dHdq - + return Hx def H(self) -> np.ndarray: @@ -262,14 +267,12 @@ def reset_error_state(self) -> None: self.error_state.fill_states(np.zeros(18)) def imu_update(self, imu_data: Measurement) -> None: - """Updates the state using the IMU data. - """ + """Updates the state using the IMU data.""" self.nominal_state_discrete(imu_data) self.error_state_prediction(imu_data) def dvl_update(self, dvl_measurement: Measurement) -> float: - """Updates the state using the DVL measurement. - """ + """Updates the state using the DVL measurement.""" NIS = self.measurement_update(dvl_measurement) self.injection() self.reset_error_state() @@ -278,15 +281,13 @@ def dvl_update(self, dvl_measurement: Measurement) -> float: # functions for tuning the filter def NIS(self, S: np.ndarray, innovation: np.ndarray) -> float: - """Calculates the Normalized Innovation Squared (NIS) value. - """ + """Calculates the Normalized Innovation Squared (NIS) value.""" return innovation.T @ np.linalg.inv(S) @ innovation def NEEDS( self, P: np.ndarray, true_state: StateQuat, estimate_state: StateQuat ) -> float: - """Calculates the Normalized Estimation Error Squared (NEEDS) value. - """ + """Calculates the Normalized Estimation Error Squared (NEEDS) value.""" return ( (true_state - estimate_state).as_vector().T @ np.linalg.inv(P) diff --git a/navigation/eskf_python/eskf_python/eskf_python_node.py b/navigation/eskf_python/eskf_python/eskf_python_node.py index ec206ab64..7b300ecc6 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_node.py +++ b/navigation/eskf_python/eskf_python/eskf_python_node.py @@ -1,12 +1,12 @@ #!/usr/bin/env python3 +import numpy as np import rclpy +from geometry_msgs.msg import TwistWithCovarianceStamped from nav_msgs.msg import Odometry from rclpy.node import Node from rclpy.qos import QoSProfile, qos_profile_sensor_data from sensor_msgs.msg import Imu -import numpy as np -from geometry_msgs.msg import TwistWithCovarianceStamped # NEED TO CHANGE THIS TO THE CORRECT PATH from eskf_python.eskf_python_filter import ( @@ -33,7 +33,10 @@ def __init__(self): ) self.twist_dvl_subscriber_ = self.create_subscription( - TwistWithCovarianceStamped, '/dvl/twist', self.filter_callback, qos_profile=qos_profile + TwistWithCovarianceStamped, + '/dvl/twist', + self.filter_callback, + qos_profile=qos_profile, ) # This publisher will publish the estimtaed state of the vehicle @@ -50,14 +53,22 @@ def __init__(self): self.get_logger().info("Error State Kalman Filter started") def imu_callback(self, msg: Imu): - # Get the IMU data imu_acceleartion = msg.linear_acceleration imu_angular_velocity = msg.angular_velocity # Combine the IMU data - imu_data = np.array([imu_acceleartion.x, imu_acceleartion.y, imu_acceleartion.z, imu_angular_velocity.x, imu_angular_velocity.y, imu_angular_velocity.z]) + imu_data = np.array( + [ + imu_acceleartion.x, + imu_acceleartion.y, + imu_acceleartion.z, + imu_angular_velocity.x, + imu_angular_velocity.y, + imu_angular_velocity.z, + ] + ) # Update the filter with the IMU data self.current_state_nom, self.current_state_error = ( @@ -84,8 +95,6 @@ def imu_callback(self, msg: Imu): # Publish self.state_publisher_.publish(self.odom_msg) - - def filter_callback(self, msg: TwistWithCovarianceStamped): """Callback function for the filter measurement update, this will be called when the filter needs to be updated with the DVL data. @@ -93,7 +102,13 @@ def filter_callback(self, msg: TwistWithCovarianceStamped): self.get_logger().info("Filter callback, got DVL data") # Get the DVL data (linear velocity) - dvl_data = np.array([msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z]) + dvl_data = np.array( + [ + msg.twist.twist.linear.x, + msg.twist.twist.linear.y, + msg.twist.twist.linear.z, + ] + ) # Update the filter with the DVL data self.current_state_nom, self.current_state_error = ( @@ -124,7 +139,6 @@ def filter_callback(self, msg: TwistWithCovarianceStamped): self.state_publisher_.publish(self.odom_msg) - def main(args=None): rclpy.init(args=args) node = ESKalmanFilterNode() diff --git a/navigation/eskf_python/eskf_python/eskf_python_utils.py b/navigation/eskf_python/eskf_python/eskf_python_utils.py index aaef5f8d6..bbe13d759 100644 --- a/navigation/eskf_python/eskf_python/eskf_python_utils.py +++ b/navigation/eskf_python/eskf_python/eskf_python_utils.py @@ -1,61 +1,61 @@ import numpy as np + def skew_matrix(vector: np.ndarray) -> np.ndarray: - """ - Returns the skew symmetric matrix of a 3x1 vector. + """Returns the skew symmetric matrix of a 3x1 vector. """ return np.array( [ [0, -vector[2], vector[1]], [vector[2], 0, -vector[0]], - [-vector[1], vector[0], 0] + [-vector[1], vector[0], 0], ] ) + def quat_norm(quat: np.ndarray) -> np.ndarray: - """ - Function that normalizes a quaternion + """Function that normalizes a quaternion """ quat = quat / np.linalg.norm(quat) return quat + def quaternion_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: - """Calculates the quaternion super product of two quaternions. + """Calculates the quaternion super product of two quaternions. - Args: - q1 (np.ndarray): The first quaternion. - q2 (np.ndarray): The second quaternion. + Args: + q1 (np.ndarray): The first quaternion. + q2 (np.ndarray): The second quaternion. - Returns: - np.ndarray: The quaternion super product. - """ + Returns: + np.ndarray: The quaternion super product. + """ + eta_0, e_0_x, e_0_y, e_0_z = q1 + eta_1, e_1_x, e_1_y, e_1_z = q2 - eta_0, e_0_x, e_0_y, e_0_z = q1 - eta_1, e_1_x, e_1_y, e_1_z = q2 + e_0 = np.array([e_0_x, e_0_y, e_0_z]) + e_1 = np.array([e_1_x, e_1_y, e_1_z]) - e_0 = np.array([e_0_x, e_0_y, e_0_z]) - e_1 = np.array([e_1_x, e_1_y, e_1_z]) + eta_new = eta_0 * eta_1 - np.dot(e_0, e_1) + nu_new = e_1 * eta_0 + e_0 * eta_1 + np.cross(e_0, e_1) - eta_new = eta_0 * eta_1 - np.dot(e_0, e_1) - nu_new = e_1 * eta_0 + e_0 * eta_1 + np.cross(e_0, e_1) + q_new = np.array([eta_new, nu_new[0], nu_new[1], nu_new[2]]) + q_new = q_new / np.linalg.norm(q_new) - q_new = np.array([eta_new, nu_new[0], nu_new[1], nu_new[2]]) - q_new = q_new / np.linalg.norm(q_new) + return q_new - return q_new def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: + """Calculates the error between two quaternions """ - Calculates the error between two quaternions - """ - quat_2_inv = np.array([quat_2[0], -quat_2[1], -quat_2[2], -quat_2[3]]) error_quat = quaternion_product(quat_1, quat_2_inv) return error_quat + def angle_axis_to_quaternion(vector: np.ndarray) -> np.ndarray: """Converts an angle-axis representation to a quaternion. @@ -71,13 +71,12 @@ def angle_axis_to_quaternion(vector: np.ndarray) -> np.ndarray: else: axis = vector / angle - q = np.zeros(4) q[0] = np.cos(angle / 2) q[1:] = np.sin(angle / 2) * axis return q - + def R_from_angle_axis(vector: np.ndarray) -> np.ndarray: """Calculates the rotation matrix from the angle-axis representation. @@ -109,40 +108,41 @@ def R_from_angle_axis(vector: np.ndarray) -> np.ndarray: 1 - 2 * q1**2 - 2 * q2**2, ], ] - ) + ) return R + def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: - """ - Converts Euler angles to a quaternion + """Converts Euler angles to a quaternion """ psi, theta, phi = euler_angles c_psi = np.cos(psi / 2) - s_psi = np.sin(psi / 2) + s_psi = np.sin(psi / 2) c_theta = np.cos(theta / 2) s_theta = np.sin(theta / 2) c_phi = np.cos(phi / 2) s_phi = np.sin(phi / 2) - quat = np.array([ - c_psi * c_theta * c_phi + s_psi * s_theta * s_phi, - c_psi * c_theta * s_phi - s_psi * s_theta * c_phi, - s_psi * c_theta * s_phi + c_psi * s_theta * c_phi, - s_psi * c_theta * c_phi - c_psi * s_theta * s_phi - ]) + quat = np.array( + [ + c_psi * c_theta * c_phi + s_psi * s_theta * s_phi, + c_psi * c_theta * s_phi - s_psi * s_theta * c_phi, + s_psi * c_theta * s_phi + c_psi * s_theta * c_phi, + s_psi * c_theta * c_phi - c_psi * s_theta * s_phi, + ] + ) return quat + def quat_to_euler(quat: np.ndarray) -> np.ndarray: - """ - Converts a quaternion to Euler angles + """Converts a quaternion to Euler angles """ nu, eta_1, eta_2, eta_3 = quat - phi = np.arctan2(2*(eta_2 * eta_3 + nu * eta_1), 1 - 2 * (eta_1 ** 2 + eta_2 ** 2)) + phi = np.arctan2(2 * (eta_2 * eta_3 + nu * eta_1), 1 - 2 * (eta_1**2 + eta_2**2)) theta = -np.arcsin(2 * (eta_1 * eta_3 - nu * eta_2)) - psi = np.arctan2(2 * (nu * eta_3 + eta_1 * eta_2), 1 - 2 * (eta_2 ** 2 + eta_3 ** 2)) + psi = np.arctan2(2 * (nu * eta_3 + eta_1 * eta_2), 1 - 2 * (eta_2**2 + eta_3**2)) return np.array([phi, theta, psi]) - diff --git a/navigation/eskf_python/eskf_python/eskf_test.py b/navigation/eskf_python/eskf_python/eskf_test.py index 0930d9f6c..2c6d94c09 100644 --- a/navigation/eskf_python/eskf_python/eskf_test.py +++ b/navigation/eskf_python/eskf_python/eskf_test.py @@ -4,7 +4,6 @@ from eskf_python_filter import ESKF from eskf_python_utils import quat_to_euler from eskf_test_utils import StateQuatModel, process_model -from scipy.stats import chi2 def simulate_eskf(): @@ -356,4 +355,4 @@ def simulate_eskf(): plt.tight_layout() plt.show() -""" \ No newline at end of file +""" diff --git a/navigation/eskf_python/eskf_python/eskf_test_utils.py b/navigation/eskf_python/eskf_python/eskf_test_utils.py index 34abe8eda..a60e62ff0 100644 --- a/navigation/eskf_python/eskf_python/eskf_test_utils.py +++ b/navigation/eskf_python/eskf_python/eskf_test_utils.py @@ -1,15 +1,23 @@ -import numpy as np from dataclasses import dataclass, field -from typing import Tuple -from eskf_python_utils import quaternion_product, euler_to_quat, quat_to_euler, quaternion_error, quat_norm, skew_matrix + +import numpy as np +from eskf_python_utils import ( + euler_to_quat, + quat_norm, + quat_to_euler, + quaternion_error, + quaternion_product, + skew_matrix, +) # This was the original code from the ukf_okid.py file + @dataclass class StateQuatModel: + """A class to represent the state to be estimated by the UKF. """ - A class to represent the state to be estimated by the UKF. - """ + position: np.ndarray = field(default_factory=lambda: np.zeros(3)) orientation: np.ndarray = field(default_factory=lambda: np.array([1, 0, 0, 0])) velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) @@ -18,7 +26,9 @@ class StateQuatModel: def as_vector(self) -> np.ndarray: """Returns the StateVector as a numpy array.""" - return np.concatenate([self.position, self.orientation, self.velocity, self.angular_velocity]) + return np.concatenate( + [self.position, self.orientation, self.velocity, self.angular_velocity] + ) def nu(self) -> np.ndarray: """Calculates the nu vector.""" @@ -27,11 +37,25 @@ def nu(self) -> np.ndarray: def R_q(self) -> np.ndarray: """Calculates the rotation matrix from the orientation quaternion.""" q0, q1, q2, q3 = self.orientation - R = np.array([ - [1 - 2 * q2**2 - 2 * q3**2, 2 * (q1 * q2 - q0 * q3), 2 * (q0 * q2 + q1 * q3)], - [2 * (q1 * q2 + q0 * q3), 1 - 2 * q1**2 - 2 * q3**2, 2 * (q2 * q3 - q0 * q1)], - [2 * (q1 * q3 - q0 * q2), 2 * (q0 * q1 + q2 * q3), 1 - 2 * q1**2 - 2 * q2**2] - ]) + R = np.array( + [ + [ + 1 - 2 * q2**2 - 2 * q3**2, + 2 * (q1 * q2 - q0 * q3), + 2 * (q0 * q2 + q1 * q3), + ], + [ + 2 * (q1 * q2 + q0 * q3), + 1 - 2 * q1**2 - 2 * q3**2, + 2 * (q2 * q3 - q0 * q1), + ], + [ + 2 * (q1 * q3 - q0 * q2), + 2 * (q0 * q1 + q2 * q3), + 1 - 2 * q1**2 - 2 * q2**2, + ], + ] + ) return R def fill_states(self, state: np.ndarray) -> None: @@ -41,10 +65,14 @@ def fill_states(self, state: np.ndarray) -> None: self.velocity = state[7:10] self.angular_velocity = state[10:13] - def fill_states_different_dim(self, state: np.ndarray, state_euler: np.ndarray) -> None: + def fill_states_different_dim( + self, state: np.ndarray, state_euler: np.ndarray + ) -> None: """Fills states when the state vector has different dimensions than the default state vector.""" self.position = state[0:3] + state_euler[0:3] - self.orientation = quaternion_product(state[3:7], euler_to_quat(state_euler[3:6])) + self.orientation = quaternion_product( + state[3:7], euler_to_quat(state_euler[3:6]) + ) self.velocity = state[7:10] + state_euler[6:9] self.angular_velocity = state[10:13] + state_euler[9:12] @@ -52,7 +80,9 @@ def subtract(self, other: 'StateQuatModel') -> np.ndarray: """Subtracts two StateQuatModel objects, returning the difference with Euler angles.""" new_array = np.zeros(len(self.as_vector()) - 1) new_array[:3] = self.position - other.position - new_array[3:6] = quat_to_euler(quaternion_error(self.orientation, other.orientation)) + new_array[3:6] = quat_to_euler( + quaternion_error(self.orientation, other.orientation) + ) new_array[6:9] = self.velocity - other.velocity new_array[9:12] = self.angular_velocity - other.angular_velocity @@ -92,7 +122,9 @@ def insert_weights(self, weights: np.ndarray) -> np.ndarray: """Inserts the weights into the covariance matrix.""" new_state = StateQuatModel() new_state.position = self.position - weights[:3] - new_state.orientation = quaternion_error(self.orientation, euler_to_quat(weights[3:6])) + new_state.orientation = quaternion_error( + self.orientation, euler_to_quat(weights[3:6]) + ) new_state.velocity = self.velocity - weights[6:9] new_state.angular_velocity = self.angular_velocity - weights[9:12] @@ -107,9 +139,9 @@ def add_without_quaternions(self, other: 'StateQuatModel') -> None: @dataclass class process_model: + """A class defined for a general process model. """ - A class defined for a general process model. - """ + state_vector: StateQuatModel = field(default_factory=StateQuatModel) state_vector_dot: StateQuatModel = field(default_factory=StateQuatModel) state_vector_prev: StateQuatModel = field(default_factory=StateQuatModel) @@ -119,7 +151,7 @@ class process_model: damping_linear: np.ndarray = field(default_factory=lambda: np.zeros(6)) damping_nonlinear: np.ndarray = field(default_factory=lambda: np.zeros(6)) m: float = 0.0 - inertia: np.ndarray = field(default_factory=lambda: np.zeros((3,3))) + inertia: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) r_b_bg: np.ndarray = field(default_factory=lambda: np.zeros(3)) dt: float = 0.0 integral_error_position: np.ndarray = field(default_factory=lambda: np.zeros(3)) @@ -130,22 +162,33 @@ class process_model: def R(self) -> np.ndarray: """Calculates the rotation matrix.""" nu, e_1, e_2, e_3 = self.state_vector.orientation - R = np.array([ - [1 - 2 * e_2 ** 2 - 2 * e_3 ** 2, 2 * e_1 * e_2 - 2 * nu * e_3, 2 * e_1 * e_3 + 2 * nu * e_2], - [2 * e_1 * e_2 + 2 * nu * e_3, 1 - 2 * e_1 ** 2 - 2 * e_3 ** 2, 2 * e_2 * e_3 - 2 * nu * e_1], - [2 * e_1 * e_3 - 2 * nu * e_2, 2 * e_2 * e_3 + 2 * nu * e_1, 1 - 2 * e_1 ** 2 - 2 * e_2 ** 2] - ]) + R = np.array( + [ + [ + 1 - 2 * e_2**2 - 2 * e_3**2, + 2 * e_1 * e_2 - 2 * nu * e_3, + 2 * e_1 * e_3 + 2 * nu * e_2, + ], + [ + 2 * e_1 * e_2 + 2 * nu * e_3, + 1 - 2 * e_1**2 - 2 * e_3**2, + 2 * e_2 * e_3 - 2 * nu * e_1, + ], + [ + 2 * e_1 * e_3 - 2 * nu * e_2, + 2 * e_2 * e_3 + 2 * nu * e_1, + 1 - 2 * e_1**2 - 2 * e_2**2, + ], + ] + ) return R def T(self) -> np.ndarray: """Calculates the transformation matrix.""" nu, e_1, e_2, e_3 = self.state_vector.orientation - T = 0.5 * np.array([ - [-e_1, -e_2, -e_3], - [nu, -e_3, e_2], - [e_3, nu, -e_1], - [-e_2, e_1, nu] - ]) + T = 0.5 * np.array( + [[-e_1, -e_2, -e_3], [nu, -e_3, e_2], [e_3, nu, -e_1], [-e_2, e_1, nu]] + ) return T def Crb(self) -> np.ndarray: @@ -170,15 +213,31 @@ def model_prediction(self, state: StateQuatModel) -> None: """Calculates the model of the system.""" self.state_vector = state self.state_vector_dot.position = np.dot(self.R(), self.state_vector.velocity) - self.state_vector_dot.orientation = np.dot(self.T(), self.state_vector.angular_velocity) - Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ (self.Control_input - np.dot(self.Crb(), self.state_vector.nu()) - np.dot(self.D(), self.state_vector.nu())) + self.state_vector_dot.orientation = np.dot( + self.T(), self.state_vector.angular_velocity + ) + Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ ( + self.Control_input + - np.dot(self.Crb(), self.state_vector.nu()) + - np.dot(self.D(), self.state_vector.nu()) + ) self.state_vector_dot.velocity = Nu[:3] self.state_vector_dot.angular_velocity = Nu[3:] def euler_forward(self) -> StateQuatModel: """Calculates the forward Euler integration.""" - self.state_vector.position = self.state_vector_prev.position + self.state_vector_dot.position * self.dt - self.state_vector.orientation = quat_norm(self.state_vector_prev.orientation + self.state_vector_dot.orientation * self.dt) - self.state_vector.velocity = self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt - self.state_vector.angular_velocity = self.state_vector_prev.angular_velocity + self.state_vector_dot.angular_velocity * self.dt - return self.state_vector \ No newline at end of file + self.state_vector.position = ( + self.state_vector_prev.position + self.state_vector_dot.position * self.dt + ) + self.state_vector.orientation = quat_norm( + self.state_vector_prev.orientation + + self.state_vector_dot.orientation * self.dt + ) + self.state_vector.velocity = ( + self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt + ) + self.state_vector.angular_velocity = ( + self.state_vector_prev.angular_velocity + + self.state_vector_dot.angular_velocity * self.dt + ) + return self.state_vector diff --git a/navigation/ukf_okid/ukf_python/rest.py b/navigation/ukf_okid/ukf_python/rest.py index df7392bd4..52cffb2df 100644 --- a/navigation/ukf_okid/ukf_python/rest.py +++ b/navigation/ukf_okid/ukf_python/rest.py @@ -1,28 +1,33 @@ def mean_set(set_points: list[StateQuat], weights: np.ndarray = None) -> np.ndarray: - """ - Function that calculates the mean of a set of points + """Function that calculates the mean of a set of points """ n = len(set_points[0].as_vector()) - 1 mean_value = StateQuat() if weights is None: for i in range(2 * n + 1): - weight_temp_list = (1/ (2 * n + 1)) * np.ones(2 * n + 1) + weight_temp_list = (1 / (2 * n + 1)) * np.ones(2 * n + 1) mean_value.add_without_quaternions(weight_temp_list[i] * set_points[i]) - - mean_value.orientation = iterative_quaternion_mean_statequat(set_points, weight_temp_list) - + + mean_value.orientation = iterative_quaternion_mean_statequat( + set_points, weight_temp_list + ) + else: for i in range(2 * n + 1): mean_value.add_without_quaternions(weights[i] * set_points[i]) - mean_value.orientation = iterative_quaternion_mean_statequat(set_points, weights) - + mean_value.orientation = iterative_quaternion_mean_statequat( + set_points, weights + ) + return mean_value.as_vector() -def mean_measurement(set_points: list[MeasModel], weights: np.ndarray = None) -> np.ndarray: - """ - Function that calculates the mean of a set of points + +def mean_measurement( + set_points: list[MeasModel], weights: np.ndarray = None +) -> np.ndarray: + """Function that calculates the mean of a set of points """ n = len(set_points) mean_value = MeasModel() @@ -33,5 +38,5 @@ def mean_measurement(set_points: list[MeasModel], weights: np.ndarray = None) -> else: for i in range(n): mean_value = mean_value + (weights[i] * set_points[i]) - - return mean_value.measurement \ No newline at end of file + + return mean_value.measurement diff --git a/navigation/ukf_okid/ukf_python/ukf_okid.py b/navigation/ukf_okid/ukf_python/ukf_okid.py index 16312935a..80a7c939c 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid.py @@ -1,7 +1,6 @@ -from ukf_okid_class import * + import numpy as np -import time -import matplotlib.pyplot as plt +from ukf_okid_class import * class UKF: @@ -17,8 +16,7 @@ def __init__(self, process_model: process_model, x_0, P_0, Q, R): self.T = self.generate_T_matrix(len(P_0)) def generate_T_matrix(self, n: float) -> np.ndarray: - """ - Generates the orthonormal transformation matrix T used in the TUKF sigma point generation. + """Generates the orthonormal transformation matrix T used in the TUKF sigma point generation. Parameters: n (int): The state dimension. @@ -29,7 +27,7 @@ def generate_T_matrix(self, n: float) -> np.ndarray: T = np.zeros((n, n)) for i in range(n): - for j in range(n//2): + for j in range(n // 2): T[2 * j - 2, i - 1] = np.sqrt(2) * np.cos(((2 * j - 1) * i * np.pi) / n) T[2 * j - 1, i - 1] = np.sqrt(2) * np.sin(((2 * j - 1) * i * np.pi) / n) @@ -41,8 +39,7 @@ def generate_T_matrix(self, n: float) -> np.ndarray: return T def sigma_points(self, current_state: StateQuat) -> list[StateQuat]: - """ - Functions that generate the sigma points for the UKF + """Functions that generate the sigma points for the UKF """ n = len(current_state.covariance) @@ -60,18 +57,15 @@ def sigma_points(self, current_state: StateQuat) -> list[StateQuat]: return self.sigma_points_list - def unscented_transform(self, current_state: StateQuat) -> StateQuat: + """The unscented transform function generates the priori state estimate """ - The unscented transform function generates the priori state estimate - """ - - _ = self.sigma_points(current_state) + _ = self.sigma_points(current_state) n = len(current_state.covariance) self.y_i = [StateQuat() for _ in range(2 * n)] - for i in range(2 * n ): + for i in range(2 * n): self.process_model.model_prediction(self.sigma_points_list[i]) self.y_i[i] = self.process_model.euler_forward() @@ -82,12 +76,12 @@ def unscented_transform(self, current_state: StateQuat) -> StateQuat: state_estimate.covariance = covariance_set(self.y_i, x) return state_estimate - def measurement_update(self, current_state: StateQuat, measurement: MeasModel) -> tuple[MeasModel, np.ndarray]: - """ - Function that updates the state estimate with a measurement + def measurement_update( + self, current_state: StateQuat, measurement: MeasModel + ) -> tuple[MeasModel, np.ndarray]: + """Function that updates the state estimate with a measurement Hopefully this is the DVL or GNSS """ - n = len(current_state.covariance) z_i = [MeasModel() for _ in range(2 * n)] @@ -100,15 +94,21 @@ def measurement_update(self, current_state: StateQuat, measurement: MeasModel) - meas_update.covariance = covariance_measurement(z_i, meas_update.measurement) - cross_correlation = cross_covariance(self.y_i, current_state.as_vector(), z_i, meas_update.measurement) + cross_correlation = cross_covariance( + self.y_i, current_state.as_vector(), z_i, meas_update.measurement + ) return meas_update, cross_correlation - def posteriori_estimate(self, current_state: StateQuat, cross_correlation: np.ndarray, measurement: MeasModel, ex_measuremnt: MeasModel) -> StateQuat: - """ - Calculates the posteriori estimate using measurement and the prior estimate + def posteriori_estimate( + self, + current_state: StateQuat, + cross_correlation: np.ndarray, + measurement: MeasModel, + ex_measuremnt: MeasModel, + ) -> StateQuat: + """Calculates the posteriori estimate using measurement and the prior estimate """ - nu_k = MeasModel() nu_k.measurement = measurement.measurement - ex_measuremnt.measurement @@ -118,8 +118,12 @@ def posteriori_estimate(self, current_state: StateQuat, cross_correlation: np.nd posteriori_estimate = StateQuat() - posteriori_estimate.fill_states_different_dim(current_state.as_vector(), np.dot(K_k, nu_k.measurement)) - posteriori_estimate.covariance = current_state.covariance - np.dot(K_k, np.dot(nu_k.covariance, np.transpose(K_k))) + posteriori_estimate.fill_states_different_dim( + current_state.as_vector(), np.dot(K_k, nu_k.measurement) + ) + posteriori_estimate.covariance = current_state.covariance - np.dot( + K_k, np.dot(nu_k.covariance, np.transpose(K_k)) + ) self.process_model.state_vector_prev = posteriori_estimate diff --git a/navigation/ukf_okid/ukf_python/ukf_okid_class.py b/navigation/ukf_okid/ukf_python/ukf_okid_class.py index 4d3281260..181d1f4af 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid_class.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid_class.py @@ -1,15 +1,13 @@ from dataclasses import dataclass, field -import numpy as np - -from dataclasses import dataclass, field import numpy as np + @dataclass class StateQuat: + """A class to represent the state to be estimated by the UKF. """ - A class to represent the state to be estimated by the UKF. - """ + position: np.ndarray = field(default_factory=lambda: np.zeros(3)) orientation: np.ndarray = field(default_factory=lambda: np.array([1, 0, 0, 0])) velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) @@ -18,7 +16,9 @@ class StateQuat: def as_vector(self) -> np.ndarray: """Returns the StateVector as a numpy array.""" - return np.concatenate([self.position, self.orientation, self.velocity, self.angular_velocity]) + return np.concatenate( + [self.position, self.orientation, self.velocity, self.angular_velocity] + ) def nu(self) -> np.ndarray: """Calculates the nu vector.""" @@ -27,11 +27,25 @@ def nu(self) -> np.ndarray: def R_q(self) -> np.ndarray: """Calculates the rotation matrix from the orientation quaternion.""" q0, q1, q2, q3 = self.orientation - R = np.array([ - [1 - 2 * q2**2 - 2 * q3**2, 2 * (q1 * q2 - q0 * q3), 2 * (q0 * q2 + q1 * q3)], - [2 * (q1 * q2 + q0 * q3), 1 - 2 * q1**2 - 2 * q3**2, 2 * (q2 * q3 - q0 * q1)], - [2 * (q1 * q3 - q0 * q2), 2 * (q0 * q1 + q2 * q3), 1 - 2 * q1**2 - 2 * q2**2] - ]) + R = np.array( + [ + [ + 1 - 2 * q2**2 - 2 * q3**2, + 2 * (q1 * q2 - q0 * q3), + 2 * (q0 * q2 + q1 * q3), + ], + [ + 2 * (q1 * q2 + q0 * q3), + 1 - 2 * q1**2 - 2 * q3**2, + 2 * (q2 * q3 - q0 * q1), + ], + [ + 2 * (q1 * q3 - q0 * q2), + 2 * (q0 * q1 + q2 * q3), + 1 - 2 * q1**2 - 2 * q2**2, + ], + ] + ) return R def fill_states(self, state: np.ndarray) -> None: @@ -41,10 +55,14 @@ def fill_states(self, state: np.ndarray) -> None: self.velocity = state[7:10] self.angular_velocity = state[10:13] - def fill_states_different_dim(self, state: np.ndarray, state_euler: np.ndarray) -> None: + def fill_states_different_dim( + self, state: np.ndarray, state_euler: np.ndarray + ) -> None: """Fills states when the state vector has different dimensions than the default state vector.""" self.position = state[0:3] + state_euler[0:3] - self.orientation = quaternion_super_product(state[3:7], euler_to_quat(state_euler[3:6])) + self.orientation = quaternion_super_product( + state[3:7], euler_to_quat(state_euler[3:6]) + ) self.velocity = state[7:10] + state_euler[6:9] self.angular_velocity = state[10:13] + state_euler[9:12] @@ -62,7 +80,9 @@ def __add__(self, other: 'StateQuat') -> 'StateQuat': """Adds two StateQuat objects.""" new_state = StateQuat() new_state.position = self.position + other.position - new_state.orientation = quaternion_super_product(self.orientation, other.orientation) + new_state.orientation = quaternion_super_product( + self.orientation, other.orientation + ) new_state.velocity = self.velocity + other.velocity new_state.angular_velocity = self.angular_velocity + other.angular_velocity @@ -92,7 +112,9 @@ def insert_weights(self, weights: np.ndarray) -> np.ndarray: """Inserts the weights into the covariance matrix.""" new_state = StateQuat() new_state.position = self.position - weights[:3] - new_state.orientation = quaternion_error(self.orientation, euler_to_quat(weights[3:6])) + new_state.orientation = quaternion_error( + self.orientation, euler_to_quat(weights[3:6]) + ) new_state.velocity = self.velocity - weights[6:9] new_state.angular_velocity = self.angular_velocity - weights[9:12] @@ -104,11 +126,12 @@ def add_without_quaternions(self, other: 'StateQuat') -> None: self.velocity += other.velocity self.angular_velocity += other.angular_velocity + @dataclass class MeasModel: + """A class defined for a general measurement model. """ - A class defined for a general measurement model. - """ + measurement: np.ndarray = field(default_factory=lambda: np.zeros(3)) covariance: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) @@ -138,11 +161,12 @@ def __sub__(self, other: 'MeasModel') -> 'MeasModel': result.measurement = self.measurement - other.measurement return result + @dataclass class process_model: + """A class defined for a general process model. """ - A class defined for a general process model. - """ + state_vector: StateQuat = field(default_factory=StateQuat) state_vector_dot: StateQuat = field(default_factory=StateQuat) state_vector_prev: StateQuat = field(default_factory=StateQuat) @@ -152,7 +176,7 @@ class process_model: damping_linear: np.ndarray = field(default_factory=lambda: np.zeros(6)) damping_nonlinear: np.ndarray = field(default_factory=lambda: np.zeros(6)) m: float = 0.0 - inertia: np.ndarray = field(default_factory=lambda: np.zeros((3,3))) + inertia: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) r_b_bg: np.ndarray = field(default_factory=lambda: np.zeros(3)) dt: float = 0.0 integral_error_position: np.ndarray = field(default_factory=lambda: np.zeros(3)) @@ -163,22 +187,33 @@ class process_model: def R(self) -> np.ndarray: """Calculates the rotation matrix.""" nu, e_1, e_2, e_3 = self.state_vector.orientation - R = np.array([ - [1 - 2 * e_2 ** 2 - 2 * e_3 ** 2, 2 * e_1 * e_2 - 2 * nu * e_3, 2 * e_1 * e_3 + 2 * nu * e_2], - [2 * e_1 * e_2 + 2 * nu * e_3, 1 - 2 * e_1 ** 2 - 2 * e_3 ** 2, 2 * e_2 * e_3 - 2 * nu * e_1], - [2 * e_1 * e_3 - 2 * nu * e_2, 2 * e_2 * e_3 + 2 * nu * e_1, 1 - 2 * e_1 ** 2 - 2 * e_2 ** 2] - ]) + R = np.array( + [ + [ + 1 - 2 * e_2**2 - 2 * e_3**2, + 2 * e_1 * e_2 - 2 * nu * e_3, + 2 * e_1 * e_3 + 2 * nu * e_2, + ], + [ + 2 * e_1 * e_2 + 2 * nu * e_3, + 1 - 2 * e_1**2 - 2 * e_3**2, + 2 * e_2 * e_3 - 2 * nu * e_1, + ], + [ + 2 * e_1 * e_3 - 2 * nu * e_2, + 2 * e_2 * e_3 + 2 * nu * e_1, + 1 - 2 * e_1**2 - 2 * e_2**2, + ], + ] + ) return R def T(self) -> np.ndarray: """Calculates the transformation matrix.""" nu, e_1, e_2, e_3 = self.state_vector.orientation - T = 0.5 * np.array([ - [-e_1, -e_2, -e_3], - [nu, -e_3, e_2], - [e_3, nu, -e_1], - [-e_2, e_1, nu] - ]) + T = 0.5 * np.array( + [[-e_1, -e_2, -e_3], [nu, -e_3, e_2], [e_3, nu, -e_1], [-e_2, e_1, nu]] + ) return T def Crb(self) -> np.ndarray: @@ -203,138 +238,157 @@ def model_prediction(self, state: StateQuat) -> None: """Calculates the model of the system.""" self.state_vector = state self.state_vector_dot.position = np.dot(self.R(), self.state_vector.velocity) - self.state_vector_dot.orientation = np.dot(self.T(), self.state_vector.angular_velocity) - Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ (self.Control_input - np.dot(self.Crb(), self.state_vector.nu()) - np.dot(self.D(), self.state_vector.nu())) + self.state_vector_dot.orientation = np.dot( + self.T(), self.state_vector.angular_velocity + ) + Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ ( + self.Control_input + - np.dot(self.Crb(), self.state_vector.nu()) + - np.dot(self.D(), self.state_vector.nu()) + ) self.state_vector_dot.velocity = Nu[:3] self.state_vector_dot.angular_velocity = Nu[3:] def euler_forward(self) -> StateQuat: """Calculates the forward Euler integration.""" - self.state_vector.position = self.state_vector_prev.position + self.state_vector_dot.position * self.dt - self.state_vector.orientation = quat_norm(self.state_vector_prev.orientation + self.state_vector_dot.orientation * self.dt) - self.state_vector.velocity = self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt - self.state_vector.angular_velocity = self.state_vector_prev.angular_velocity + self.state_vector_dot.angular_velocity * self.dt + self.state_vector.position = ( + self.state_vector_prev.position + self.state_vector_dot.position * self.dt + ) + self.state_vector.orientation = quat_norm( + self.state_vector_prev.orientation + + self.state_vector_dot.orientation * self.dt + ) + self.state_vector.velocity = ( + self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt + ) + self.state_vector.angular_velocity = ( + self.state_vector_prev.angular_velocity + + self.state_vector_dot.angular_velocity * self.dt + ) return self.state_vector + def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: - """ - Converts Euler angles to a quaternion + """Converts Euler angles to a quaternion """ psi, theta, phi = euler_angles c_psi = np.cos(psi / 2) - s_psi = np.sin(psi / 2) + s_psi = np.sin(psi / 2) c_theta = np.cos(theta / 2) s_theta = np.sin(theta / 2) c_phi = np.cos(phi / 2) s_phi = np.sin(phi / 2) - quat = np.array([ - c_psi * c_theta * c_phi + s_psi * s_theta * s_phi, - c_psi * c_theta * s_phi - s_psi * s_theta * c_phi, - s_psi * c_theta * s_phi + c_psi * s_theta * c_phi, - s_psi * c_theta * c_phi - c_psi * s_theta * s_phi - ]) + quat = np.array( + [ + c_psi * c_theta * c_phi + s_psi * s_theta * s_phi, + c_psi * c_theta * s_phi - s_psi * s_theta * c_phi, + s_psi * c_theta * s_phi + c_psi * s_theta * c_phi, + s_psi * c_theta * c_phi - c_psi * s_theta * s_phi, + ] + ) return quat + def quat_to_euler(quat: np.ndarray) -> np.ndarray: - """ - Converts a quaternion to Euler angles + """Converts a quaternion to Euler angles """ nu, eta_1, eta_2, eta_3 = quat - phi = np.arctan2(2*(eta_2 * eta_3 + nu * eta_1), 1 - 2 * (eta_1 ** 2 + eta_2 ** 2)) + phi = np.arctan2(2 * (eta_2 * eta_3 + nu * eta_1), 1 - 2 * (eta_1**2 + eta_2**2)) theta = -np.arcsin(2 * (eta_1 * eta_3 - nu * eta_2)) - psi = np.arctan2(2 * (nu * eta_3 + eta_1 * eta_2), 1 - 2 * (eta_2 ** 2 + eta_3 ** 2)) + psi = np.arctan2(2 * (nu * eta_3 + eta_1 * eta_2), 1 - 2 * (eta_2**2 + eta_3**2)) return np.array([phi, theta, psi]) + def quat_norm(quat: np.ndarray) -> np.ndarray: + """Function that normalizes a quaternion """ - Function that normalizes a quaternion - """ - quat = quat / np.linalg.norm(quat) return quat + def skew_symmetric(vector: np.ndarray) -> np.ndarray: - """Calculates the skew symmetric matrix of a vector. + """Calculates the skew symmetric matrix of a vector. - Args: - vector (np.ndarray): The vector. + Args: + vector (np.ndarray): The vector. + + Returns: + np.ndarray: The skew symmetric matrix. + """ + return np.array( + [ + [0, -vector[2], vector[1]], + [vector[2], 0, -vector[0]], + [-vector[1], vector[0], 0], + ] + ) - Returns: - np.ndarray: The skew symmetric matrix. - """ - return np.array( - [ - [0, -vector[2], vector[1]], - [vector[2], 0, -vector[0]], - [-vector[1], vector[0], 0], - ] - ) def quaternion_super_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: - """Calculates the quaternion super product of two quaternions. + """Calculates the quaternion super product of two quaternions. - Args: - q1 (np.ndarray): The first quaternion. - q2 (np.ndarray): The second quaternion. + Args: + q1 (np.ndarray): The first quaternion. + q2 (np.ndarray): The second quaternion. - Returns: - np.ndarray: The quaternion super product. - """ - eta_0, e_0_x, e_0_y, e_0_z = q1 - eta_1, e_1_x, e_1_y, e_1_z = q2 + Returns: + np.ndarray: The quaternion super product. + """ + eta_0, e_0_x, e_0_y, e_0_z = q1 + eta_1, e_1_x, e_1_y, e_1_z = q2 + + e_0 = np.array([e_0_x, e_0_y, e_0_z]) + e_1 = np.array([e_1_x, e_1_y, e_1_z]) - e_0 = np.array([e_0_x, e_0_y, e_0_z]) - e_1 = np.array([e_1_x, e_1_y, e_1_z]) + eta_new = eta_0 * eta_1 - (e_0_x * e_1_x + e_0_y * e_1_y + e_0_z * e_1_z) + nu_new = e_1 * eta_0 + e_0 * eta_1 + np.dot(skew_symmetric(e_0), e_1) - eta_new = eta_0 * eta_1 - (e_0_x * e_1_x + e_0_y * e_1_y + e_0_z * e_1_z) - nu_new = e_1 * eta_0 + e_0 * eta_1 + np.dot(skew_symmetric(e_0), e_1) + q_new = quat_norm(np.array([eta_new, nu_new[0], nu_new[1], nu_new[2]])) - q_new = quat_norm(np.array([eta_new, nu_new[0], nu_new[1], nu_new[2]])) + return q_new - return q_new def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: + """Calculates the error between two quaternions """ - Calculates the error between two quaternions - """ - quat_2_inv = np.array([quat_2[0], -quat_2[1], -quat_2[2], -quat_2[3]]) error_quat = quaternion_super_product(quat_1, quat_2_inv) return error_quat -def iterative_quaternion_mean_statequat(state_list: list[StateQuat], tol: float = 1e-6, max_iter: int = 100) -> np.ndarray: - """ - Computes the weighted mean of the quaternion orientations from a list of StateQuat objects + +def iterative_quaternion_mean_statequat( + state_list: list[StateQuat], tol: float = 1e-6, max_iter: int = 100 +) -> np.ndarray: + """Computes the weighted mean of the quaternion orientations from a list of StateQuat objects using an iterative approach, without requiring the caller to manually extract the quaternion. - + Parameters: state_list (list[StateQuat]): List of StateQuat objects. weights (np.ndarray): Weights for each state. tol (float): Convergence tolerance. max_iter (int): Maximum number of iterations. - + Returns: np.ndarray: The averaged quaternion as a 4-element numpy array. """ - sigma_quats = [state.orientation for state in state_list] n = len(state_list) mean_q = sigma_quats[0].copy() - + for _ in range(max_iter): weighted_error_vectors = [] for i, q in enumerate(sigma_quats): mean_q_conj = np.array([mean_q[0], -mean_q[1], -mean_q[2], -mean_q[3]]) e = quaternion_super_product(q, mean_q_conj) - + e0_clipped = np.clip(e[0], -1.0, 1.0) angle = 2 * np.arccos(e0_clipped) if np.abs(angle) < 1e-8: @@ -342,28 +396,32 @@ def iterative_quaternion_mean_statequat(state_list: list[StateQuat], tol: float else: error_vec = (angle / np.sin(angle / 2)) * e[1:4] weighted_error_vectors.append(error_vec) - + error_avg = (1 / n) * np.sum(weighted_error_vectors, axis=0) if np.linalg.norm(error_avg) < tol: break - + error_norm = np.linalg.norm(error_avg) if error_norm > 0: - delta_q = np.array([np.cos(error_norm / 2), - *(np.sin(error_norm / 2) * (error_avg / error_norm))]) + delta_q = np.array( + [ + np.cos(error_norm / 2), + *(np.sin(error_norm / 2) * (error_avg / error_norm)), + ] + ) else: delta_q = np.array([1.0, 0.0, 0.0, 0.0]) mean_q = quaternion_super_product(delta_q, mean_q) mean_q = quat_norm(mean_q) - + return mean_q + def mean_set(set_points: list[StateQuat]) -> np.ndarray: - """ - Functio calculates the mean vector of a set of points - - Args: + """Function calculates the mean vector of a set of points + + Args: set_points (list[StateQuat]): List of StateQuat objects Returns: @@ -374,30 +432,30 @@ def mean_set(set_points: list[StateQuat]) -> np.ndarray: for state in set_points: mean_value.add_without_quaternions(state) - - mean_value = (1 / (n)) * mean_value + + mean_value = (1 / (n)) * mean_value mean_value.orientation = iterative_quaternion_mean_statequat(set_points) return mean_value.as_vector() + def mean_measurement(set_points: list[MeasModel]) -> np.ndarray: - """ - Function that calculates the mean of a set of points + """Function that calculates the mean of a set of points """ n = len(set_points) mean_value = MeasModel() for state in set_points: mean_value = mean_value + state - + mean_value = (1 / n) * mean_value return mean_value.measurement + def covariance_set(set_points: list[StateQuat], mean: np.ndarray) -> np.ndarray: - """ - Function that calculates the covariance of a set of points + """Function that calculates the covariance of a set of points """ n = len(set_points) covariance = np.zeros(set_points[0].covariance.shape) @@ -410,23 +468,25 @@ def covariance_set(set_points: list[StateQuat], mean: np.ndarray) -> np.ndarray: for state in set_points: q = state.orientation diff_q = quaternion_error(q, mean_q) - + e0_clipped = np.clip(diff_q[0], -1.0, 1.0) angle = 2.0 * np.arccos(e0_clipped) if abs(angle) < 1e-8: e_vec = np.zeros(3) else: - e_vec = (angle / np.sin(angle/2)) * diff_q[1:4] + e_vec = (angle / np.sin(angle / 2)) * diff_q[1:4] - covariance += np.outer(state.subtract(mean_quat, e_vec), state.subtract(mean_quat, e_vec)) + covariance += np.outer( + state.subtract(mean_quat, e_vec), state.subtract(mean_quat, e_vec) + ) covariance = (1 / (n)) * covariance return covariance + def covariance_measurement(set_points: list[MeasModel], mean: np.ndarray) -> np.ndarray: - """ - Function that calculates the covariance of a set of points + """Function that calculates the covariance of a set of points """ n = len(set_points) co_size = len(set_points[0].measurement) @@ -443,9 +503,14 @@ def covariance_measurement(set_points: list[MeasModel], mean: np.ndarray) -> np. return covariance -def cross_covariance(set_y: list[StateQuat], mean_y: np.ndarray, set_z: list[MeasModel], mean_z: np.ndarray) -> np.ndarray: - """ - Calculates the cross covariance between the measurement and state prediction + +def cross_covariance( + set_y: list[StateQuat], + mean_y: np.ndarray, + set_z: list[MeasModel], + mean_z: np.ndarray, +) -> np.ndarray: + """Calculates the cross covariance between the measurement and state prediction """ n = len(set_y) @@ -458,16 +523,18 @@ def cross_covariance(set_y: list[StateQuat], mean_y: np.ndarray, set_z: list[Mea for i in range(n): q = set_y[i].orientation diff_q = quaternion_error(q, mean_q) - + e0_clipped = np.clip(diff_q[0], -1.0, 1.0) angle = 2.0 * np.arccos(e0_clipped) if abs(angle) < 1e-8: e_vec = np.zeros(3) else: - e_vec = (angle / np.sin(angle/2)) * diff_q[1:4] + e_vec = (angle / np.sin(angle / 2)) * diff_q[1:4] + + cross_covariance += np.outer( + set_y[i].subtract(mean_quat, e_vec), set_z[i].measurement - mean_z + ) - cross_covariance += np.outer(set_y[i].subtract(mean_quat, e_vec), set_z[i].measurement - mean_z) - cross_covariance = (1 / n) * cross_covariance return cross_covariance diff --git a/navigation/ukf_okid/ukf_python/ukf_test.py b/navigation/ukf_okid/ukf_python/ukf_test.py index 3c197ed63..cebb53ac6 100644 --- a/navigation/ukf_okid/ukf_python/ukf_test.py +++ b/navigation/ukf_okid/ukf_python/ukf_test.py @@ -1,27 +1,28 @@ -from ukf_okid import UKF -from ukf_okid_class import StateQuat, process_model, MeasModel -import numpy as np import time -import matplotlib.pyplot as plt -from ukf_utils import print_StateQuat_list, print_StateQuat -from ukf_okid_class import quaternion_super_product, quat_to_euler, mean_set, covariance_set +import matplotlib.pyplot as plt +import numpy as np +from ukf_okid import UKF +from ukf_okid_class import ( + MeasModel, + StateQuat, + process_model, + quat_to_euler, + quaternion_super_product, +) def add_quaternion_noise(q, noise_std): - noise = np.random.normal(0, noise_std, 3) theta = np.linalg.norm(noise) if theta > 0: - axis = noise / theta - q_noise = np.hstack((np.cos(theta/2), np.sin(theta/2) * axis)) + q_noise = np.hstack((np.cos(theta / 2), np.sin(theta / 2) * axis)) else: - q_noise = np.array([1.0, 0.0, 0.0, 0.0]) q_new = quaternion_super_product(q, q_noise) @@ -30,7 +31,6 @@ def add_quaternion_noise(q, noise_std): if __name__ == '__main__': - # Create initial state vector and covariance matrix. x0 = np.zeros(13) x0[0:3] = [0.3, 0.3, 0.3] @@ -38,20 +38,22 @@ def add_quaternion_noise(q, noise_std): x0[7:10] = [0.2, 0.2, 0.2] dt = 0.01 R = (0.01) * np.eye(3) - + Q = 0.00015 * np.eye(12) P0 = np.eye(12) * 0.0001 model = process_model() model.dt = 0.01 - model.mass_interia_matrix = np.array([ - [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] - ]) + model.mass_interia_matrix = np.array( + [ + [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], + ] + ) model.m = 30.0 model.r_b_bg = np.array([0.01, 0.0, 0.02]) model.inertia = np.diag([0.68, 3.32, 3.34]) @@ -61,14 +63,16 @@ def add_quaternion_noise(q, noise_std): model_ukf = process_model() model_ukf.dt = 0.01 - model_ukf.mass_interia_matrix = np.array([ - [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - [0.6, 0.3, 0.0, 0.0, 0.0, 3.34] - ]) + model_ukf.mass_interia_matrix = np.array( + [ + [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], + ] + ) model_ukf.m = 30.0 model_ukf.r_b_bg = np.array([0.01, 0.0, 0.02]) model_ukf.inertia = np.diag([0.68, 3.32, 3.34]) @@ -101,7 +105,7 @@ def add_quaternion_noise(q, noise_std): measurment_model = MeasModel() measurment_model.measurement = np.array([0.0, 0.0, 0.0]) - measurment_model.covariance = R + measurment_model.covariance = R # Initialize arrays to store the results positions = np.zeros((num_steps, 3)) @@ -129,7 +133,16 @@ def add_quaternion_noise(q, noise_std): elapsed_times = [] - u = lambda t: np.array([2 * np.sin(1 * t), 2 * np.sin(1 * t), 2 * np.sin(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t), 0.2 * np.cos(1 * t)]) + u = lambda t: np.array( + [ + 2 * np.sin(1 * t), + 2 * np.sin(1 * t), + 2 * np.sin(1 * t), + 0.2 * np.cos(1 * t), + 0.2 * np.cos(1 * t), + 0.2 * np.cos(1 * t), + ] + ) # Run the simulation for step in range(num_steps): @@ -142,10 +155,18 @@ def add_quaternion_noise(q, noise_std): new_state = model.euler_forward() # Adding noise in the state vector - estimated_state.position = estimated_state.position # + np.random.normal(0, 0.01, 3) - estimated_state.orientation = estimated_state.orientation #add_quaternion_noise(estimated_state.orientation, 0.01) - estimated_state.velocity = estimated_state.velocity # + np.random.normal(0, 0.01, 3) - estimated_state.angular_velocity = estimated_state.angular_velocity # + np.random.normal(0, 0.01, 3) + estimated_state.position = ( + estimated_state.position + ) # + np.random.normal(0, 0.01, 3) + estimated_state.orientation = ( + estimated_state.orientation + ) # add_quaternion_noise(estimated_state.orientation, 0.01) + estimated_state.velocity = ( + estimated_state.velocity + ) # + np.random.normal(0, 0.01, 3) + estimated_state.angular_velocity = ( + estimated_state.angular_velocity + ) # + np.random.normal(0, 0.01, 3) start_time = time.time() estimated_state = ukf.unscented_transform(estimated_state) @@ -155,10 +176,15 @@ def add_quaternion_noise(q, noise_std): elapsed_times.append(elapsed_time) if step % 20 == 0: - measurment_model.measurement = new_state.velocity # + np.random.normal(0, 0.01, 3) - meas_update, covariance_matrix = ukf.measurement_update(estimated_state, measurment_model) - estimated_state = ukf.posteriori_estimate(estimated_state, covariance_matrix, measurment_model, meas_update) - + measurment_model.measurement = ( + new_state.velocity + ) # + np.random.normal(0, 0.01, 3) + meas_update, covariance_matrix = ukf.measurement_update( + estimated_state, measurment_model + ) + estimated_state = ukf.posteriori_estimate( + estimated_state, covariance_matrix, measurment_model, meas_update + ) positions[step, :] = new_state.position orientations[step, :] = quat_to_euler(new_state.orientation) @@ -169,7 +195,7 @@ def add_quaternion_noise(q, noise_std): orientations_est[step, :] = quat_to_euler(estimated_state.orientation) velocities_est[step, :] = estimated_state.velocity angular_velocities_est[step, :] = estimated_state.angular_velocity - + # Update the state for the next iteration model.state_vector_prev = new_state @@ -294,4 +320,4 @@ def add_quaternion_noise(q, noise_std): plt.legend() plt.tight_layout() - plt.show() \ No newline at end of file + plt.show() diff --git a/navigation/ukf_okid/ukf_python/ukf_utils.py b/navigation/ukf_okid/ukf_python/ukf_utils.py index ad5871567..da56a7dfc 100644 --- a/navigation/ukf_okid/ukf_python/ukf_utils.py +++ b/navigation/ukf_okid/ukf_python/ukf_utils.py @@ -1,19 +1,21 @@ + import numpy as np -from dataclasses import dataclass from ukf_okid_class import StateQuat -def print_StateQuat_list(state_list: list[StateQuat], name="StateQuat List", print_covariance=True): - """ - Custom print function to print a list of StateQuat objects in a formatted form. + +def print_StateQuat_list( + state_list: list[StateQuat], name="StateQuat List", print_covariance=True +): + """Custom print function to print a list of StateQuat objects in a formatted form. """ print(f"{name}:") for i, state in enumerate(state_list): print(f"Index {i}:") print_StateQuat(state, f"StateQuat {i}", print_covariance) + def print_StateQuat(state: StateQuat, name="StateQuat", print_covariance=True): - """ - Custom print function to print StateQuat objects in a formatted form. + """Custom print function to print StateQuat objects in a formatted form. """ print(f"{name}:") print(f" Position: {state.position}") @@ -24,9 +26,9 @@ def print_StateQuat(state: StateQuat, name="StateQuat", print_covariance=True): if print_covariance: print_matrix(state.covariance, "Covariance") + def print_matrix(matrix, name="Matrix"): - """ - Custom print function to print matrices in a formatted form. + """Custom print function to print matrices in a formatted form. """ print(f"{name}: {matrix.shape}") if isinstance(matrix, np.ndarray): From 9b44fce6228741339964ced4b14f0bba47c4d774 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Thu, 3 Apr 2025 19:31:45 +0200 Subject: [PATCH 13/30] refactor: remove python eskf --- navigation/eskf_python/CMakeLists.txt | 33 -- navigation/eskf_python/README.md | 0 .../eskf_python/config/eskf_python.yaml | 3 - .../eskf_python/eskf_python/__init__.py | 0 .../eskf_python/eskf_python_class.py | 196 ---------- .../eskf_python/eskf_python_filter.py | 295 --------------- .../eskf_python/eskf_python_node.py | 151 -------- .../eskf_python/eskf_python_utils.py | 148 -------- .../eskf_python/eskf_python/eskf_test.py | 358 ------------------ .../eskf_python/eskf_test_utils.py | 243 ------------ navigation/eskf_python/launch/eskf.launch.py | 22 -- navigation/eskf_python/package.xml | 23 -- navigation/ukf_okid/ukf_python/rest.py | 6 +- navigation/ukf_okid/ukf_python/ukf_okid.py | 10 +- .../ukf_okid/ukf_python/ukf_okid_class.py | 33 +- navigation/ukf_okid/ukf_python/ukf_utils.py | 10 +- 16 files changed, 19 insertions(+), 1512 deletions(-) delete mode 100644 navigation/eskf_python/CMakeLists.txt delete mode 100644 navigation/eskf_python/README.md delete mode 100644 navigation/eskf_python/config/eskf_python.yaml delete mode 100644 navigation/eskf_python/eskf_python/__init__.py delete mode 100644 navigation/eskf_python/eskf_python/eskf_python_class.py delete mode 100644 navigation/eskf_python/eskf_python/eskf_python_filter.py delete mode 100644 navigation/eskf_python/eskf_python/eskf_python_node.py delete mode 100644 navigation/eskf_python/eskf_python/eskf_python_utils.py delete mode 100644 navigation/eskf_python/eskf_python/eskf_test.py delete mode 100644 navigation/eskf_python/eskf_python/eskf_test_utils.py delete mode 100644 navigation/eskf_python/launch/eskf.launch.py delete mode 100644 navigation/eskf_python/package.xml diff --git a/navigation/eskf_python/CMakeLists.txt b/navigation/eskf_python/CMakeLists.txt deleted file mode 100644 index b4fc9118c..000000000 --- a/navigation/eskf_python/CMakeLists.txt +++ /dev/null @@ -1,33 +0,0 @@ -cmake_minimum_required(VERSION 3.8) -project(eskf_python) - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -find_package(ament_cmake_python REQUIRED) -find_package(rclpy REQUIRED) -find_package(vortex_msgs REQUIRED) -find_package(geometry_msgs REQUIRED) - -ament_python_install_package(${PROJECT_NAME}) - -install(DIRECTORY - launch - config - DESTINATION share/${PROJECT_NAME} -) - -install(PROGRAMS - eskf_python/eskf_python_node.py - DESTINATION lib/${PROJECT_NAME} -) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - find_package(ament_cmake_pytest REQUIRED) - set(ament_cmake_copyright_FOUND TRUE) - set(ament_cmake_cpplint_FOUND TRUE) -endif() - -ament_package() diff --git a/navigation/eskf_python/README.md b/navigation/eskf_python/README.md deleted file mode 100644 index e69de29bb..000000000 diff --git a/navigation/eskf_python/config/eskf_python.yaml b/navigation/eskf_python/config/eskf_python.yaml deleted file mode 100644 index 0d80b90df..000000000 --- a/navigation/eskf_python/config/eskf_python.yaml +++ /dev/null @@ -1,3 +0,0 @@ -/**: - ros__parameters: - eskf_python_node: diff --git a/navigation/eskf_python/eskf_python/__init__.py b/navigation/eskf_python/eskf_python/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/navigation/eskf_python/eskf_python/eskf_python_class.py b/navigation/eskf_python/eskf_python/eskf_python_class.py deleted file mode 100644 index 65d41425d..000000000 --- a/navigation/eskf_python/eskf_python/eskf_python_class.py +++ /dev/null @@ -1,196 +0,0 @@ -from dataclasses import dataclass, field - -import numpy as np -from eskf_python_utils import quaternion_error - - -@dataclass -class StateQuat: - position: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Position vector (x, y, z) - velocity: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Velocity vector (u, v, w) - orientation: np.ndarray = field( - default_factory=lambda: np.array([1, 0, 0, 0]) - ) # Orientation quaternion (w, x, y, z) - acceleration_bias: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Acceleration bias vector (b_ax, b_ay, b_az) - gyro_bias: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Gyro bias vector (b_gx, b_gy, b_gz) - g: np.ndarray = field(default_factory=lambda: np.array([0, 0, 0])) # Gravity vector - - def as_vector(self) -> np.ndarray: - """Returns the state vector as a numpy array. - - Returns: - np.ndarray: The state vector. - """ - return np.concatenate( - [ - self.position, - self.velocity, - self.orientation, - self.acceleration_bias, - self.gyro_bias, - self.g, - ] - ) - - def fill_states(self, state: np.ndarray) -> None: - """Fills the state vector with the values from a numpy array. - - Args: - state (np.ndarray): The state vector. - """ - self.position = state[0:3] - self.velocity = state[3:6] - self.orientation = state[6:10] - self.acceleration_bias = state[10:13] - self.gyro_bias = state[13:16] - self.g = state[16:19] - - def R_q(self) -> np.ndarray: - """Calculates the rotation matrix from the orientation quaternion. - - Returns: - np.ndarray: The rotation matrix. - """ - q0, q1, q2, q3 = self.orientation - R = np.array( - [ - [ - 1 - 2 * q2**2 - 2 * q3**2, - 2 * (q1 * q2 - q0 * q3), - 2 * (q0 * q2 + q1 * q3), - ], - [ - 2 * (q1 * q2 + q0 * q3), - 1 - 2 * q1**2 - 2 * q3**2, - 2 * (q2 * q3 - q0 * q1), - ], - [ - 2 * (q1 * q3 - q0 * q2), - 2 * (q0 * q1 + q2 * q3), - 1 - 2 * q1**2 - 2 * q2**2, - ], - ] - ) - - return R - - def __sub__(self, other: 'StateQuat') -> 'StateQuat': - """Subtracts the values of two state vectors. - - Args: - other (StateQuat): The state vector to subtract. - - Returns: - np.ndarray: The difference between the two state vectors. - """ - result = StateQuat() - result.position = self.position - other.position - result.velocity = self.velocity - other.velocity - result.orientation = quaternion_error(self.orientation, other.orientation) - result.acceleration_bias = self.acceleration_bias - other.acceleration_bias - result.gyro_bias = self.gyro_bias - other.gyro_bias - result.g = self.g - other.g - - return result - - -@dataclass -class StateEuler: - position: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Position vector (x, y, z) - velocity: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Velocity vector (u, v, w) - orientation: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Orientation angles (roll, pitch, yaw) - acceleration_bias: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Acceleration bias vector (b_ax, b_ay, b_az) - gyro_bias: np.ndarray = field( - default_factory=lambda: np.zeros(3) - ) # Gyro bias vector (b_gx, b_gy, b_gz) - g: np.ndarray = field( - default_factory=lambda: np.array([0, 0, 9.81]) - ) # Gravity vector - covariance: np.ndarray = field( - default_factory=lambda: np.zeros((18, 18)) - ) # Covariance matrix - - def as_vector(self) -> np.ndarray: - """Returns the state vector as a numpy array. - - Returns: - np.ndarray: The state vector. - """ - return np.concatenate( - [ - self.position, - self.velocity, - self.orientation, - self.acceleration_bias, - self.gyro_bias, - self.g, - ] - ) - - def fill_states(self, state: np.ndarray) -> None: - """Fills the state vector with the values from a numpy array. - - Args: - state (np.ndarray): The state vector. - """ - self.position = state[0:3] - self.velocity = state[3:6] - self.orientation = state[6:9] - self.acceleration_bias = state[9:12] - self.gyro_bias = state[12:15] - self.g = state[15:18] - - def copy_state(self, wanted_state: 'StateEuler') -> None: - """Copies the state from a StateVector object into the current StateVector object. - - Args: - wanted_state (StateVector_euler): The quaternion state to copy from. - """ - self.position = wanted_state.position - self.velocity = wanted_state.velocity - self.orientation = wanted_state.orientation - self.acceleration_bias = wanted_state.acceleration_bias - self.gyro_bias = wanted_state.gyro_bias - - -@dataclass -class MeasurementModel: - measurement: np.ndarray = field(default_factory=lambda: np.zeros(6)) - measurement_covariance: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) - - def H(self) -> np.ndarray: - """Calculates the measurement matrix. - - Returns: - np.ndarray: The measurement matrix. - """ - H = np.zeros((3, 15)) - - H[0:3, 3:6] = np.eye(3) - - return H - - -@dataclass -class Measurement: - acceleration: np.ndarray = field(default_factory=lambda: np.zeros(3)) - angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) - aiding: np.ndarray = field(default_factory=lambda: np.zeros(3)) - - aiding_covariance: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) diff --git a/navigation/eskf_python/eskf_python/eskf_python_filter.py b/navigation/eskf_python/eskf_python/eskf_python_filter.py deleted file mode 100644 index fac3c8526..000000000 --- a/navigation/eskf_python/eskf_python/eskf_python_filter.py +++ /dev/null @@ -1,295 +0,0 @@ -# from dataclasses import dataclass -from typing import Tuple - -import numpy as np -from eskf_python_class import Measurement, StateEuler, StateQuat -from eskf_python_utils import ( - angle_axis_to_quaternion, - euler_to_quat, - quaternion_product, - skew_matrix, -) -from scipy.linalg import block_diag, expm - - -class ESKF: - def __init__( - self, Q: np.ndarray, P0, nom_state: StateQuat, p_accBias, p_gyroBias, dt - ): - self.Q = Q - self.dt = dt - self.nom_state = nom_state - self.error_state = StateEuler() - self.error_state.covariance = P0 - self.p_accBias = p_accBias - self.p_gyroBias = p_gyroBias - - def Q_delta_theta(self) -> np.ndarray: - """Calculates the Q_delta_theta matrix. - See Joan Solà. Quaternion kinematics for the error-state Kalman filter. - chapter: 6.1.1 eq. 281 - """ - qw, qx, qy, qz = self.nom_state.orientation - - Q_delta_theta = 0.5 * np.array( - [ - [-qx, -qy, -qz], - [qw, -qz, qy], - [qz, qw, -qx], - [-qy, qx, qw], - ] - ) - - return Q_delta_theta - - def Hx(self) -> np.ndarray: - """Computes the true-state measurement Jacobian for the measurement - h(x) = R(q) * velocity, - where: - - R(q) is the rotation matrix from the quaternion (q, q, q, q) with q as the scalar part, - - velocity is a 3-vector. - - The state is assumed to be ordered as: - [position (3), velocity (3), quaternion (4), ...] (total length 19). - - The Jacobian Hx is a 3x19 matrix with nonzero blocks: - - Columns 3:6 (velocity): R(q) - - Columns 6:10 (quaternion): - """ - q = self.nom_state.orientation # shape (4,) - v = self.nom_state.velocity # shape (3,) - q0, q1, q2, q3 = q - v1, v2, v3 = v - - R = self.nom_state.R_q().transpose() # shape (3, 3) - - dhdq0 = 2 * np.array( - [ - q0 * v1 - q3 * v2 + q2 * v3, - q3 * v1 + q0 * v2 - q1 * v3, - -q2 * v1 + q1 * v2 + q0 * v3, - ] - ) - - dhdq1 = 2 * np.array( - [ - q1 * v1 + q2 * v2 + q3 * v3, - q2 * v1 - q1 * v2 - q0 * v3, - q3 * v1 + q0 * v2 - q1 * v3, - ] - ) - - dhdq2 = 2 * np.array( - [ - -q2 * v1 + q1 * v2 + q0 * v3, - q1 * v1 + q2 * v2 + q3 * v3, - -q0 * v1 + q3 * v2 - q2 * v3, - ] - ) - - dhdq3 = 2 * np.array( - [ - -q3 * v1 - q0 * v2 + q1 * v3, - q0 * v1 - q3 * v2 + q2 * v3, - q1 * v1 + q2 * v2 + q3 * v3, - ] - ) - - dHdq = np.column_stack((dhdq0, dhdq1, dhdq2, dhdq3)) # shape (3, 4) - - Hx = np.zeros((3, 19)) - Hx[:, 3:6] = R - Hx[:, 6:10] = dHdq - - return Hx - - def H(self) -> np.ndarray: - """Calculates the measurement matrix. - - Returns: - np.ndarray: The measurement matrix. - """ - X_deltax = block_diag(np.eye(6), self.Q_delta_theta(), np.eye(9)) - - H = self.Hx() @ X_deltax - - return H - - def h(self) -> np.ndarray: - """Calculates the measurement model. - - Returns: - np.ndarray: The measurement model. - """ - return self.nom_state.R_q() @ self.nom_state.velocity - - def nominal_state_discrete(self, imu_data: Measurement) -> None: - """Calculates the next nominal state using the discrete-time process model defined in: - Joan Solà. Quaternion kinematics for the error-state Kalman filter. - Chapter: 5.4.1 The nominal state kinematics - - Args: - imu_data (np.ndarray): The IMU data. - """ - # Rectify measurements. - acc_rect = imu_data.acceleration - self.nom_state.acceleration_bias - gyro_rect = imu_data.angular_velocity - self.nom_state.gyro_bias - - R = self.nom_state.R_q() - - self.nom_state.position = ( - self.nom_state.position - + self.nom_state.velocity * self.dt - + 0.5 * (R @ acc_rect + self.nom_state.g) * self.dt**2 - ) - self.nom_state.velocity = ( - self.nom_state.velocity + (R @ acc_rect + self.nom_state.g) * self.dt - ) - self.nom_state.orientation = quaternion_product( - self.nom_state.orientation, angle_axis_to_quaternion(gyro_rect * self.dt) - ) - self.nom_state.acceleration_bias = self.nom_state.acceleration_bias - self.nom_state.gyro_bias = self.nom_state.gyro_bias - self.nom_state.g = self.nom_state.g - - def van_loan_discretization(self, A_c, G_c) -> Tuple[np.ndarray, np.ndarray]: - """Calculates the Van Loan discretization of a continuous-time system. - - Args: - A_c (np.ndarray): The A matrix. - G_c (np.ndarray): The G matrix. - - Returns: - Tuple: The A_d and GQG_d matrices. - """ - GQG_T = np.dot(np.dot(G_c, self.Q), G_c.T) - - matrix_exp = ( - np.block( - [ - [-A_c, GQG_T], - [np.zeros((A_c.shape[0], A_c.shape[0])), np.transpose(A_c)], - ] - ) - * self.dt - ) - - van_loan_matrix = expm(matrix_exp) - - V1 = van_loan_matrix[A_c.shape[0] :, A_c.shape[0] :] - V2 = van_loan_matrix[: A_c.shape[0], A_c.shape[0] :] - - A_d = V1.T - GQG_d = A_d @ V2 - - return A_d, GQG_d - - def error_state_prediction(self, imu_data: Measurement) -> None: - # Rectify measurements. - acc_rect = imu_data.acceleration - self.nom_state.acceleration_bias - gyro_rect = imu_data.angular_velocity - self.nom_state.gyro_bias - - R = self.nom_state.R_q() - - A_c = np.zeros((18, 18)) - - A_c[0:3, 3:6] = np.eye(3) - A_c[3:6, 6:9] = -R @ skew_matrix(acc_rect) - A_c[6:9, 6:9] = -skew_matrix(gyro_rect) - A_c[3:6, 9:12] = -R - A_c[9:12, 9:12] = -self.p_accBias * np.eye(3) - A_c[12:15, 12:15] = -self.p_gyroBias * np.eye(3) - A_c[6:9, 12:15] = -np.eye(3) - A_c[3:6, 15:18] = np.eye(3) - - G_c = np.zeros((18, 12)) - - G_c[3:6, 0:3] = -R - G_c[6:9, 3:6] = -np.eye(3) - G_c[9:12, 6:9] = np.eye(3) - G_c[12:15, 9:12] = np.eye(3) - - A_d, GQG_d = self.van_loan_discretization(A_c, G_c) - - self.error_state.covariance = A_d @ self.error_state.covariance @ A_d.T + GQG_d - - def measurement_update(self, dvl_measurement: Measurement) -> float: - """Updates the error state using the DVL measurement. - Joan Solà. Quaternion kinematics for the error-state Kalman filter. - Chapter: 6.1 eq. 274-276 - - Args: - dvl_measurement (np.ndarray): The DVL measurement. - """ - H = self.H() - P = self.error_state.covariance - R = dvl_measurement.aiding_covariance - - S = H @ P @ H.T + R - K = P @ H.T @ np.linalg.inv(S) - innovation = dvl_measurement.aiding - self.h() - - NIS_value = self.NIS(S, innovation) - - self.error_state.fill_states(K @ innovation) - - I_KH = np.eye(18) - K @ H - self.error_state.covariance = ( - I_KH @ P @ I_KH.T + K @ R @ K.T - ) # Joseph form for more stability - return NIS_value - - def injection(self) -> None: - """Injects the error state into the nominal state to produce the estimated state. - Joan Solà. Quaternion kinematics for the error-state Kalman filter. - Chapter 6.2 eq. 282-283 - - """ - self.nom_state.position = self.nom_state.position + self.error_state.position - self.nom_state.velocity = self.nom_state.velocity + self.error_state.velocity - self.nom_state.orientation = quaternion_product( - self.nom_state.orientation, euler_to_quat(self.error_state.orientation) - ) - self.nom_state.acceleration_bias = ( - self.nom_state.acceleration_bias + self.error_state.acceleration_bias - ) - self.nom_state.gyro_bias = self.nom_state.gyro_bias + self.error_state.gyro_bias - self.nom_state.g = self.nom_state.g + self.error_state.g - - def reset_error_state(self) -> None: - """Resets the error state after injection. - Joan Solà. Quaternion kinematics for the error-state Kalman filter. - Chapter 6.3 eq. 284-286 - """ - G = np.eye(18) # Neglecting the delta_theta as this is most common in practice - - self.error_state.covariance = G @ self.error_state.covariance @ G.T - self.error_state.fill_states(np.zeros(18)) - - def imu_update(self, imu_data: Measurement) -> None: - """Updates the state using the IMU data.""" - self.nominal_state_discrete(imu_data) - self.error_state_prediction(imu_data) - - def dvl_update(self, dvl_measurement: Measurement) -> float: - """Updates the state using the DVL measurement.""" - NIS = self.measurement_update(dvl_measurement) - self.injection() - self.reset_error_state() - - return NIS - - # functions for tuning the filter - def NIS(self, S: np.ndarray, innovation: np.ndarray) -> float: - """Calculates the Normalized Innovation Squared (NIS) value.""" - return innovation.T @ np.linalg.inv(S) @ innovation - - def NEEDS( - self, P: np.ndarray, true_state: StateQuat, estimate_state: StateQuat - ) -> float: - """Calculates the Normalized Estimation Error Squared (NEEDS) value.""" - return ( - (true_state - estimate_state).as_vector().T - @ np.linalg.inv(P) - @ (true_state - estimate_state).as_vector() - ) diff --git a/navigation/eskf_python/eskf_python/eskf_python_node.py b/navigation/eskf_python/eskf_python/eskf_python_node.py deleted file mode 100644 index 7b300ecc6..000000000 --- a/navigation/eskf_python/eskf_python/eskf_python_node.py +++ /dev/null @@ -1,151 +0,0 @@ -#!/usr/bin/env python3 - -import numpy as np -import rclpy -from geometry_msgs.msg import TwistWithCovarianceStamped -from nav_msgs.msg import Odometry -from rclpy.node import Node -from rclpy.qos import QoSProfile, qos_profile_sensor_data -from sensor_msgs.msg import Imu - -# NEED TO CHANGE THIS TO THE CORRECT PATH -from eskf_python.eskf_python_filter import ( - ErrorStateKalmanFilter, - MeasurementModel, - StateVector_euler, - StateVector_quaternion, -) - -qos_profile = QoSProfile( - depth=1, - history=qos_profile_sensor_data.history, - reliability=qos_profile_sensor_data.reliability, -) - - -class ESKalmanFilterNode(Node): - def __init__(self): - super().__init__("eskf_python_node") - - # This callback will supply information from the IMU (Inertial Measurement Unit) 1000 Hz - self.imu_subscriber_ = self.create_subscription( - Imu, '/orca/imu', self.imu_callback, qos_profile=qos_profile - ) - - self.twist_dvl_subscriber_ = self.create_subscription( - TwistWithCovarianceStamped, - '/dvl/twist', - self.filter_callback, - qos_profile=qos_profile, - ) - - # This publisher will publish the estimtaed state of the vehicle - self.state_publisher_ = self.create_publisher( - Odometry, '/orca/odom', qos_profile=qos_profile - ) - - self.eskf_modual = ErrorStateKalmanFilter() - self.current_state_nom = StateVector_quaternion() - self.current_state_error = StateVector_euler() - self.measurement_pred = MeasurementModel() - self.odom_msg = Odometry() - - self.get_logger().info("Error State Kalman Filter started") - - def imu_callback(self, msg: Imu): - # Get the IMU data - - imu_acceleartion = msg.linear_acceleration - imu_angular_velocity = msg.angular_velocity - - # Combine the IMU data - imu_data = np.array( - [ - imu_acceleartion.x, - imu_acceleartion.y, - imu_acceleartion.z, - imu_angular_velocity.x, - imu_angular_velocity.y, - imu_angular_velocity.z, - ] - ) - - # Update the filter with the IMU data - self.current_state_nom, self.current_state_error = ( - ErrorStateKalmanFilter.imu_update_states( - self.current_state_nom, self.current_state_error, imu_data - ) - ) - - # Inserting the nominal state into the msg - self.odom_msg.pose.pose.position.x = self.current_state_nom.position[0] - self.odom_msg.pose.pose.position.y = self.current_state_nom.position[1] - self.odom_msg.pose.pose.position.z = self.current_state_nom.position[2] - self.odom_msg.pose.pose.orientation.x = self.current_state_nom.orientation[0] - self.odom_msg.pose.pose.orientation.y = self.current_state_nom.orientation[1] - self.odom_msg.pose.pose.orientation.z = self.current_state_nom.orientation[2] - self.odom_msg.pose.pose.orientation.w = self.current_state_nom.orientation[3] - self.odom_msg.twist.twist.linear.x = self.current_state_nom.velocity[0] - self.odom_msg.twist.twist.linear.y = self.current_state_nom.velocity[1] - self.odom_msg.twist.twist.linear.z = self.current_state_nom.velocity[2] - self.odom_msg.twist.twist.angular.x = imu_angular_velocity.x - self.odom_msg.twist.twist.angular.y = imu_angular_velocity.y - self.odom_msg.twist.twist.angular.z = imu_angular_velocity.z - - # Publish - self.state_publisher_.publish(self.odom_msg) - - def filter_callback(self, msg: TwistWithCovarianceStamped): - """Callback function for the filter measurement update, - this will be called when the filter needs to be updated with the DVL data. - """ - self.get_logger().info("Filter callback, got DVL data") - - # Get the DVL data (linear velocity) - dvl_data = np.array( - [ - msg.twist.twist.linear.x, - msg.twist.twist.linear.y, - msg.twist.twist.linear.z, - ] - ) - - # Update the filter with the DVL data - self.current_state_nom, self.current_state_error = ( - ErrorStateKalmanFilter.dvl_update_states( - self.current_state_nom, self.current_state_error, dvl_data - ) - ) - self.current_state_nom, self.current_state_error = ( - ErrorStateKalmanFilter.injection_and_reset( - self.current_state_nom, self.current_state_error - ) - ) - - # Inserting data into the msg - self.odom_msg.pose.pose.position.x = self.current_state_nom.position[0] - self.odom_msg.pose.pose.position.y = self.current_state_nom.position[1] - self.odom_msg.pose.pose.position.z = self.current_state_nom.position[2] - self.odom_msg.pose.pose.orientation.x = self.current_state_nom.orientation[0] - self.odom_msg.pose.pose.orientation.y = self.current_state_nom.orientation[1] - self.odom_msg.pose.pose.orientation.z = self.current_state_nom.orientation[2] - self.odom_msg.pose.pose.orientation.w = self.current_state_nom.orientation[3] - self.odom_msg.twist.twist.linear.x = self.current_state_nom.velocity[0] - self.odom_msg.twist.twist.linear.y = self.current_state_nom.velocity[1] - self.odom_msg.twist.twist.linear.z = self.current_state_nom.velocity[2] - self.odom_msg.twist.twist.linear.z = self.current_state_nom.velocity[2] - - # Publishing the data - self.state_publisher_.publish(self.odom_msg) - - -def main(args=None): - rclpy.init(args=args) - node = ESKalmanFilterNode() - rclpy.spin(node) - node.destroy_node() - rclpy.shutdown() - - -if __name__ == "__main__": - main() diff --git a/navigation/eskf_python/eskf_python/eskf_python_utils.py b/navigation/eskf_python/eskf_python/eskf_python_utils.py deleted file mode 100644 index bbe13d759..000000000 --- a/navigation/eskf_python/eskf_python/eskf_python_utils.py +++ /dev/null @@ -1,148 +0,0 @@ -import numpy as np - - -def skew_matrix(vector: np.ndarray) -> np.ndarray: - """Returns the skew symmetric matrix of a 3x1 vector. - """ - return np.array( - [ - [0, -vector[2], vector[1]], - [vector[2], 0, -vector[0]], - [-vector[1], vector[0], 0], - ] - ) - - -def quat_norm(quat: np.ndarray) -> np.ndarray: - """Function that normalizes a quaternion - """ - quat = quat / np.linalg.norm(quat) - - return quat - - -def quaternion_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: - """Calculates the quaternion super product of two quaternions. - - Args: - q1 (np.ndarray): The first quaternion. - q2 (np.ndarray): The second quaternion. - - Returns: - np.ndarray: The quaternion super product. - """ - eta_0, e_0_x, e_0_y, e_0_z = q1 - eta_1, e_1_x, e_1_y, e_1_z = q2 - - e_0 = np.array([e_0_x, e_0_y, e_0_z]) - e_1 = np.array([e_1_x, e_1_y, e_1_z]) - - eta_new = eta_0 * eta_1 - np.dot(e_0, e_1) - nu_new = e_1 * eta_0 + e_0 * eta_1 + np.cross(e_0, e_1) - - q_new = np.array([eta_new, nu_new[0], nu_new[1], nu_new[2]]) - q_new = q_new / np.linalg.norm(q_new) - - return q_new - - -def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: - """Calculates the error between two quaternions - """ - quat_2_inv = np.array([quat_2[0], -quat_2[1], -quat_2[2], -quat_2[3]]) - - error_quat = quaternion_product(quat_1, quat_2_inv) - - return error_quat - - -def angle_axis_to_quaternion(vector: np.ndarray) -> np.ndarray: - """Converts an angle-axis representation to a quaternion. - - Args: - vector (np.ndarray): The angle-axis representation. - - Returns: - np.ndarray: The quaternion representation. - """ - angle = np.linalg.norm(vector) - if angle < 1e-8: - return np.array([1, 0, 0, 0]) - else: - axis = vector / angle - - q = np.zeros(4) - q[0] = np.cos(angle / 2) - q[1:] = np.sin(angle / 2) * axis - - return q - - -def R_from_angle_axis(vector: np.ndarray) -> np.ndarray: - """Calculates the rotation matrix from the angle-axis representation. - - Args: - vector (np.ndarray): The angle-axis representation. - - Returns: - np.ndarray: The rotation matrix. - """ - quaternion = angle_axis_to_quaternion(vector) - q0, q1, q2, q3 = quaternion - - R = np.array( - [ - [ - 1 - 2 * q2**2 - 2 * q3**2, - 2 * (q1 * q2 - q0 * q3), - 2 * (q0 * q2 + q1 * q3), - ], - [ - 2 * (q1 * q2 + q0 * q3), - 1 - 2 * q1**2 - 2 * q3**2, - 2 * (q2 * q3 - q0 * q1), - ], - [ - 2 * (q1 * q3 - q0 * q2), - 2 * (q0 * q1 + q2 * q3), - 1 - 2 * q1**2 - 2 * q2**2, - ], - ] - ) - - return R - - -def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: - """Converts Euler angles to a quaternion - """ - psi, theta, phi = euler_angles - c_psi = np.cos(psi / 2) - s_psi = np.sin(psi / 2) - c_theta = np.cos(theta / 2) - s_theta = np.sin(theta / 2) - c_phi = np.cos(phi / 2) - s_phi = np.sin(phi / 2) - - quat = np.array( - [ - c_psi * c_theta * c_phi + s_psi * s_theta * s_phi, - c_psi * c_theta * s_phi - s_psi * s_theta * c_phi, - s_psi * c_theta * s_phi + c_psi * s_theta * c_phi, - s_psi * c_theta * c_phi - c_psi * s_theta * s_phi, - ] - ) - - return quat - - -def quat_to_euler(quat: np.ndarray) -> np.ndarray: - """Converts a quaternion to Euler angles - """ - nu, eta_1, eta_2, eta_3 = quat - - phi = np.arctan2(2 * (eta_2 * eta_3 + nu * eta_1), 1 - 2 * (eta_1**2 + eta_2**2)) - theta = -np.arcsin(2 * (eta_1 * eta_3 - nu * eta_2)) - psi = np.arctan2(2 * (nu * eta_3 + eta_1 * eta_2), 1 - 2 * (eta_2**2 + eta_3**2)) - - return np.array([phi, theta, psi]) diff --git a/navigation/eskf_python/eskf_python/eskf_test.py b/navigation/eskf_python/eskf_python/eskf_test.py deleted file mode 100644 index 2c6d94c09..000000000 --- a/navigation/eskf_python/eskf_python/eskf_test.py +++ /dev/null @@ -1,358 +0,0 @@ -import matplotlib.pyplot as plt -import numpy as np -from eskf_python_class import Measurement, StateQuat -from eskf_python_filter import ESKF -from eskf_python_utils import quat_to_euler -from eskf_test_utils import StateQuatModel, process_model - - -def simulate_eskf(): - # Simulation parameters - simulation_time = 20.0 # seconds - dt = 0.01 - num_steps = int(simulation_time / dt) - time = np.linspace(0, simulation_time, num_steps) - - # ----------------------- Setup Initial States, Filter & Model ----------------------- - # True initial state - true_state_init = StateQuat() - true_state_init.position = np.array([0.1, 0.0, 0.0]) - true_state_init.velocity = np.array([0.1, 0.0, 0.0]) - P0 = np.diag( - [ - 0.3, - 0.3, - 0.3, # Position - 0.2, - 0.2, - 0.2, # Velocity - 0.2, - 0.2, - 0.2, # Orientation - 0.0001, - 0.0001, - 0.0001, # Acceleration bias - 0.00001, - 0.00001, - 0.00001, # Gyro bias - 0.00001, - 0.00001, - 0.00001, # Gravity - ] - ) - # Noise parameters - Q = np.diag( - [ - (0.13**2), - (0.13**2), - (0.13**2), # Adjusted Accelerometer noise - (0.13**2), - (0.13**2), - (0.13**2), # Adjusted Gyroscope noise - 0.0001, - 0.0001, - 0.0001, # Adjusted Acceleration bias random walk - 0.0001, - 0.0001, - 0.0001, # Adjusted Gyro bias random walk - ] - ) - - # Create filter object - eskf = ESKF(Q, P0, true_state_init, 1e-13, 1e-13, dt) - - # Create measurement objects - imu_data = Measurement() - dvl_data = Measurement() - - # R matrix for DVL aiding - dvl_data.aiding_covariance = np.diag( - [(0.01) ** 2, (0.01) ** 2, (0.01) ** 2] - ) # Adjusted DVL aiding covariance - - # Setup the process model for simulation of AUV - model = process_model() - model.dt = dt - model.mass_interia_matrix = np.array( - [ - [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], - ] - ) - model.m = 30.0 - model.r_b_bg = np.array([0.01, 0.0, 0.02]) - model.inertia = np.diag([0.68, 3.32, 3.34]) - model.damping_linear = np.diag([0.03, 0.03, 0.03, 0.03, 0.03, 0.03]) - - # Initialize a dummy state for simulation dynamics. - # Two where made since there seems to be an issue with declaring two identical objects. - new_state = StateQuatModel() - new_state.position = np.array([0.1, 0.0, 0.0]) - new_state.velocity = np.array([0.1, 0.0, 0.0]) - - new_state_prev = StateQuatModel() - new_state_prev.position = np.array([0.1, 0.0, 0.0]) - new_state_prev.velocity = np.array([0.1, 0.0, 0.0]) - - model.state_vector = new_state - model.state_vector_prev = new_state_prev - - # Initialize arrays to store true and estimated states - true_positions = np.zeros((num_steps, 3)) - true_orientations = np.zeros((num_steps, 3)) - true_velocities = np.zeros((num_steps, 3)) - - est_positions = np.zeros((num_steps, 3)) - est_orientations = np.zeros((num_steps, 3)) - est_velocities = np.zeros((num_steps, 3)) - - # covariance arrays - pos_cov = np.zeros((num_steps, 3)) - vel_cov = np.zeros((num_steps, 3)) - ori_cov = np.zeros((num_steps, 3)) - - prev_velocity = np.zeros(3) - u = lambda t: np.array( - [ - 0.5 * np.sin(0.1 * t), - 0.5 * np.sin(0.1 * t + 0.3), - 0.5 * np.sin(0.1 * t + 0.6), - 0.05 * np.cos(0.1 * t), - 0.05 * np.cos(0.1 * t + 0.3), - 0.05 * np.cos(0.1 * t + 0.6), - ] - ) - - NIS_list = [] - NIS_value = 0.0 - - # Sim - for step in range(num_steps): - t = step * dt - - model.Control_input = u(t) - model.model_prediction(new_state) - new_state = model.euler_forward() - - imu_data.acceleration = ( - (new_state.velocity - prev_velocity) / dt - ) + np.random.normal(0, 0.13, 3) - imu_data.angular_velocity = new_state.angular_velocity + np.random.normal( - 0, 0.13, 3 - ) - - eskf.imu_update(imu_data) - - if step % 200 == 0: - dvl_data.aiding = new_state.velocity + np.random.normal(0, 0.01, 3) - NIS_value = eskf.dvl_update(dvl_data) - NIS_list.append(NIS_value) - - true_positions[step, :] = np.copy(new_state.position) - true_orientations[step, :] = quat_to_euler(np.copy(new_state.orientation)) - true_velocities[step, :] = np.copy(new_state.velocity) - - est_positions[step, :] = np.copy(eskf.nom_state.position) - est_orientations[step, :] = quat_to_euler(np.copy(eskf.nom_state.orientation)) - est_velocities[step, :] = np.copy(eskf.nom_state.velocity) - - P_diag = np.diag(eskf.error_state.covariance) - pos_cov[step, :] = P_diag[0:3] - vel_cov[step, :] = P_diag[3:6] - ori_cov[step, :] = P_diag[6:9] - - prev_velocity = new_state.velocity - model.state_vector_prev = new_state - - return ( - time, - true_positions, - true_orientations, - true_velocities, - est_positions, - est_orientations, - est_velocities, - pos_cov, - vel_cov, - ori_cov, - NIS_list, - ) - - -( - time, - true_positions, - true_orientations, - true_velocities, - est_positions, - est_orientations, - est_velocities, - pos_cov, - vel_cov, - ori_cov, - _, -) = simulate_eskf() - -# Plotting -axis_labels_pos = ["X", "Y", "Z"] -axis_labels_vel = ["X", "Y", "Z"] -axis_labels_ori = ["Roll", "Pitch", "Yaw"] - -# Plot Position -fig_pos, axs_pos = plt.subplots(3, 1, figsize=(10, 12)) -fig_pos.suptitle("True Data vs Filter Estimates for Position") -for i in range(3): - ax_pos = axs_pos[i] - ax_pos.plot( - time, - true_positions[:, i], - label=f"True Pos {axis_labels_pos[i]}", - color=f"C{i}", - linestyle='-', - ) - ax_pos.plot( - time, - est_positions[:, i], - label=f"Est Pos {axis_labels_pos[i]}", - color=f"C{i}", - linestyle='--', - ) - sigma_pos = np.sqrt(pos_cov[:, i]) - ax_pos.fill_between( - time, - est_positions[:, i] - sigma_pos, - est_positions[:, i] + sigma_pos, - color=f"C{i}", - alpha=0.2, - ) - ax_pos.set_title(f"Position [{axis_labels_pos[i]}] [m]") - ax_pos.set_xlabel("Time [s]") - ax_pos.set_ylabel("Position") - ax_pos.grid(True) - ax_pos.legend() - -plt.tight_layout(rect=[0, 0, 1, 0.96]) -plt.show() - -# Plot Velocity -fig_vel, axs_vel = plt.subplots(3, 1, figsize=(10, 12)) -fig_vel.suptitle("True Data vs Filter Estimates for Velocity") -for i in range(3): - ax_vel = axs_vel[i] - ax_vel.plot( - time, - true_velocities[:, i], - label=f"True Vel {axis_labels_vel[i]}", - color=f"C{i}", - linestyle='-', - ) - ax_vel.plot( - time, - est_velocities[:, i], - label=f"Est Vel {axis_labels_vel[i]}", - color=f"C{i}", - linestyle='--', - ) - sigma_vel = np.sqrt(vel_cov[:, i]) - ax_vel.fill_between( - time, - est_velocities[:, i] - sigma_vel, - est_velocities[:, i] + sigma_vel, - color=f"C{i}", - alpha=0.2, - ) - ax_vel.set_title(f"Velocity [{axis_labels_vel[i]}] [m/s]") - ax_vel.set_xlabel("Time [s]") - ax_vel.set_ylabel("Velocity") - ax_vel.grid(True) - ax_vel.legend() - -plt.tight_layout(rect=[0, 0, 1, 0.96]) -plt.show() - -# Plot Orientation -fig_ori, axs_ori = plt.subplots(3, 1, figsize=(10, 12)) -fig_ori.suptitle("True Data vs Filter Estimates for Orientation") -for i in range(3): - ax_ori = axs_ori[i] - ax_ori.plot( - time, - true_orientations[:, i], - label=f"True Ori {axis_labels_ori[i]}", - color=f"C{i}", - linestyle='-', - ) - ax_ori.plot( - time, - est_orientations[:, i], - label=f"Est Ori {axis_labels_ori[i]}", - color=f"C{i}", - linestyle='--', - ) - sigma_ori = np.sqrt(ori_cov[:, i]) - ax_ori.fill_between( - time, - est_orientations[:, i] - sigma_ori, - est_orientations[:, i] + sigma_ori, - color=f"C{i}", - alpha=0.2, - ) - ax_ori.set_title(f"Orientation [{axis_labels_ori[i]}] [rad]") - ax_ori.set_xlabel("Time [s]") - ax_ori.set_ylabel("Orientation") - ax_ori.grid(True) - ax_ori.legend() - -plt.tight_layout(rect=[0, 0, 1, 0.96]) -plt.show() - - -### _______ NIS AND NEEDS _______ -""" -num_simulations = 10 -NIS_runs = [] - -for sim in range(num_simulations): - ( - time, - true_positions, - true_orientations, - true_velocities, - est_positions, - est_orientations, - est_velocities, - pos_cov, - vel_cov, - ori_cov, - NIS_list, - ) = simulate_eskf() - - NIS_runs.append(np.array(NIS_list)) - -NIS_runs = np.vstack(NIS_runs) -ANIS = np.mean(NIS_runs, axis=0) - -measurement_dimension = 3 - -chi2_lower = chi2.ppf(0.025, measurement_dimension) / num_simulations -chi2_upper = chi2.ppf(0.975, measurement_dimension) / num_simulations - -time_steps = np.arange(len(ANIS)) * 0.01 * 20 - -fig, ax = plt.subplots(figsize=(10, 6)) -ax.plot(time_steps, ANIS, label="ANIS", color="C0") -ax.axhline(chi2_lower, color="C1", linestyle="--", label="95% CI Lower") -ax.axhline(chi2_upper, color="C2", linestyle="--", label="95% CI Upper") -ax.set_title("Average Normalized Innovation Squared (ANIS)") -ax.set_xlabel("Time [s]") -ax.set_ylabel("ANIS") -ax.grid(True) -ax.legend() - -plt.tight_layout() -plt.show() -""" diff --git a/navigation/eskf_python/eskf_python/eskf_test_utils.py b/navigation/eskf_python/eskf_python/eskf_test_utils.py deleted file mode 100644 index a60e62ff0..000000000 --- a/navigation/eskf_python/eskf_python/eskf_test_utils.py +++ /dev/null @@ -1,243 +0,0 @@ -from dataclasses import dataclass, field - -import numpy as np -from eskf_python_utils import ( - euler_to_quat, - quat_norm, - quat_to_euler, - quaternion_error, - quaternion_product, - skew_matrix, -) - -# This was the original code from the ukf_okid.py file - - -@dataclass -class StateQuatModel: - """A class to represent the state to be estimated by the UKF. - """ - - position: np.ndarray = field(default_factory=lambda: np.zeros(3)) - orientation: np.ndarray = field(default_factory=lambda: np.array([1, 0, 0, 0])) - velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) - angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) - covariance: np.ndarray = field(default_factory=lambda: np.zeros((12, 12))) - - def as_vector(self) -> np.ndarray: - """Returns the StateVector as a numpy array.""" - return np.concatenate( - [self.position, self.orientation, self.velocity, self.angular_velocity] - ) - - def nu(self) -> np.ndarray: - """Calculates the nu vector.""" - return np.concatenate([self.velocity, self.angular_velocity]) - - def R_q(self) -> np.ndarray: - """Calculates the rotation matrix from the orientation quaternion.""" - q0, q1, q2, q3 = self.orientation - R = np.array( - [ - [ - 1 - 2 * q2**2 - 2 * q3**2, - 2 * (q1 * q2 - q0 * q3), - 2 * (q0 * q2 + q1 * q3), - ], - [ - 2 * (q1 * q2 + q0 * q3), - 1 - 2 * q1**2 - 2 * q3**2, - 2 * (q2 * q3 - q0 * q1), - ], - [ - 2 * (q1 * q3 - q0 * q2), - 2 * (q0 * q1 + q2 * q3), - 1 - 2 * q1**2 - 2 * q2**2, - ], - ] - ) - return R - - def fill_states(self, state: np.ndarray) -> None: - """Fills the state vector with the values from a numpy array.""" - self.position = state[0:3] - self.orientation = state[3:7] - self.velocity = state[7:10] - self.angular_velocity = state[10:13] - - def fill_states_different_dim( - self, state: np.ndarray, state_euler: np.ndarray - ) -> None: - """Fills states when the state vector has different dimensions than the default state vector.""" - self.position = state[0:3] + state_euler[0:3] - self.orientation = quaternion_product( - state[3:7], euler_to_quat(state_euler[3:6]) - ) - self.velocity = state[7:10] + state_euler[6:9] - self.angular_velocity = state[10:13] + state_euler[9:12] - - def subtract(self, other: 'StateQuatModel') -> np.ndarray: - """Subtracts two StateQuatModel objects, returning the difference with Euler angles.""" - new_array = np.zeros(len(self.as_vector()) - 1) - new_array[:3] = self.position - other.position - new_array[3:6] = quat_to_euler( - quaternion_error(self.orientation, other.orientation) - ) - new_array[6:9] = self.velocity - other.velocity - new_array[9:12] = self.angular_velocity - other.angular_velocity - - return new_array - - def __add__(self, other: 'StateQuatModel') -> 'StateQuatModel': - """Adds two StateQuatModel objects.""" - new_state = StateQuatModel() - new_state.position = self.position + other.position - new_state.orientation = quaternion_product(self.orientation, other.orientation) - new_state.velocity = self.velocity + other.velocity - new_state.angular_velocity = self.angular_velocity + other.angular_velocity - - return new_state - - def __sub__(self, other: 'StateQuatModel') -> 'StateQuatModel': - """Subtracts two StateQuatModel objects.""" - new_state = StateQuatModel() - new_state.position = self.position - other.position - new_state.orientation = quaternion_error(self.orientation, other.orientation) - new_state.velocity = self.velocity - other.velocity - new_state.angular_velocity = self.angular_velocity - other.angular_velocity - - return new_state.as_vector() - - def __rmul__(self, scalar: float) -> 'StateQuatModel': - """Multiplies the StateQuatModel object by a scalar.""" - new_state = StateQuatModel() - new_state.position = scalar * self.position - new_state.orientation = quat_norm(scalar * self.orientation) - new_state.velocity = scalar * self.velocity - new_state.angular_velocity = scalar * self.angular_velocity - - return new_state - - def insert_weights(self, weights: np.ndarray) -> np.ndarray: - """Inserts the weights into the covariance matrix.""" - new_state = StateQuatModel() - new_state.position = self.position - weights[:3] - new_state.orientation = quaternion_error( - self.orientation, euler_to_quat(weights[3:6]) - ) - new_state.velocity = self.velocity - weights[6:9] - new_state.angular_velocity = self.angular_velocity - weights[9:12] - - return new_state.as_vector() - - def add_without_quaternions(self, other: 'StateQuatModel') -> None: - """Adds elements into the state vector without considering the quaternions.""" - self.position += other.position - self.velocity += other.velocity - self.angular_velocity += other.angular_velocity - - -@dataclass -class process_model: - """A class defined for a general process model. - """ - - state_vector: StateQuatModel = field(default_factory=StateQuatModel) - state_vector_dot: StateQuatModel = field(default_factory=StateQuatModel) - state_vector_prev: StateQuatModel = field(default_factory=StateQuatModel) - Control_input: np.ndarray = field(default_factory=lambda: np.zeros(6)) - mass_interia_matrix: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) - added_mass: np.ndarray = field(default_factory=lambda: np.zeros(6)) - damping_linear: np.ndarray = field(default_factory=lambda: np.zeros(6)) - damping_nonlinear: np.ndarray = field(default_factory=lambda: np.zeros(6)) - m: float = 0.0 - inertia: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) - r_b_bg: np.ndarray = field(default_factory=lambda: np.zeros(3)) - dt: float = 0.0 - integral_error_position: np.ndarray = field(default_factory=lambda: np.zeros(3)) - integral_error_orientation: np.ndarray = field(default_factory=lambda: np.zeros(4)) - prev_position_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) - prev_orientation_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) - - def R(self) -> np.ndarray: - """Calculates the rotation matrix.""" - nu, e_1, e_2, e_3 = self.state_vector.orientation - R = np.array( - [ - [ - 1 - 2 * e_2**2 - 2 * e_3**2, - 2 * e_1 * e_2 - 2 * nu * e_3, - 2 * e_1 * e_3 + 2 * nu * e_2, - ], - [ - 2 * e_1 * e_2 + 2 * nu * e_3, - 1 - 2 * e_1**2 - 2 * e_3**2, - 2 * e_2 * e_3 - 2 * nu * e_1, - ], - [ - 2 * e_1 * e_3 - 2 * nu * e_2, - 2 * e_2 * e_3 + 2 * nu * e_1, - 1 - 2 * e_1**2 - 2 * e_2**2, - ], - ] - ) - return R - - def T(self) -> np.ndarray: - """Calculates the transformation matrix.""" - nu, e_1, e_2, e_3 = self.state_vector.orientation - T = 0.5 * np.array( - [[-e_1, -e_2, -e_3], [nu, -e_3, e_2], [e_3, nu, -e_1], [-e_2, e_1, nu]] - ) - return T - - def Crb(self) -> np.ndarray: - """Calculates the Coriolis matrix.""" - ang_vel = self.state_vector.angular_velocity - ang_vel_skew = skew_matrix(ang_vel) - lever_arm_skew = skew_matrix(self.r_b_bg) - Crb = np.zeros((6, 6)) - Crb[0:3, 0:3] = self.m * ang_vel_skew - Crb[3:6, 3:6] = -skew_matrix(np.dot(self.inertia, ang_vel)) - Crb[0:3, 3:6] = -self.m * np.dot(ang_vel_skew, lever_arm_skew) - Crb[3:6, 0:3] = self.m * np.dot(lever_arm_skew, ang_vel_skew) - return Crb - - def D(self) -> np.ndarray: - """Calculates the damping matrix.""" - D_l = -np.diag(self.damping_linear) - D_nl = -np.diag(self.damping_nonlinear) * np.abs(self.state_vector.nu()) - return D_l + D_nl - - def model_prediction(self, state: StateQuatModel) -> None: - """Calculates the model of the system.""" - self.state_vector = state - self.state_vector_dot.position = np.dot(self.R(), self.state_vector.velocity) - self.state_vector_dot.orientation = np.dot( - self.T(), self.state_vector.angular_velocity - ) - Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ ( - self.Control_input - - np.dot(self.Crb(), self.state_vector.nu()) - - np.dot(self.D(), self.state_vector.nu()) - ) - self.state_vector_dot.velocity = Nu[:3] - self.state_vector_dot.angular_velocity = Nu[3:] - - def euler_forward(self) -> StateQuatModel: - """Calculates the forward Euler integration.""" - self.state_vector.position = ( - self.state_vector_prev.position + self.state_vector_dot.position * self.dt - ) - self.state_vector.orientation = quat_norm( - self.state_vector_prev.orientation - + self.state_vector_dot.orientation * self.dt - ) - self.state_vector.velocity = ( - self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt - ) - self.state_vector.angular_velocity = ( - self.state_vector_prev.angular_velocity - + self.state_vector_dot.angular_velocity * self.dt - ) - return self.state_vector diff --git a/navigation/eskf_python/launch/eskf.launch.py b/navigation/eskf_python/launch/eskf.launch.py deleted file mode 100644 index 3cae83dce..000000000 --- a/navigation/eskf_python/launch/eskf.launch.py +++ /dev/null @@ -1,22 +0,0 @@ -import os - -from ament_index_python.packages import get_package_share_directory -from launch import LaunchDescription -from launch_ros.actions import Node - - -def generate_launch_description(): - eskf_python_node = Node( - package='eskf_python', - executable='eskf_python_node.py', - name='eskf_python_node', - parameters=[ - os.path.join( - get_package_share_directory('eskf_python'), - 'config', - 'eskf_python.yaml', - ), - ], - output='screen', - ) - return LaunchDescription([eskf_python_node]) diff --git a/navigation/eskf_python/package.xml b/navigation/eskf_python/package.xml deleted file mode 100644 index 980653c40..000000000 --- a/navigation/eskf_python/package.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - eskf_python - 1.0.0 - This package provides the implementation of a error-state kalman filter in python - talhanc - MIT - - ament_cmake_python - - rclpy - python-transforms3d-pip - geometry_msgs - vortex_msgs - - python3-pytest - - - - ament_cmake - - diff --git a/navigation/ukf_okid/ukf_python/rest.py b/navigation/ukf_okid/ukf_python/rest.py index 52cffb2df..c8b4f3b14 100644 --- a/navigation/ukf_okid/ukf_python/rest.py +++ b/navigation/ukf_okid/ukf_python/rest.py @@ -1,6 +1,5 @@ def mean_set(set_points: list[StateQuat], weights: np.ndarray = None) -> np.ndarray: - """Function that calculates the mean of a set of points - """ + """Function that calculates the mean of a set of points""" n = len(set_points[0].as_vector()) - 1 mean_value = StateQuat() @@ -27,8 +26,7 @@ def mean_set(set_points: list[StateQuat], weights: np.ndarray = None) -> np.ndar def mean_measurement( set_points: list[MeasModel], weights: np.ndarray = None ) -> np.ndarray: - """Function that calculates the mean of a set of points - """ + """Function that calculates the mean of a set of points""" n = len(set_points) mean_value = MeasModel() diff --git a/navigation/ukf_okid/ukf_python/ukf_okid.py b/navigation/ukf_okid/ukf_python/ukf_okid.py index 80a7c939c..50c68e08c 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid.py @@ -1,4 +1,3 @@ - import numpy as np from ukf_okid_class import * @@ -39,8 +38,7 @@ def generate_T_matrix(self, n: float) -> np.ndarray: return T def sigma_points(self, current_state: StateQuat) -> list[StateQuat]: - """Functions that generate the sigma points for the UKF - """ + """Functions that generate the sigma points for the UKF""" n = len(current_state.covariance) I = np.hstack([np.eye(n), -np.eye(n)]) @@ -58,8 +56,7 @@ def sigma_points(self, current_state: StateQuat) -> list[StateQuat]: return self.sigma_points_list def unscented_transform(self, current_state: StateQuat) -> StateQuat: - """The unscented transform function generates the priori state estimate - """ + """The unscented transform function generates the priori state estimate""" _ = self.sigma_points(current_state) n = len(current_state.covariance) @@ -107,8 +104,7 @@ def posteriori_estimate( measurement: MeasModel, ex_measuremnt: MeasModel, ) -> StateQuat: - """Calculates the posteriori estimate using measurement and the prior estimate - """ + """Calculates the posteriori estimate using measurement and the prior estimate""" nu_k = MeasModel() nu_k.measurement = measurement.measurement - ex_measuremnt.measurement diff --git a/navigation/ukf_okid/ukf_python/ukf_okid_class.py b/navigation/ukf_okid/ukf_python/ukf_okid_class.py index 181d1f4af..45bbffcfe 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid_class.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid_class.py @@ -5,8 +5,7 @@ @dataclass class StateQuat: - """A class to represent the state to be estimated by the UKF. - """ + """A class to represent the state to be estimated by the UKF.""" position: np.ndarray = field(default_factory=lambda: np.zeros(3)) orientation: np.ndarray = field(default_factory=lambda: np.array([1, 0, 0, 0])) @@ -129,8 +128,7 @@ def add_without_quaternions(self, other: 'StateQuat') -> None: @dataclass class MeasModel: - """A class defined for a general measurement model. - """ + """A class defined for a general measurement model.""" measurement: np.ndarray = field(default_factory=lambda: np.zeros(3)) covariance: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) @@ -164,8 +162,7 @@ def __sub__(self, other: 'MeasModel') -> 'MeasModel': @dataclass class process_model: - """A class defined for a general process model. - """ + """A class defined for a general process model.""" state_vector: StateQuat = field(default_factory=StateQuat) state_vector_dot: StateQuat = field(default_factory=StateQuat) @@ -269,8 +266,7 @@ def euler_forward(self) -> StateQuat: def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: - """Converts Euler angles to a quaternion - """ + """Converts Euler angles to a quaternion""" psi, theta, phi = euler_angles c_psi = np.cos(psi / 2) s_psi = np.sin(psi / 2) @@ -292,8 +288,7 @@ def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: def quat_to_euler(quat: np.ndarray) -> np.ndarray: - """Converts a quaternion to Euler angles - """ + """Converts a quaternion to Euler angles""" nu, eta_1, eta_2, eta_3 = quat phi = np.arctan2(2 * (eta_2 * eta_3 + nu * eta_1), 1 - 2 * (eta_1**2 + eta_2**2)) @@ -304,8 +299,7 @@ def quat_to_euler(quat: np.ndarray) -> np.ndarray: def quat_norm(quat: np.ndarray) -> np.ndarray: - """Function that normalizes a quaternion - """ + """Function that normalizes a quaternion""" quat = quat / np.linalg.norm(quat) return quat @@ -354,8 +348,7 @@ def quaternion_super_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: - """Calculates the error between two quaternions - """ + """Calculates the error between two quaternions""" quat_2_inv = np.array([quat_2[0], -quat_2[1], -quat_2[2], -quat_2[3]]) error_quat = quaternion_super_product(quat_1, quat_2_inv) @@ -441,8 +434,7 @@ def mean_set(set_points: list[StateQuat]) -> np.ndarray: def mean_measurement(set_points: list[MeasModel]) -> np.ndarray: - """Function that calculates the mean of a set of points - """ + """Function that calculates the mean of a set of points""" n = len(set_points) mean_value = MeasModel() @@ -455,8 +447,7 @@ def mean_measurement(set_points: list[MeasModel]) -> np.ndarray: def covariance_set(set_points: list[StateQuat], mean: np.ndarray) -> np.ndarray: - """Function that calculates the covariance of a set of points - """ + """Function that calculates the covariance of a set of points""" n = len(set_points) covariance = np.zeros(set_points[0].covariance.shape) @@ -486,8 +477,7 @@ def covariance_set(set_points: list[StateQuat], mean: np.ndarray) -> np.ndarray: def covariance_measurement(set_points: list[MeasModel], mean: np.ndarray) -> np.ndarray: - """Function that calculates the covariance of a set of points - """ + """Function that calculates the covariance of a set of points""" n = len(set_points) co_size = len(set_points[0].measurement) covariance = np.zeros((co_size, co_size)) @@ -510,8 +500,7 @@ def cross_covariance( set_z: list[MeasModel], mean_z: np.ndarray, ) -> np.ndarray: - """Calculates the cross covariance between the measurement and state prediction - """ + """Calculates the cross covariance between the measurement and state prediction""" n = len(set_y) cross_covariance = np.zeros((len(mean_y) - 1, len(mean_z))) diff --git a/navigation/ukf_okid/ukf_python/ukf_utils.py b/navigation/ukf_okid/ukf_python/ukf_utils.py index da56a7dfc..cb92d9393 100644 --- a/navigation/ukf_okid/ukf_python/ukf_utils.py +++ b/navigation/ukf_okid/ukf_python/ukf_utils.py @@ -1,4 +1,3 @@ - import numpy as np from ukf_okid_class import StateQuat @@ -6,8 +5,7 @@ def print_StateQuat_list( state_list: list[StateQuat], name="StateQuat List", print_covariance=True ): - """Custom print function to print a list of StateQuat objects in a formatted form. - """ + """Custom print function to print a list of StateQuat objects in a formatted form.""" print(f"{name}:") for i, state in enumerate(state_list): print(f"Index {i}:") @@ -15,8 +13,7 @@ def print_StateQuat_list( def print_StateQuat(state: StateQuat, name="StateQuat", print_covariance=True): - """Custom print function to print StateQuat objects in a formatted form. - """ + """Custom print function to print StateQuat objects in a formatted form.""" print(f"{name}:") print(f" Position: {state.position}") print(f" Orientation: {state.orientation}") @@ -28,8 +25,7 @@ def print_StateQuat(state: StateQuat, name="StateQuat", print_covariance=True): def print_matrix(matrix, name="Matrix"): - """Custom print function to print matrices in a formatted form. - """ + """Custom print function to print matrices in a formatted form.""" print(f"{name}: {matrix.shape}") if isinstance(matrix, np.ndarray): for row in matrix: From ea29da3c0e4418cdb6484ad071bfc31c0eb31ddb Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Sat, 5 Apr 2025 18:27:32 +0200 Subject: [PATCH 14/30] fix: added errorstate and nominalstate variables into the eskf class --- navigation/eskf/config/eskf_params.yaml | 3 +- navigation/eskf/include/eskf/eskf.hpp | 56 +++--- navigation/eskf/include/eskf/eskf_ros.hpp | 2 +- navigation/eskf/include/eskf/typedefs.hpp | 13 +- navigation/eskf/src/eskf.cpp | 202 ++++++++++------------ navigation/eskf/src/eskf_node.cpp | 2 +- navigation/eskf/src/eskf_ros.cpp | 40 ++--- navigation/eskf/src/eskf_utils.cpp | 5 +- 8 files changed, 149 insertions(+), 174 deletions(-) diff --git a/navigation/eskf/config/eskf_params.yaml b/navigation/eskf/config/eskf_params.yaml index f89b62f79..87d50ee44 100644 --- a/navigation/eskf/config/eskf_params.yaml +++ b/navigation/eskf/config/eskf_params.yaml @@ -3,4 +3,5 @@ eskf_node: imu_topic: imu/data_raw dvl_twist: /orca/twist odom_topic: odom - diag_Q_std: [0.0103, 0.0118, 0.0043, 0.00193, 0.00306, 0.00118, 0.000001, 0.000001, 0.000001, 0.000003, 0.000003, 0.000003] + diag_Q_std: [0.0103, 0.0118, 0.0043, 0.00193, 0.00306, 0.00118, 0.000001, 0.000001, 0.000001, 0.00001, 0.00001, 0.00001] + diag_p_init: [1.0, 1.0, 1.0, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp index b30dc35b0..5cc3e0708 100644 --- a/navigation/eskf/include/eskf/eskf.hpp +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -10,52 +10,41 @@ class ESKF { public: ESKF(const eskf_params& params); + // @brief Update the nominal state and error state + // @param imu_meas: IMU measurement + // @param dt: Time step + // @return Updated nominal state and error state std::pair imu_update( - const state_quat& nom_state, - const state_euler& error_state, const imu_measurement& imu_meas, const double dt); + // @brief Update the nominal state and error state + // @param dvl_meas: DVL measurement + // @return Updated nominal state and error state std::pair dvl_update( - const state_quat& nom_state, - const state_euler& error_state, const dvl_measurement& dvl_meas); private: // @brief Predict the nominal state - // @param nom_state: Nominal state // @param imu_meas: IMU measurement + // @param dt: Time step // @return Predicted nominal state - state_quat nominal_state_discrete(const state_quat& nom_state, - const imu_measurement& imu_meas, - const double dt); + void nominal_state_discrete(const imu_measurement& imu_meas, + const double dt); // @brief Predict the error state - // @param error_state: Error state - // @param nom_state: Nominal state // @param imu_meas: IMU measurement + // @param dt: Time step // @return Predicted error state - state_euler error_state_prediction(const state_euler& error_state, - const state_quat& nom_state, - const imu_measurement& imu_meas, - const double dt); + void error_state_prediction(const imu_measurement& imu_meas, + const double dt); // @brief Update the error state - // @param error_state: Error state // @param dvl_meas: DVL measurement - // @return Updated error state - state_euler measurement_update(const state_quat& nom_state, - const state_euler& error_state, - const dvl_measurement& dvl_meas); + void measurement_update(const dvl_measurement& dvl_meas); // @brief Inject the error state into the nominal state and reset the error - // state - // @param nom_state: Nominal state - // @param error_state: Error state - // @return Injected and reset state - std::pair injection_and_reset( - const state_quat& nom_state, - const state_euler& error_state); + void injection_and_reset(); // @brief Van Loan discretization // @param A_c: Continuous state transition matrix @@ -69,24 +58,31 @@ class ESKF { // @brief Calculate the delta quaternion matrix // @param nom_state: Nominal state // @return Delta quaternion matrix - Eigen::Matrix4x3d calculate_Q_delta(const state_quat& nom_state); + Eigen::Matrix4x3d calculate_q_delta(); // @brief Calculate the measurement matrix jakobian // @param nom_state: Nominal state // @return Measurement matrix - Eigen::Matrix3x19d calculate_Hx(const state_quat& nom_state); + Eigen::Matrix3x19d calculate_hx(); // @brief Calculate the full measurement matrix // @param nom_state: Nominal state // @return Measurement matrix - Eigen::Matrix3x18d calculate_H(const state_quat& nom_state); + Eigen::Matrix3x18d calculate_h_jacobian(); // @brief Calculate the measurement // @param nom_state: Nominal state // @return Measurement - Eigen::Vector3d calculate_h(const state_quat& nom_state); + Eigen::Vector3d calculate_h(); + // Process noise covariance matrix Eigen::Matrix12d Q_; + + // Member variable for the current error state + state_euler current_error_state_; + + // Member variable for the current nominal state + state_quat current_nom_state_; }; #endif // ESKF_HPP diff --git a/navigation/eskf/include/eskf/eskf_ros.hpp b/navigation/eskf/include/eskf/eskf_ros.hpp index 88f97459f..b5c0b1dab 100644 --- a/navigation/eskf/include/eskf/eskf_ros.hpp +++ b/navigation/eskf/include/eskf/eskf_ros.hpp @@ -13,7 +13,7 @@ #include #include "eskf/eskf.hpp" #include "eskf/typedefs.hpp" -#include "typedefs.hpp" +#include "spdlog/spdlog.h" class ESKFNode : public rclcpp::Node { public: diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index 925d8fd72..9be435753 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -27,6 +27,13 @@ typedef Eigen::Matrix Matrix6d; typedef Eigen::Matrix Matrix9d; } // namespace Eigen +template +Eigen::Matrix createDiagonalMatrix( + const std::vector& diag) { + return Eigen::Map>(diag.data()) + .asDiagonal(); +} + struct state_quat { Eigen::Vector3d pos = Eigen::Vector3d::Zero(); Eigen::Vector3d vel = Eigen::Vector3d::Zero(); @@ -51,8 +58,6 @@ struct state_quat { diff.accel_bias = accel_bias - other.accel_bias; return diff; } - - Eigen::Matrix3d get_R() const { return quat.toRotationMatrix(); } }; struct state_euler { @@ -91,8 +96,8 @@ struct imu_measurement { Eigen::Matrix3d R_nb; R_nb << 0, 0, -1, 0, -1, 0, -1, 0, 0; - accel = R_nb * accel_uncorrected; - gyro = R_nb * gyro_uncorrected; + accel = (R_nb * accel_uncorrected); + gyro = (R_nb * gyro_uncorrected); } }; diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index 58c532afa..06c9c44c8 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -30,27 +30,27 @@ std::pair ESKF::van_loan_discretization( return {A_d, GQG_d}; } -Eigen::Matrix4x3d ESKF::calculate_Q_delta(const state_quat& nom_state) { - Eigen::Matrix4x3d Q_delta_theta = Eigen::Matrix4x3d::Zero(); - double qw = nom_state.quat.w(); - double qx = nom_state.quat.x(); - double qy = nom_state.quat.y(); - double qz = nom_state.quat.z(); +Eigen::Matrix4x3d ESKF::calculate_q_delta() { + Eigen::Matrix4x3d q_delta_theta = Eigen::Matrix4x3d::Zero(); + double qw = current_nom_state_.quat.w(); + double qx = current_nom_state_.quat.x(); + double qy = current_nom_state_.quat.y(); + double qz = current_nom_state_.quat.z(); - Q_delta_theta << -qx, -qy, -qz, qw, -qz, qy, qz, qw, -qx, -qy, qx, qw; + q_delta_theta << -qx, -qy, -qz, qw, -qz, qy, qz, qw, -qx, -qy, qx, qw; - Q_delta_theta *= 0.5; - return Q_delta_theta; + q_delta_theta *= 0.5; + return q_delta_theta; } -Eigen::Matrix3x19d ESKF::calculate_Hx(const state_quat& nom_state) { +Eigen::Matrix3x19d ESKF::calculate_hx() { Eigen::Matrix3x19d Hx = Eigen::Matrix3x19d::Zero(); - Eigen::Quaterniond q = nom_state.quat.normalized(); + Eigen::Quaterniond q = current_nom_state_.quat.normalized(); Eigen::Matrix3d R_bn = q.toRotationMatrix(); - Eigen::Vector3d v_n = nom_state.vel; + Eigen::Vector3d v_n = current_nom_state_.vel; - Hx.block<3, 3>(0, 3) = R_bn.transpose(); + Hx.block<3, 3>(0, 3) = R_bn; Eigen::Matrix dR_dq; double qw = q.w(); @@ -58,80 +58,79 @@ Eigen::Matrix3x19d ESKF::calculate_Hx(const state_quat& nom_state) { double qy = q.y(); double qz = q.z(); + Eigen::Vector3d epsilon(qx, qy, qz); + + Eigen::Vector3d e_1(1, 0, 0); + Eigen::Vector3d e_2(0, 1, 0); + Eigen::Vector3d e_3(0, 0, 1); + dR_dq.col(0) = - 2 * Eigen::Vector3d(qw * v_n.x() + qz * v_n.y() - qy * v_n.z(), - -qz * v_n.x() + qw * v_n.y() + qx * v_n.z(), - qy * v_n.x() - qx * v_n.y() + qw * v_n.z()); + ((4 * qw * Eigen::Matrix3d::Identity()) + (2 * skew(epsilon))) * v_n; - dR_dq.col(1) = - 2 * Eigen::Vector3d(qx * v_n.x() + qy * v_n.y() + qz * v_n.z(), - qy * v_n.x() - qx * v_n.y() - qw * v_n.z(), - qz * v_n.x() + qw * v_n.y() - qx * v_n.z()); + dR_dq.col(1) = 2 * + ((e_1 * epsilon.transpose()) + (epsilon * e_1.transpose()) + + (qw * skew(e_1))) * + v_n; - dR_dq.col(2) = - 2 * Eigen::Vector3d(-qy * v_n.x() + qx * v_n.y() + qw * v_n.z(), - qx * v_n.x() + qy * v_n.y() + qz * v_n.z(), - -qw * v_n.x() + qz * v_n.y() - qy * v_n.z()); + dR_dq.col(2) = 2 * + ((e_2 * epsilon.transpose()) + (epsilon * e_2.transpose()) + + (qw * skew(e_2))) * + v_n; - dR_dq.col(3) = - 2 * Eigen::Vector3d(-qz * v_n.x() - qw * v_n.y() + qx * v_n.z(), - qw * v_n.x() - qz * v_n.y() + qy * v_n.z(), - qx * v_n.x() + qy * v_n.y() + qz * v_n.z()); + dR_dq.col(3) = 2 * + ((e_3 * epsilon.transpose()) + (epsilon * e_3.transpose()) + + (qw * skew(e_3))) * + v_n; Hx.block<3, 4>(0, 6) = dR_dq; return Hx; } -Eigen::Matrix3x18d ESKF::calculate_H(const state_quat& nom_state) { - Eigen::Matrix19x18d X_delta = Eigen::Matrix19x18d::Zero(); - X_delta.block<6, 6>(0, 0) = Eigen::Matrix6d::Identity(); - X_delta.block<4, 3>(6, 6) = calculate_Q_delta(nom_state); - X_delta.block<9, 9>(10, 9) = Eigen::Matrix9d::Identity(); +Eigen::Matrix3x18d ESKF::calculate_h_jacobian() { + Eigen::Matrix19x18d x_delta = Eigen::Matrix19x18d::Zero(); + x_delta.block<6, 6>(0, 0) = Eigen::Matrix6d::Identity(); + x_delta.block<4, 3>(6, 6) = calculate_q_delta(); + x_delta.block<9, 9>(10, 9) = Eigen::Matrix9d::Identity(); - Eigen::Matrix3x18d H = calculate_Hx(nom_state) * X_delta; + Eigen::Matrix3x18d H = calculate_hx() * x_delta; return H; } -Eigen::Matrix3x1d ESKF::calculate_h(const state_quat& nom_state) { +Eigen::Matrix3x1d ESKF::calculate_h() { Eigen::Matrix3x1d h; Eigen::Matrix3d R_bn = - nom_state.quat.normalized().toRotationMatrix().transpose(); + current_nom_state_.quat.normalized().toRotationMatrix(); - h = R_bn * nom_state.vel; + h = R_bn * current_nom_state_.vel; return h; } -state_quat ESKF::nominal_state_discrete(const state_quat& nom_state, - const imu_measurement& imu_meas, - const double dt) { +void ESKF::nominal_state_discrete(const imu_measurement& imu_meas, + const double dt) { Eigen::Vector3d acc = - nom_state.get_R() * (imu_meas.accel - nom_state.accel_bias) + - nom_state.gravity; - Eigen::Vector3d gyro = (imu_meas.gyro - nom_state.gyro_bias) * dt; - - state_quat next_nom_state; - - next_nom_state.pos = - nom_state.pos + nom_state.vel * dt + 0.5 * sq(dt) * acc; - next_nom_state.vel = nom_state.vel + dt * acc; - next_nom_state.quat = (nom_state.quat * vector3d_to_quaternion(gyro)); - next_nom_state.quat.normalize(); - next_nom_state.gyro_bias = nom_state.gyro_bias; - next_nom_state.accel_bias = nom_state.accel_bias; - next_nom_state.gravity = nom_state.gravity; - - return next_nom_state; + current_nom_state_.quat.normalized().toRotationMatrix() * + (imu_meas.accel - current_nom_state_.accel_bias) + + current_nom_state_.gravity; + Eigen::Vector3d gyro = (imu_meas.gyro - current_nom_state_.gyro_bias) * dt; + + current_nom_state_.pos = current_nom_state_.pos + + current_nom_state_.vel * dt + 0.5 * sq(dt) * acc; + current_nom_state_.vel = current_nom_state_.vel + dt * acc; + current_nom_state_.quat = + (current_nom_state_.quat * vector3d_to_quaternion(gyro)); + current_nom_state_.quat.normalize(); + current_nom_state_.gyro_bias = current_nom_state_.gyro_bias; + current_nom_state_.accel_bias = current_nom_state_.accel_bias; + current_nom_state_.gravity = current_nom_state_.gravity; } -state_euler ESKF::error_state_prediction(const state_euler& error_state, - const state_quat& nom_state, - const imu_measurement& imu_meas, - const double dt) { - Eigen::Matrix3d R = nom_state.get_R(); - Eigen::Vector3d acc = (imu_meas.accel - nom_state.accel_bias); - Eigen::Vector3d gyro = (imu_meas.gyro - nom_state.gyro_bias); +void ESKF::error_state_prediction(const imu_measurement& imu_meas, + const double dt) { + Eigen::Matrix3d R = current_nom_state_.quat.normalized().toRotationMatrix(); + Eigen::Vector3d acc = (imu_meas.accel - current_nom_state_.accel_bias); + Eigen::Vector3d gyro = (imu_meas.gyro - current_nom_state_.gyro_bias); Eigen::Matrix18d A_c = Eigen::Matrix18d::Zero(); A_c.block<3, 3>(0, 3) = Eigen::Matrix3d::Identity(); @@ -152,77 +151,60 @@ state_euler ESKF::error_state_prediction(const state_euler& error_state, auto [A_d, GQG_d] = van_loan_discretization(A_c, G_c, dt); state_euler next_error_state; - next_error_state.covariance = - A_d * error_state.covariance * A_d.transpose() + GQG_d; - - return next_error_state; + current_error_state_.covariance = + A_d * current_error_state_.covariance * A_d.transpose() + GQG_d; } -state_euler ESKF::measurement_update(const state_quat& nom_state, - const state_euler& error_state, - const dvl_measurement& dvl_meas) { - state_euler new_error_state; - - Eigen::Matrix3x18d H = calculate_H(nom_state); - Eigen::Matrix18d P = error_state.covariance; +void ESKF::measurement_update(const dvl_measurement& dvl_meas) { + Eigen::Matrix3x18d H = calculate_h_jacobian(); + Eigen::Matrix18d P = current_error_state_.covariance; Eigen::Matrix3d R = dvl_meas.cov; Eigen::Matrix3d S = H * P * H.transpose() + R; Eigen::Matrix18x3d K = P * H.transpose() * S.inverse(); - Eigen::Vector3d innovation = dvl_meas.vel - calculate_h(nom_state); - new_error_state.set_from_vector(K * innovation); + Eigen::Vector3d innovation = dvl_meas.vel - calculate_h(); + current_error_state_.set_from_vector(K * innovation); Eigen::Matrix18d I_KH = Eigen::Matrix18d::Identity() - K * H; - new_error_state.covariance = + current_error_state_.covariance = I_KH * P * I_KH.transpose() + K * R * K.transpose(); // Used joseph form for more stable calculations - - return new_error_state; } -std::pair ESKF::injection_and_reset( - const state_quat& nom_state, - const state_euler& error_state) { - state_quat next_nom_state; - - next_nom_state.pos = nom_state.pos + error_state.pos; - next_nom_state.vel = nom_state.vel + error_state.vel; - next_nom_state.quat = - nom_state.quat * vector3d_to_quaternion(error_state.euler); - next_nom_state.quat.normalize(); - next_nom_state.gyro_bias = nom_state.gyro_bias + error_state.gyro_bias; - next_nom_state.accel_bias = nom_state.accel_bias + error_state.accel_bias; - next_nom_state.gravity = nom_state.gravity + error_state.gravity; - - state_euler new_error_state; +void ESKF::injection_and_reset() { + current_nom_state_.pos = current_nom_state_.pos + current_error_state_.pos; + current_nom_state_.vel = current_nom_state_.vel + current_error_state_.vel; + current_nom_state_.quat = + current_nom_state_.quat * + vector3d_to_quaternion(current_error_state_.euler); + current_nom_state_.quat.normalize(); + current_nom_state_.gyro_bias = + current_nom_state_.gyro_bias + current_error_state_.gyro_bias; + current_nom_state_.accel_bias = + current_nom_state_.accel_bias + current_error_state_.accel_bias; + current_nom_state_.gravity = + current_nom_state_.gravity + current_error_state_.gravity; Eigen::Matrix18d G = Eigen::Matrix18d::Identity(); - new_error_state.covariance = G * error_state.covariance * G.transpose(); - - return {next_nom_state, new_error_state}; + current_error_state_.covariance = + G * current_error_state_.covariance * G.transpose(); + current_error_state_.set_from_vector(Eigen::Vector18d::Zero()); } std::pair ESKF::imu_update( - const state_quat& nom_state, - const state_euler& error_state, const imu_measurement& imu_meas, const double dt) { - state_quat next_nom_state = nominal_state_discrete(nom_state, imu_meas, dt); - state_euler next_error_state = - error_state_prediction(error_state, next_nom_state, imu_meas, dt); + nominal_state_discrete(imu_meas, dt); + error_state_prediction(imu_meas, dt); - return {next_nom_state, next_error_state}; + return {current_nom_state_, current_error_state_}; } std::pair ESKF::dvl_update( - const state_quat& nom_state, - const state_euler& error_state, const dvl_measurement& dvl_meas) { - state_euler new_error_state = - measurement_update(nom_state, error_state, dvl_meas); - auto [updated_nom_state, updated_error_state] = - injection_and_reset(nom_state, new_error_state); + measurement_update(dvl_meas); + injection_and_reset(); - return {updated_nom_state, updated_error_state}; + return {current_nom_state_, current_error_state_}; } diff --git a/navigation/eskf/src/eskf_node.cpp b/navigation/eskf/src/eskf_node.cpp index e90cebde3..196fa7916 100644 --- a/navigation/eskf/src/eskf_node.cpp +++ b/navigation/eskf/src/eskf_node.cpp @@ -2,7 +2,7 @@ int main(int argc, char** argv) { rclcpp::init(argc, argv); - RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Started ESKF Node"); + spdlog::info("Starting ESKF Node"); rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index d679d600e..06bb047b9 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -20,20 +20,20 @@ void ESKFNode::set_subscribers_and_publisher() { auto qos_sensor_data = rclcpp::QoS( rclcpp::QoSInitialization(qos_profile.history, 1), qos_profile); - this->declare_parameter("imu_topic", "imu/data_raw"); + this->declare_parameter("imu_topic"); std::string imu_topic = this->get_parameter("imu_topic").as_string(); imu_sub_ = this->create_subscription( imu_topic, qos_sensor_data, std::bind(&ESKFNode::imu_callback, this, std::placeholders::_1)); - this->declare_parameter("dvl_topic", "/orca/twist"); + this->declare_parameter("dvl_topic"); std::string dvl_topic = this->get_parameter("dvl_topic").as_string(); dvl_sub_ = this->create_subscription< geometry_msgs::msg::TwistWithCovarianceStamped>( dvl_topic, qos_sensor_data, std::bind(&ESKFNode::dvl_callback, this, std::placeholders::_1)); - this->declare_parameter("odom_topic", "odom"); + this->declare_parameter("odom_topic"); std::string odom_topic = this->get_parameter("odom_topic").as_string(); odom_pub_ = this->create_publisher( odom_topic, qos_sensor_data); @@ -41,34 +41,24 @@ void ESKFNode::set_subscribers_and_publisher() { void ESKFNode::set_parameters() { std::vector diag_Q_std; - this->declare_parameter>( - "diag_Q_std"); // gyroscope bias noise + this->declare_parameter>("diag_Q_std"); diag_Q_std = this->get_parameter("diag_Q_std").as_double_array(); Eigen::Matrix12d Q; Q.setZero(); spdlog::info("Q diagonal: {}", diag_Q_std[0]); - Q.diagonal() << sq(diag_Q_std[0]), sq(diag_Q_std[1]), - sq(diag_Q_std[2]), // acceleration noise - sq(diag_Q_std[3]), sq(diag_Q_std[4]), - sq(diag_Q_std[5]), // gyroscope noise - sq(diag_Q_std[6]), sq(diag_Q_std[7]), - sq(diag_Q_std[8]), // acceleration bias noise - sq(diag_Q_std[9]), sq(diag_Q_std[10]), - sq(diag_Q_std[11]); // gyroscope bias noise + Q.diagonal() << sq(diag_Q_std[0]), sq(diag_Q_std[1]), sq(diag_Q_std[2]), + sq(diag_Q_std[3]), sq(diag_Q_std[4]), sq(diag_Q_std[5]), + sq(diag_Q_std[6]), sq(diag_Q_std[7]), sq(diag_Q_std[8]), + sq(diag_Q_std[9]), sq(diag_Q_std[10]), sq(diag_Q_std[11]); eskf_params_.Q = Q; eskf_ = std::make_unique(eskf_params_); - Eigen::Matrix18d P; - P.setZero(); - P.diagonal() << 1.0, 1.0, 1.0, // position - 0.1, 0.1, 0.1, // velocity - 0.1, 0.1, 0.1, // euler angles - 0.001, 0.001, 0.001, // accel bias - 0.001, 0.001, 0.001, // gyro bias - 0.001, 0.001, 0.001; // gravity + std::vector diag_p_init = + this->declare_parameter>("diag_p_init"); + Eigen::Matrix18d P = createDiagonalMatrix<18>(diag_p_init); error_state_.covariance = P; } @@ -91,8 +81,7 @@ void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { msg->angular_velocity.y, msg->angular_velocity.z; imu_meas_.correct(); - std::tie(nom_state_, error_state_) = - eskf_->imu_update(nom_state_, error_state_, imu_meas_, dt); + std::tie(nom_state_, error_state_) = eskf_->imu_update(imu_meas_, dt); } void ESKFNode::dvl_callback( @@ -105,8 +94,7 @@ void ESKFNode::dvl_callback( msg->twist.covariance[12], msg->twist.covariance[13], msg->twist.covariance[14]; - std::tie(nom_state_, error_state_) = - eskf_->dvl_update(nom_state_, error_state_, dvl_meas_); + std::tie(nom_state_, error_state_) = eskf_->dvl_update(dvl_meas_); } void ESKFNode::publish_odom() { @@ -125,6 +113,6 @@ void ESKFNode::publish_odom() { odom_msg.twist.twist.linear.y = nom_state_.vel.y(); odom_msg.twist.twist.linear.z = nom_state_.vel.z(); - odom_msg.header.stamp = this->now(); // Add timestamp to the message + odom_msg.header.stamp = this->now(); odom_pub_->publish(odom_msg); } diff --git a/navigation/eskf/src/eskf_utils.cpp b/navigation/eskf/src/eskf_utils.cpp index 930167eaa..133589d05 100644 --- a/navigation/eskf/src/eskf_utils.cpp +++ b/navigation/eskf/src/eskf_utils.cpp @@ -18,7 +18,9 @@ Eigen::Quaterniond vector3d_to_quaternion(const Eigen::Vector3d& vector) { return Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0); } else { Eigen::Vector3d axis = vector / angle; - return Eigen::Quaterniond(Eigen::AngleAxisd(angle, axis)); + Eigen::Quaterniond quat = + Eigen::Quaterniond(Eigen::AngleAxisd(angle, axis)); + return quat; } } @@ -27,5 +29,6 @@ Eigen::Quaterniond euler_to_quaternion(const Eigen::Vector3d& euler) { q = Eigen::AngleAxisd(euler.z(), Eigen::Vector3d::UnitZ()) * Eigen::AngleAxisd(euler.y(), Eigen::Vector3d::UnitY()) * Eigen::AngleAxisd(euler.x(), Eigen::Vector3d::UnitX()); + q.normalize(); return q; } From f0079088ace3225432cc897cca063ae2daf340a2 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Thu, 17 Apr 2025 18:27:14 +0200 Subject: [PATCH 15/30] feat: modified imu correction and added in tested imu noise --- navigation/eskf/config/eskf_params.yaml | 7 +- navigation/eskf/include/eskf/eskf.hpp | 1 + navigation/eskf/include/eskf/eskf_ros.hpp | 2 + navigation/eskf/include/eskf/typedefs.hpp | 16 +- navigation/eskf/src/eskf.cpp | 21 +- navigation/eskf/src/eskf_ros.cpp | 21 +- navigation/eskf/src/eskf_utils.cpp | 2 +- navigation/ukf_okid/CMakeLists.txt | 23 + navigation/ukf_okid/launch/ukf.launch.py | 16 + navigation/ukf_okid/package.xml | 22 + .../ukf_python/{__ini__.py => __init__.py} | 0 navigation/ukf_okid/ukf_python/rest.py | 40 - navigation/ukf_okid/ukf_python/ukf_okid.py | 100 +-- .../ukf_okid/ukf_python/ukf_okid_class.py | 216 +++++- navigation/ukf_okid/ukf_python/ukf_ros.py | 117 +++ navigation/ukf_okid/ukf_python/ukf_test.py | 721 ++++++++++-------- navigation/ukf_okid/ukf_python/ukf_test_2.py | 40 + navigation/ukf_okid/ukf_python/ukf_utils.py | 1 + 18 files changed, 926 insertions(+), 440 deletions(-) create mode 100644 navigation/ukf_okid/CMakeLists.txt create mode 100644 navigation/ukf_okid/launch/ukf.launch.py create mode 100644 navigation/ukf_okid/package.xml rename navigation/ukf_okid/ukf_python/{__ini__.py => __init__.py} (100%) delete mode 100644 navigation/ukf_okid/ukf_python/rest.py create mode 100755 navigation/ukf_okid/ukf_python/ukf_ros.py create mode 100644 navigation/ukf_okid/ukf_python/ukf_test_2.py diff --git a/navigation/eskf/config/eskf_params.yaml b/navigation/eskf/config/eskf_params.yaml index 87d50ee44..639af1fc9 100644 --- a/navigation/eskf/config/eskf_params.yaml +++ b/navigation/eskf/config/eskf_params.yaml @@ -1,7 +1,8 @@ eskf_node: ros__parameters: imu_topic: imu/data_raw - dvl_twist: /orca/twist + dvl_topic: /orca/twist odom_topic: odom - diag_Q_std: [0.0103, 0.0118, 0.0043, 0.00193, 0.00306, 0.00118, 0.000001, 0.000001, 0.000001, 0.00001, 0.00001, 0.00001] - diag_p_init: [1.0, 1.0, 1.0, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] + diag_Q_std: [0.027293, 0.028089, 0.029067, 0.00255253, 0.00270035, 0.00280294, 0.000001, 0.000001, 0.000001, 0.00001, 0.00001, 0.00001] + diag_p_init: [1.0, 1.0, 0.5, 0.5, 0.5, 1.0, 0.1, 0.1, 0.1, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] + imu_frame: [0, 0, -1, 0, -1, 0, -1, 0, 0 ] diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp index 5cc3e0708..80b086d26 100644 --- a/navigation/eskf/include/eskf/eskf.hpp +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -25,6 +25,7 @@ class ESKF { const dvl_measurement& dvl_meas); private: + // @brief Predict the nominal state // @param imu_meas: IMU measurement // @param dt: Time step diff --git a/navigation/eskf/include/eskf/eskf_ros.hpp b/navigation/eskf/include/eskf/eskf_ros.hpp index b5c0b1dab..e0b777c86 100644 --- a/navigation/eskf/include/eskf/eskf_ros.hpp +++ b/navigation/eskf/include/eskf/eskf_ros.hpp @@ -64,6 +64,8 @@ class ESKFNode : public rclcpp::Node { rclcpp::Time last_imu_time_; bool first_imu_msg_received_ = false; + + Eigen::Matrix3d R_imu_eskf_; }; #endif // ESKF_ROS_HPP diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index 9be435753..fac89baa7 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -7,6 +7,7 @@ #include #include +#include namespace Eigen { typedef Eigen::Matrix Vector19d; @@ -40,7 +41,11 @@ struct state_quat { Eigen::Quaterniond quat = Eigen::Quaterniond::Identity(); Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero(); Eigen::Vector3d accel_bias = Eigen::Vector3d::Zero(); - Eigen::Vector3d gravity = Eigen::Vector3d(0, 0, 9.81); + Eigen::Vector3d gravity = Eigen::Vector3d::Zero(); + + state_quat() { + gravity << 0, 0, 9.81; + } Eigen::Vector19d as_vector() const { Eigen::Vector19d vec; @@ -89,16 +94,7 @@ struct state_euler { struct imu_measurement { Eigen::Vector3d accel = Eigen::Vector3d::Zero(); Eigen::Vector3d gyro = Eigen::Vector3d::Zero(); - Eigen::Vector3d accel_uncorrected = Eigen::Vector3d::Zero(); - Eigen::Vector3d gyro_uncorrected = Eigen::Vector3d::Zero(); - void correct() { - Eigen::Matrix3d R_nb; - R_nb << 0, 0, -1, 0, -1, 0, -1, 0, 0; - - accel = (R_nb * accel_uncorrected); - gyro = (R_nb * gyro_uncorrected); - } }; struct dvl_measurement { diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index 06c9c44c8..bbd367c7f 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -107,20 +107,24 @@ Eigen::Matrix3x1d ESKF::calculate_h() { return h; } + void ESKF::nominal_state_discrete(const imu_measurement& imu_meas, const double dt) { Eigen::Vector3d acc = - current_nom_state_.quat.normalized().toRotationMatrix() * - (imu_meas.accel - current_nom_state_.accel_bias) + + current_nom_state_.quat.normalized().toRotationMatrix() * imu_meas.accel + current_nom_state_.gravity; - Eigen::Vector3d gyro = (imu_meas.gyro - current_nom_state_.gyro_bias) * dt; + Eigen::Vector3d gyro = imu_meas.gyro * dt/2; current_nom_state_.pos = current_nom_state_.pos + current_nom_state_.vel * dt + 0.5 * sq(dt) * acc; current_nom_state_.vel = current_nom_state_.vel + dt * acc; - current_nom_state_.quat = - (current_nom_state_.quat * vector3d_to_quaternion(gyro)); + + + current_nom_state_.quat = (current_nom_state_.quat * vector3d_to_quaternion(gyro)); + + current_nom_state_.quat.normalize(); + current_nom_state_.gyro_bias = current_nom_state_.gyro_bias; current_nom_state_.accel_bias = current_nom_state_.accel_bias; current_nom_state_.gravity = current_nom_state_.gravity; @@ -129,8 +133,8 @@ void ESKF::nominal_state_discrete(const imu_measurement& imu_meas, void ESKF::error_state_prediction(const imu_measurement& imu_meas, const double dt) { Eigen::Matrix3d R = current_nom_state_.quat.normalized().toRotationMatrix(); - Eigen::Vector3d acc = (imu_meas.accel - current_nom_state_.accel_bias); - Eigen::Vector3d gyro = (imu_meas.gyro - current_nom_state_.gyro_bias); + Eigen::Vector3d acc = imu_meas.accel; + Eigen::Vector3d gyro = imu_meas.gyro; Eigen::Matrix18d A_c = Eigen::Matrix18d::Zero(); A_c.block<3, 3>(0, 3) = Eigen::Matrix3d::Identity(); @@ -148,7 +152,8 @@ void ESKF::error_state_prediction(const imu_measurement& imu_meas, G_c.block<3, 3>(9, 6) = Eigen::Matrix3d::Identity(); G_c.block<3, 3>(12, 9) = Eigen::Matrix3d::Identity(); - auto [A_d, GQG_d] = van_loan_discretization(A_c, G_c, dt); + Eigen::Matrix18d A_d, GQG_d; + std::tie(A_d, GQG_d) = van_loan_discretization(A_c, G_c, dt); state_euler next_error_state; current_error_state_.covariance = diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index 06bb047b9..a35273103 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -40,6 +40,11 @@ void ESKFNode::set_subscribers_and_publisher() { } void ESKFNode::set_parameters() { + std::vector R_imu_correction; + this->declare_parameter>("imu_frame"); + R_imu_correction = get_parameter("imu_rotation_matrix").as_double_array(); + R_imu_eskf_ = Eigen::Map>(R_imu_correction.data()); + std::vector diag_Q_std; this->declare_parameter>("diag_Q_std"); @@ -75,11 +80,17 @@ void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { double dt = (current_time - last_imu_time_).nanoseconds() * 1e-9; last_imu_time_ = current_time; - imu_meas_.accel_uncorrected << msg->linear_acceleration.x, - msg->linear_acceleration.y, msg->linear_acceleration.z; - imu_meas_.gyro_uncorrected << msg->angular_velocity.x, - msg->angular_velocity.y, msg->angular_velocity.z; - imu_meas_.correct(); + Eigen::Vector3d raw_accel(msg->linear_acceleration.x, + msg->linear_acceleration.y, + msg->linear_acceleration.z); + + imu_meas_.accel = R_imu_eskf_ * raw_accel; + + Eigen::Vector3d raw_gyro(msg->angular_velocity.x, + msg->angular_velocity.y, + msg->angular_velocity.z); + + imu_meas_.gyro = R_imu_eskf_ * raw_gyro; std::tie(nom_state_, error_state_) = eskf_->imu_update(imu_meas_, dt); } diff --git a/navigation/eskf/src/eskf_utils.cpp b/navigation/eskf/src/eskf_utils.cpp index 133589d05..a07f3acda 100644 --- a/navigation/eskf/src/eskf_utils.cpp +++ b/navigation/eskf/src/eskf_utils.cpp @@ -20,7 +20,7 @@ Eigen::Quaterniond vector3d_to_quaternion(const Eigen::Vector3d& vector) { Eigen::Vector3d axis = vector / angle; Eigen::Quaterniond quat = Eigen::Quaterniond(Eigen::AngleAxisd(angle, axis)); - return quat; + return quat.normalized(); } } diff --git a/navigation/ukf_okid/CMakeLists.txt b/navigation/ukf_okid/CMakeLists.txt new file mode 100644 index 000000000..901ca044b --- /dev/null +++ b/navigation/ukf_okid/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 3.8) +project(ukf_python) + +find_package(ament_cmake_python REQUIRED) +find_package(rclpy REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(vortex_msgs REQUIRED) + +install(DIRECTORY + launch + config + DESTINATION share/${PROJECT_NAME} +) + +ament_python_install_package(${PROJECT_NAME}) + +install(PROGRAMS + ukf_python/ukf_ros.py + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/navigation/ukf_okid/launch/ukf.launch.py b/navigation/ukf_okid/launch/ukf.launch.py new file mode 100644 index 000000000..62a439b94 --- /dev/null +++ b/navigation/ukf_okid/launch/ukf.launch.py @@ -0,0 +1,16 @@ +import os + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch_ros.actions import Node + + +def generate_launch_description() -> LaunchDescription: + + ukf_node = Node( + package="ukf_python", + executable="ukf_ros.py", + name="ukf_node", + ) + + return LaunchDescription([ukf_node]) diff --git a/navigation/ukf_okid/package.xml b/navigation/ukf_okid/package.xml new file mode 100644 index 000000000..1c1b2b4cb --- /dev/null +++ b/navigation/ukf_okid/package.xml @@ -0,0 +1,22 @@ + + + + ukf_python + 1.0.0 + Uscented Kalman filter for AUV model + talha + MIT + + ament_cmake_python + + rclpy + geometry_msgs + nav_msgs + vortex_msgs + python-control-pip + std_msgs + + + ament_cmake + + diff --git a/navigation/ukf_okid/ukf_python/__ini__.py b/navigation/ukf_okid/ukf_python/__init__.py similarity index 100% rename from navigation/ukf_okid/ukf_python/__ini__.py rename to navigation/ukf_okid/ukf_python/__init__.py diff --git a/navigation/ukf_okid/ukf_python/rest.py b/navigation/ukf_okid/ukf_python/rest.py deleted file mode 100644 index c8b4f3b14..000000000 --- a/navigation/ukf_okid/ukf_python/rest.py +++ /dev/null @@ -1,40 +0,0 @@ -def mean_set(set_points: list[StateQuat], weights: np.ndarray = None) -> np.ndarray: - """Function that calculates the mean of a set of points""" - n = len(set_points[0].as_vector()) - 1 - mean_value = StateQuat() - - if weights is None: - for i in range(2 * n + 1): - weight_temp_list = (1 / (2 * n + 1)) * np.ones(2 * n + 1) - mean_value.add_without_quaternions(weight_temp_list[i] * set_points[i]) - - mean_value.orientation = iterative_quaternion_mean_statequat( - set_points, weight_temp_list - ) - - else: - for i in range(2 * n + 1): - mean_value.add_without_quaternions(weights[i] * set_points[i]) - - mean_value.orientation = iterative_quaternion_mean_statequat( - set_points, weights - ) - - return mean_value.as_vector() - - -def mean_measurement( - set_points: list[MeasModel], weights: np.ndarray = None -) -> np.ndarray: - """Function that calculates the mean of a set of points""" - n = len(set_points) - mean_value = MeasModel() - - if weights is None: - for i in range(n): - mean_value = mean_value + set_points[i] - else: - for i in range(n): - mean_value = mean_value + (weights[i] * set_points[i]) - - return mean_value.measurement diff --git a/navigation/ukf_okid/ukf_python/ukf_okid.py b/navigation/ukf_okid/ukf_python/ukf_okid.py index 50c68e08c..af61d1a79 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid.py @@ -1,69 +1,77 @@ import numpy as np -from ukf_okid_class import * +from ukf_utils import print_StateQuat +from ukf_okid_class import ( + MeasModel, + StateQuat, + covariance_measurement, + covariance_set, + cross_covariance, + mean_measurement, + mean_set, + process_model, + okid_process_model, +) class UKF: - def __init__(self, process_model: process_model, x_0, P_0, Q, R): + def __init__(self, process_model: okid_process_model, x_0, P_0, Q, G): self.x = x_0 self.P = P_0 self.Q = Q - self.R = R + self.G = G self.process_model = process_model self.sigma_points_list = None + self.measurement_updated = MeasModel() self.y_i = None self.weight = None - self.T = self.generate_T_matrix(len(P_0)) + self.delta = self.generate_delta_matrix(len(x_0.as_vector()) - 1) + self.cross_correlation = None - def generate_T_matrix(self, n: float) -> np.ndarray: - """Generates the orthonormal transformation matrix T used in the TUKF sigma point generation. + def generate_delta_matrix(self, n: float) -> np.ndarray: + """Generates the weight matrix used in the TUKF sigma point generation. Parameters: n (int): The state dimension. Returns: - T (np.ndarray): An n x 2n orthonormal transformation matrix used to generate TUKF sigma points. + delta (np.ndarray): An n x 2n orthonormal transformation matrix used to generate TUKF sigma points. """ - T = np.zeros((n, n)) + delta = np.zeros((n, 2 * n)) + k = 0.01 #Tuning parameter to ensure pos def - for i in range(n): + for i in range(2 * n): for j in range(n // 2): - T[2 * j - 2, i - 1] = np.sqrt(2) * np.cos(((2 * j - 1) * i * np.pi) / n) - T[2 * j - 1, i - 1] = np.sqrt(2) * np.sin(((2 * j - 1) * i * np.pi) / n) - - if n % 2 == 1: # if n is odd - T[n - 1, i - 1] = (-1) ** i - - T = T / np.sqrt(2) - - return T + delta[2 * j + 1, i] = np.sqrt(2) * np.sin((2 * j - 1)) * ((k * np.pi) / n) + delta[2 * j, i] = np.sqrt(2) * np.cos((2 * j - 1)) * ((k * np.pi) / n) + + if (n % 2) == 1: + delta[n-1, i] = (-1)**i + return delta def sigma_points(self, current_state: StateQuat) -> list[StateQuat]: - """Functions that generate the sigma points for the UKF""" + """Functions that generate the sigma points for the UKF.""" n = len(current_state.covariance) - I = np.hstack([np.eye(n), -np.eye(n)]) - my = np.sqrt(n) * I - delta = self.T @ my - S = np.linalg.cholesky(current_state.covariance + self.Q) self.sigma_points_list = [StateQuat() for _ in range(2 * n)] for index, state in enumerate(self.sigma_points_list): - delta_x = S @ delta[:, index] - state.fill_states_different_dim(current_state.as_vector(), delta_x) + delta_x = S @ self.delta[:, index] + state.fill_dynamic_states(current_state.as_vector(), delta_x) return self.sigma_points_list def unscented_transform(self, current_state: StateQuat) -> StateQuat: - """The unscented transform function generates the priori state estimate""" - _ = self.sigma_points(current_state) + """The unscented transform function generates the priori state estimate.""" + self.sigma_points(current_state) n = len(current_state.covariance) self.y_i = [StateQuat() for _ in range(2 * n)] - for i in range(2 * n): - self.process_model.model_prediction(self.sigma_points_list[i]) + for i, state in enumerate(self.sigma_points_list): + self.process_model.model_prediction(state) + self.process_model.state_vector_prev = state self.y_i[i] = self.process_model.euler_forward() state_estimate = StateQuat() @@ -75,42 +83,36 @@ def unscented_transform(self, current_state: StateQuat) -> StateQuat: def measurement_update( self, current_state: StateQuat, measurement: MeasModel - ) -> tuple[MeasModel, np.ndarray]: - """Function that updates the state estimate with a measurement + ) -> None: + """Function that updates the state estimate with a measurement. + Hopefully this is the DVL or GNSS """ n = len(current_state.covariance) z_i = [MeasModel() for _ in range(2 * n)] - for i in range(2 * n): - z_i[i] = measurement.H(self.sigma_points_list[i]) + for i, state in enumerate(self.sigma_points_list): + z_i[i] = measurement.H(state) - meas_update = MeasModel() + self.measurement_updated.measurement = mean_measurement(z_i) - meas_update.measurement = mean_measurement(z_i) + self.measurement_updated.covariance = covariance_measurement(z_i, self.measurement_updated.measurement) - meas_update.covariance = covariance_measurement(z_i, meas_update.measurement) - - cross_correlation = cross_covariance( - self.y_i, current_state.as_vector(), z_i, meas_update.measurement + self.cross_correlation = cross_covariance( + self.y_i, current_state.as_vector(), z_i, self.measurement_updated.measurement ) - return meas_update, cross_correlation - def posteriori_estimate( self, current_state: StateQuat, - cross_correlation: np.ndarray, measurement: MeasModel, - ex_measuremnt: MeasModel, ) -> StateQuat: - """Calculates the posteriori estimate using measurement and the prior estimate""" + """Calculates the posteriori estimate using measurement and the prior estimate.""" nu_k = MeasModel() + nu_k.measurement = measurement.measurement - self.measurement_updated.measurement + nu_k.covariance = self.measurement_updated.covariance + measurement.covariance - nu_k.measurement = measurement.measurement - ex_measuremnt.measurement - nu_k.covariance = ex_measuremnt.covariance + measurement.covariance - - K_k = np.dot(cross_correlation, np.linalg.inv(nu_k.covariance)) + K_k = np.dot(self.cross_correlation, np.linalg.inv(nu_k.covariance)) posteriori_estimate = StateQuat() @@ -121,6 +123,4 @@ def posteriori_estimate( K_k, np.dot(nu_k.covariance, np.transpose(K_k)) ) - self.process_model.state_vector_prev = posteriori_estimate - return posteriori_estimate diff --git a/navigation/ukf_okid/ukf_python/ukf_okid_class.py b/navigation/ukf_okid/ukf_python/ukf_okid_class.py index 45bbffcfe..5558ad754 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid_class.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid_class.py @@ -2,6 +2,54 @@ import numpy as np +@dataclass +class okid: + """A class to represent the parameters for the OKID algorithm.""" + + inertia: np.ndarray = field(default_factory=lambda: np.array([0.68, 0.0, 0.0, 0.0, 3.32, 0.0, 0.0, 0.0, 3.34])) + added_mass: np.ndarray = field(default_factory=lambda: np.array([1.0,1.0,1.0,2.0,2.0,2.0])) + damping_linear: np.ndarray = field(default_factory=lambda: np.array([1.0,1.0,1.0,1.0,1.0,1.0])) + + def fill(self, state: np.ndarray) -> None: + """Fills the okid_params object with values from a numpy array.""" + self.inertia = state[0:9] + self.added_mass = state[9:15] + self.damping_linear = state[15:] + + def as_vector(self) -> np.ndarray: + """Returns the okid_params as a numpy array.""" + return np.concatenate([self.inertia, self.added_mass, self.damping_linear]) + + def __add__(self, other: 'okid') -> 'okid': + """Defines the addition operation between two okid_params objects.""" + result = okid() + result.inertia = self.inertia + other.inertia + result.added_mass = self.added_mass + other.added_mass + result.damping_linear = self.damping_linear + other.damping_linear + return result + def __sub__(self, other: 'okid') -> 'okid': + """Defines the subtraction operation between two okid_params objects.""" + result = okid() + result.inertia = self.inertia - other.inertia + result.added_mass = self.added_mass - other.added_mass + result.damping_linear = self.damping_linear - other.damping_linear + return result + + def __sub__(self, other: np.ndarray) -> 'okid': + """ Defines sub between okid_params and np.ndarray.""" + result = okid() + result.inertia = self.inertia - other[0:9] + result.added_mass = self.added_mass - other[9:15] + result.damping_linear = self.damping_linear - other[15:] + return result + + def __rmul__(self, scalar: float) -> 'okid': + """Defines the multiplication operation between a scalar and okid_params object.""" + result = okid() + result.inertia = scalar * self.inertia + result.added_mass = scalar * self.added_mass + result.damping_linear = scalar * self.damping_linear + return result @dataclass class StateQuat: @@ -11,10 +59,16 @@ class StateQuat: orientation: np.ndarray = field(default_factory=lambda: np.array([1, 0, 0, 0])) velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) - covariance: np.ndarray = field(default_factory=lambda: np.zeros((12, 12))) + okid_params: okid = field(default_factory=okid) + covariance: np.ndarray = field(default_factory=lambda: np.zeros((33, 33))) def as_vector(self) -> np.ndarray: """Returns the StateVector as a numpy array.""" + return np.concatenate( + [self.position, self.orientation, self.velocity, self.angular_velocity, self.okid_params.as_vector()] + ) + def dynamic_part(self) -> np.ndarray: + """Returns the dynamic part of the state vector.""" return np.concatenate( [self.position, self.orientation, self.velocity, self.angular_velocity] ) @@ -53,6 +107,16 @@ def fill_states(self, state: np.ndarray) -> None: self.orientation = state[3:7] self.velocity = state[7:10] self.angular_velocity = state[10:13] + self.okid_params.fill(state[13:]) + + def fill_dynamic_states(self, state: np.ndarray, state_euler: np.ndarray) -> None: + """Fills only the dynamic part of the state vector with the values from a numpy array.""" + self.position = state[0:3] + state_euler[0:3] + self.orientation = quaternion_super_product( + state[3:7], euler_to_quat(state_euler[3:6]) + ) + self.velocity = state[7:10] + state_euler[6:9] + self.angular_velocity = state[10:13] + state_euler[9:12] def fill_states_different_dim( self, state: np.ndarray, state_euler: np.ndarray @@ -64,6 +128,7 @@ def fill_states_different_dim( ) self.velocity = state[7:10] + state_euler[6:9] self.angular_velocity = state[10:13] + state_euler[9:12] + self.okid_params.fill(state[13:] + state_euler[12:]) def subtract(self, other: 'StateQuat', error_ori: 'np.ndarray') -> np.ndarray: """Subtracts two StateQuat objects, returning the difference with Euler angles.""" @@ -72,6 +137,7 @@ def subtract(self, other: 'StateQuat', error_ori: 'np.ndarray') -> np.ndarray: new_array[3:6] = error_ori new_array[6:9] = self.velocity - other.velocity new_array[9:12] = self.angular_velocity - other.angular_velocity + new_array[12:] = self.okid_params.as_vector() - other.okid_params.as_vector() return new_array @@ -84,6 +150,7 @@ def __add__(self, other: 'StateQuat') -> 'StateQuat': ) new_state.velocity = self.velocity + other.velocity new_state.angular_velocity = self.angular_velocity + other.angular_velocity + new_state.okid_params = self.okid_params + other.okid_params return new_state @@ -94,6 +161,7 @@ def __sub__(self, other: 'StateQuat') -> 'StateQuat': new_state.orientation = quaternion_error(self.orientation, other.orientation) new_state.velocity = self.velocity - other.velocity new_state.angular_velocity = self.angular_velocity - other.angular_velocity + new_state.okid_params = self.okid_params - other.okid_params return new_state.as_vector() @@ -104,6 +172,7 @@ def __rmul__(self, scalar: float) -> 'StateQuat': new_state.orientation = quat_norm(scalar * self.orientation) new_state.velocity = scalar * self.velocity new_state.angular_velocity = scalar * self.angular_velocity + new_state.okid_params = scalar * self.okid_params return new_state @@ -116,6 +185,7 @@ def insert_weights(self, weights: np.ndarray) -> np.ndarray: ) new_state.velocity = self.velocity - weights[6:9] new_state.angular_velocity = self.angular_velocity - weights[9:12] + new_state.okid_params = self.okid_params - weights[12:] return new_state.as_vector() @@ -124,6 +194,7 @@ def add_without_quaternions(self, other: 'StateQuat') -> None: self.position += other.position self.velocity += other.velocity self.angular_velocity += other.angular_velocity + self.okid_params += other.okid_params @dataclass @@ -136,9 +207,9 @@ class MeasModel: def H(self, state: StateQuat) -> 'MeasModel': """Calculates the measurement matrix.""" H = np.zeros((3, 13)) - H[0:3, 7:10] = np.eye(3) + H[:, 7:10] = np.eye(3) z_i = MeasModel() - z_i.measurement = np.dot(H, state.as_vector()) + z_i.measurement = np.dot(H, state.dynamic_part()) return z_i def __add__(self, other: 'MeasModel') -> 'MeasModel': @@ -263,10 +334,112 @@ def euler_forward(self) -> StateQuat: + self.state_vector_dot.angular_velocity * self.dt ) return self.state_vector +@dataclass +class okid_process_model: + state_vector: StateQuat = field(default_factory=StateQuat) + state_vector_dot: StateQuat = field(default_factory=StateQuat) + state_vector_prev: StateQuat = field(default_factory=StateQuat) + Control_input: np.ndarray = field(default_factory=lambda: np.zeros(6)) + mass_interia_matrix: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) + added_mass: np.ndarray = field(default_factory=lambda: np.zeros(6)) + damping_linear: np.ndarray = field(default_factory=lambda: np.zeros(6)) + m: float = 30.0 + inertia: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) + r_b_bg: np.ndarray = field(default_factory=lambda: np.zeros(3)) + dt: float = 0.01 + def R(self) -> np.ndarray: + """Calculates the rotation matrix.""" + nu, e_1, e_2, e_3 = self.state_vector.orientation + R = np.array( + [ + [ + 1 - 2 * e_2**2 - 2 * e_3**2, + 2 * e_1 * e_2 - 2 * nu * e_3, + 2 * e_1 * e_3 + 2 * nu * e_2, + ], + [ + 2 * e_1 * e_2 + 2 * nu * e_3, + 1 - 2 * e_1**2 - 2 * e_3**2, + 2 * e_2 * e_3 - 2 * nu * e_1, + ], + [ + 2 * e_1 * e_3 - 2 * nu * e_2, + 2 * e_2 * e_3 + 2 * nu * e_1, + 1 - 2 * e_1**2 - 2 * e_2**2, + ], + ] + ) + return R + + def T(self) -> np.ndarray: + """Calculates the transformation matrix.""" + nu, e_1, e_2, e_3 = self.state_vector.orientation + T = 0.5 * np.array( + [[-e_1, -e_2, -e_3], [nu, -e_3, e_2], [e_3, nu, -e_1], [-e_2, e_1, nu]] + ) + return T + + def Crb(self) -> np.ndarray: + """Calculates the Coriolis matrix.""" + ang_vel = self.state_vector.angular_velocity + ang_vel_skew = skew_symmetric(ang_vel) + lever_arm_skew = skew_symmetric(self.r_b_bg) + Crb = np.zeros((6, 6)) + Crb[0:3, 0:3] = self.m * ang_vel_skew + Crb[3:6, 3:6] = -skew_symmetric(np.dot(self.inertia, ang_vel)) + Crb[0:3, 3:6] = -self.m * np.dot(ang_vel_skew, lever_arm_skew) + Crb[3:6, 0:3] = self.m * np.dot(lever_arm_skew, ang_vel_skew) + return Crb + + def D(self) -> np.ndarray: + """Calculates the damping matrix.""" + D_l = -np.diag(self.damping_linear) + + return D_l + + def model_prediction(self, state: StateQuat) -> None: + """Calculates the model of the system.""" + self.state_vector = state + """ + separate out the different okid values + """ + self.inertia = state.okid_params.inertia.reshape((3, 3)) + self.added_mass = state.okid_params.added_mass + self.damping_linear = state.okid_params.damping_linear + + self.state_vector_dot.position = np.dot(self.R(), self.state_vector.velocity) + self.state_vector_dot.orientation = np.dot( + self.T(), self.state_vector.angular_velocity + ) + Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ ( + self.Control_input + - np.dot(self.Crb(), self.state_vector.nu()) + - np.dot(self.D(), self.state_vector.nu()) + ) + self.state_vector_dot.velocity = Nu[:3] + self.state_vector_dot.angular_velocity = Nu[3:] + + def euler_forward(self) -> None: + """Calculates the forward Euler integration.""" + self.state_vector.position = ( + self.state_vector_prev.position + self.state_vector_dot.position * self.dt + ) + self.state_vector.orientation = quat_norm( + self.state_vector_prev.orientation + + self.state_vector_dot.orientation * self.dt + ) + self.state_vector.velocity = ( + self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt + ) + self.state_vector.angular_velocity = ( + self.state_vector_prev.angular_velocity + + self.state_vector_dot.angular_velocity * self.dt + ) + return self.state_vector def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: - """Converts Euler angles to a quaternion""" + """Converts Euler angles to a quaternion.""" psi, theta, phi = euler_angles c_psi = np.cos(psi / 2) s_psi = np.sin(psi / 2) @@ -288,7 +461,7 @@ def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: def quat_to_euler(quat: np.ndarray) -> np.ndarray: - """Converts a quaternion to Euler angles""" + """Converts a quaternion to Euler angles.""" nu, eta_1, eta_2, eta_3 = quat phi = np.arctan2(2 * (eta_2 * eta_3 + nu * eta_1), 1 - 2 * (eta_1**2 + eta_2**2)) @@ -299,7 +472,7 @@ def quat_to_euler(quat: np.ndarray) -> np.ndarray: def quat_norm(quat: np.ndarray) -> np.ndarray: - """Function that normalizes a quaternion""" + """Function that normalizes a quaternion.""" quat = quat / np.linalg.norm(quat) return quat @@ -348,7 +521,7 @@ def quaternion_super_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: - """Calculates the error between two quaternions""" + """Calculates the error between two quaternions.""" quat_2_inv = np.array([quat_2[0], -quat_2[1], -quat_2[2], -quat_2[3]]) error_quat = quaternion_super_product(quat_1, quat_2_inv) @@ -359,17 +532,15 @@ def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: def iterative_quaternion_mean_statequat( state_list: list[StateQuat], tol: float = 1e-6, max_iter: int = 100 ) -> np.ndarray: - """Computes the weighted mean of the quaternion orientations from a list of StateQuat objects - using an iterative approach, without requiring the caller to manually extract the quaternion. + """Computes the iterative mean of quaternion orientations from StateQuat objects. - Parameters: - state_list (list[StateQuat]): List of StateQuat objects. - weights (np.ndarray): Weights for each state. - tol (float): Convergence tolerance. - max_iter (int): Maximum number of iterations. + Args: + state_list: List of StateQuat objects + tol: Convergence tolerance + max_iter: Maximum iterations Returns: - np.ndarray: The averaged quaternion as a 4-element numpy array. + Mean quaternion as numpy array """ sigma_quats = [state.orientation for state in state_list] n = len(state_list) @@ -412,7 +583,7 @@ def iterative_quaternion_mean_statequat( def mean_set(set_points: list[StateQuat]) -> np.ndarray: - """Function calculates the mean vector of a set of points + """Function calculates the mean vector of a set of points. Args: set_points (list[StateQuat]): List of StateQuat objects @@ -426,7 +597,10 @@ def mean_set(set_points: list[StateQuat]) -> np.ndarray: for state in set_points: mean_value.add_without_quaternions(state) - mean_value = (1 / (n)) * mean_value + mean_value.position = (1 / n) * mean_value.position + mean_value.velocity = (1 / n) * mean_value.velocity + mean_value.angular_velocity = (1 / n) * mean_value.angular_velocity + mean_value.okid_params = (1 / n) * mean_value.okid_params mean_value.orientation = iterative_quaternion_mean_statequat(set_points) @@ -434,7 +608,7 @@ def mean_set(set_points: list[StateQuat]) -> np.ndarray: def mean_measurement(set_points: list[MeasModel]) -> np.ndarray: - """Function that calculates the mean of a set of points""" + """Function that calculates the mean of a set of points.""" n = len(set_points) mean_value = MeasModel() @@ -447,7 +621,7 @@ def mean_measurement(set_points: list[MeasModel]) -> np.ndarray: def covariance_set(set_points: list[StateQuat], mean: np.ndarray) -> np.ndarray: - """Function that calculates the covariance of a set of points""" + """Function that calculates the covariance of a set of points.""" n = len(set_points) covariance = np.zeros(set_points[0].covariance.shape) @@ -477,7 +651,7 @@ def covariance_set(set_points: list[StateQuat], mean: np.ndarray) -> np.ndarray: def covariance_measurement(set_points: list[MeasModel], mean: np.ndarray) -> np.ndarray: - """Function that calculates the covariance of a set of points""" + """Function that calculates the covariance of a set of points.""" n = len(set_points) co_size = len(set_points[0].measurement) covariance = np.zeros((co_size, co_size)) @@ -500,7 +674,7 @@ def cross_covariance( set_z: list[MeasModel], mean_z: np.ndarray, ) -> np.ndarray: - """Calculates the cross covariance between the measurement and state prediction""" + """Calculates the cross covariance between the measurement and state prediction.""" n = len(set_y) cross_covariance = np.zeros((len(mean_y) - 1, len(mean_z))) diff --git a/navigation/ukf_okid/ukf_python/ukf_ros.py b/navigation/ukf_okid/ukf_python/ukf_ros.py new file mode 100755 index 000000000..66d01175c --- /dev/null +++ b/navigation/ukf_okid/ukf_python/ukf_ros.py @@ -0,0 +1,117 @@ +#!/usr/bin/env python3 +import rclpy +from geometry_msgs.msg import TwistWithCovarianceStamped, WrenchStamped +from nav_msgs.msg import Odometry +from rclpy.node import Node +from rclpy.qos import HistoryPolicy, QoSProfile, ReliabilityPolicy +from std_msgs.msg import Bool, String +from ukf_okid import UKF +from ukf_okid_class import StateQuat, process_model, MeasModel +import numpy as np + +class UKFNode(Node): + def __init__(self): + super().__init__("UKFNode") + + best_effort_qos = QoSProfile( + reliability=ReliabilityPolicy.BEST_EFFORT, + history=HistoryPolicy.KEEP_LAST, + depth=1, + ) + + #subcribers + self.dvl_subscriber = self.create_subscription(TwistWithCovarianceStamped, + "/orca/twist", + self.dvl_callback, + qos_profile=best_effort_qos, + ) + + self.control_input = self.create_subscription(WrenchStamped,"/orca/wrench_input", self.control_callback, qos_profile=best_effort_qos,) + + self.odom_publish = self.create_publisher(Odometry, "/orca/odometry", qos_profile=best_effort_qos) + dt = self.declare_parameter("dt", 0.01).get_parameter_value().double_value + self.control_timer = self.create_timer(dt, self.odom_publisher) + + self.current_state = StateQuat() + x0 = np.zeros(13) + x0[3] = 1.0 # quaternion: [1, 0, 0, 0] + P0 = np.eye(12) * 0.5 + self.ukf_model = process_model() + self.ukf_model.dt = 0.01 + self.ukf_model.mass_interia_matrix = np.array([ + [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], + ]) + self.ukf_model.m = 30.0 + self.ukf_model.r_b_bg = np.array([0.01, 0.0, 0.02]) + self.ukf_model.inertia = np.diag([0.68, 3.32, 3.34]) + self.ukf_model.damping_linear = np.array([0.01] * 6) + # self.ukf_model.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) + + Q = np.diag([0.02, 0.02, 0.02, + 0.02, 0.02, 0.02, + 0.1, 0.1, 0.1, + 0.1, 0.1, 0.1]) + + self.ukf = UKF(self.ukf_model, x0, P0, Q) + self.ukf_flagg = False + + def dvl_callback(self, msg: TwistWithCovarianceStamped): + # unpack msg + dvl_measurement = MeasModel() + # Print received DVL data to console + # self.get_logger().info(f"DVL data received: x={msg.twist.twist.linear.x}, y={msg.twist.twist.linear.y}, z={msg.twist.twist.linear.z}") + dvl_measurement.measurement = np.array([msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z]) + dvl_measurement.covariance = np.array([[msg.twist.covariance[0], msg.twist.covariance[1], msg.twist.covariance[3]], + [msg.twist.covariance[6], msg.twist.covariance[7], msg.twist.covariance[8]], + [msg.twist.covariance[12], msg.twist.covariance[13], msg.twist.covariance[14]]]) + + self.ukf.measurement_update(self.current_state, dvl_measurement) + self.current_state = self.ukf.posteriori_estimate(self.current_state, dvl_measurement) + self.ukf_flagg = True + + def control_callback(self, msg:WrenchStamped): + # unpack message + control_array = np.array([msg.wrench.force.x, msg.wrench.force.y, msg.wrench.force.z, msg.wrench.torque.x, msg.wrench.torque.y, msg.wrench.torque.z]) + self.ukf_model.Control_input = control_array + + def odom_publisher(self): + msg = Odometry() + + if self.ukf_flagg == False: + self.current_state = self.ukf.unscented_transform(self.current_state) + else: + self.ukf_flagg = False + + msg.header.stamp = self.get_clock().now().to_msg() + msg.header.frame_id = "odom" + msg.child_frame_id = "base_link" + + msg.pose.pose.position.x = self.current_state.position[0] + msg.pose.pose.position.y = self.current_state.position[1] + msg.pose.pose.position.z = self.current_state.position[2] + msg.pose.pose.orientation.w = self.current_state.orientation[0] + msg.pose.pose.orientation.x = self.current_state.orientation[1] + msg.pose.pose.orientation.y = self.current_state.orientation[2] + msg.pose.pose.orientation.z = self.current_state.orientation[3] + msg.twist.twist.linear.x = self.current_state.velocity[0] + msg.twist.twist.linear.y = self.current_state.velocity[1] + msg.twist.twist.linear.z = self.current_state.velocity[2] + msg.twist.twist.angular.x = self.current_state.angular_velocity[0] + msg.twist.twist.angular.y = self.current_state.angular_velocity[1] + msg.twist.twist.angular.z = self.current_state.angular_velocity[2] + + self.odom_publish.publish(msg) + +def main(args=None): + rclpy.init(args=args) + ukf_node = UKFNode() + rclpy.spin(ukf_node) + rclpy.shutdown() + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/navigation/ukf_okid/ukf_python/ukf_test.py b/navigation/ukf_okid/ukf_python/ukf_test.py index cebb53ac6..80ca90e86 100644 --- a/navigation/ukf_okid/ukf_python/ukf_test.py +++ b/navigation/ukf_okid/ukf_python/ukf_test.py @@ -1,323 +1,440 @@ -import time - -import matplotlib.pyplot as plt import numpy as np -from ukf_okid import UKF +import matplotlib.pyplot as plt +from ukf_utils import print_StateQuat +# Import your classes and functions. +# Adjust the import paths as necessary based on your module organization. from ukf_okid_class import ( - MeasModel, StateQuat, - process_model, - quat_to_euler, + MeasModel, + iterative_quaternion_mean_statequat, + mean_set, + mean_measurement, + covariance_set, + covariance_measurement, + cross_covariance, quaternion_super_product, + quaternion_error, + quat_to_euler, + quat_norm, ) - -def add_quaternion_noise(q, noise_std): - noise = np.random.normal(0, noise_std, 3) - - theta = np.linalg.norm(noise) - - if theta > 0: - axis = noise / theta - - q_noise = np.hstack((np.cos(theta / 2), np.sin(theta / 2) * axis)) - +# For testing, define a function to create a StateQuat with small perturbations. +def create_statequat(base_vector, position_perturbation, orientation_perturbation, velocity_perturbation, angular_velocity_perturbation): + """ + Creates a StateQuat object. + - base_vector: 1D numpy array for base state (13 elements: + position (3), quaternion (4), velocity (3), angular_velocity (3)) + - ..._perturbation: small perturbation vector to be added to each respective component. + Returns a StateQuat. + """ + state = StateQuat() + # Base state + state.position = base_vector[0:3] + position_perturbation + # For orientation, perturb by adding a small rotation: + base_quat = base_vector[3:7] + noise_angle = np.linalg.norm(orientation_perturbation) + if noise_angle < 1e-8: + noise_quat = np.array([1.0, 0.0, 0.0, 0.0]) else: - q_noise = np.array([1.0, 0.0, 0.0, 0.0]) - - q_new = quaternion_super_product(q, q_noise) - - return q_new / np.linalg.norm(q_new) - - -if __name__ == '__main__': - # Create initial state vector and covariance matrix. - x0 = np.zeros(13) - x0[0:3] = [0.3, 0.3, 0.3] - x0[3] = 1 - x0[7:10] = [0.2, 0.2, 0.2] - dt = 0.01 - R = (0.01) * np.eye(3) - - Q = 0.00015 * np.eye(12) - P0 = np.eye(12) * 0.0001 + noise_axis = orientation_perturbation / noise_angle + noise_quat = np.concatenate(([np.cos(noise_angle/2)], np.sin(noise_angle/2) * noise_axis)) + state.orientation = quat_norm(quaternion_super_product(base_quat, noise_quat)) + state.velocity = base_vector[7:10] + velocity_perturbation + state.angular_velocity = base_vector[10:13] + angular_velocity_perturbation + + # For the augmented parameters (OKID parameters), set a 21-element vector: + # 9 for inertia, 6 for added_mass, and 6 for damping_linear. + state.okid_params.fill(np.concatenate((np.zeros(9), np.zeros(6), np.zeros(6)))) + + # Set a default covariance (33x33 for the extended state) + state.covariance = np.eye(33) * 0.01 + return state + +# Test functions for state statistics +def test_state_statistics(): + # Define a base state vector (13 elements: position, quaternion, velocity, angular_velocity) + base_vector = np.zeros(13) + base_vector[0:3] = np.array([1.0, 2.0, 3.0]) + base_vector[3:7] = np.array([1.0, 0.0, 0.0, 0.0]) # identity quaternion + base_vector[7:10] = np.array([0.1, 0.2, 0.3]) + base_vector[10:13] = np.array([0.01, 0.02, 0.03]) + + # Create a list of StateQuat objects with small random perturbations. + np.random.seed(42) + state_list = [] + num_states = 10 + for _ in range(num_states): + pos_noise = np.random.normal(0, 0.05, 3) + ori_noise = np.random.normal(0, 0.01, 3) + vel_noise = np.random.normal(0, 0.02, 3) + ang_vel_noise = np.random.normal(0, 0.005, 3) + state_list.append(create_statequat(base_vector, pos_noise, ori_noise, vel_noise, ang_vel_noise)) + + # Compute the state mean using mean_set. + mean_state_vec = mean_set(state_list) + print("Computed mean state vector:") + print(mean_state_vec) + + # Compute the covariance of the states. + cov_state = covariance_set(state_list, mean_state_vec) + print("Computed state covariance matrix:") + print(cov_state) + + # Check symmetry of the covariance: + asym_error = np.linalg.norm(cov_state - cov_state.T) + print("Covariance symmetry error (should be near 0):", asym_error) + + # Check eigenvalues for positive semidefiniteness: + eigvals = np.linalg.eigvals(cov_state) + print("Eigenvalues of state covariance:") + print(eigvals) + +def test_measurement_statistics(): + # Create a list of measurement objects (MeasModel) with measurements in R^3. + np.random.seed(24) + meas_list = [] + num_meas = 10 + base_meas = np.array([1.0, 2.0, 3.0]) + for _ in range(num_meas): + noise = np.random.normal(0, 0.1, 3) + meas = MeasModel() + meas.measurement = base_meas + noise + meas_list.append(meas) + + # Compute the measurement mean. + mean_meas = mean_measurement(meas_list) + print("Computed measurement mean:") + print(mean_meas) + + # Compute the measurement covariance. + cov_meas = covariance_measurement(meas_list, mean_meas) + print("Computed measurement covariance:") + print(cov_meas) + + # Check symmetry and eigenvalues. + asym_error = np.linalg.norm(cov_meas - cov_meas.T) + print("Measurement covariance symmetry error:", asym_error) + eigvals = np.linalg.eigvals(cov_meas) + print("Eigenvalues of measurement covariance:") + print(eigvals) + +def test_cross_covariance(): + # Create a set of StateQuat and corresponding MeasModel objects. + np.random.seed(99) + num = 10 + state_list = [] + meas_list = [] + base_vector = np.zeros(13) + base_vector[0:3] = np.array([0.5, 1.0, -0.5]) + base_vector[3:7] = np.array([1.0, 0.0, 0.0, 0.0]) + base_vector[7:10] = np.array([0.05, 0.1, 0.15]) + base_vector[10:13] = np.array([0.005, 0.01, 0.015]) + + for _ in range(num): + pos_noise = np.random.normal(0, 0.02, 3) + ori_noise = np.random.normal(0, 0.005, 3) + vel_noise = np.random.normal(0, 0.01, 3) + ang_vel_noise = np.random.normal(0, 0.002, 3) + state = create_statequat(base_vector, pos_noise, ori_noise, vel_noise, ang_vel_noise) + state_list.append(state) + + # Generate a measurement from each state (e.g., state velocity plus noise). + meas = MeasModel() + meas.measurement = state.velocity + np.random.normal(0, 0.01, 3) + meas_list.append(meas) + + # Compute the state mean and measurement mean as vectors. + mean_state_vec = mean_set(state_list) + mean_meas = mean_measurement(meas_list) + + cross_cov = cross_covariance(state_list, mean_state_vec, meas_list, mean_meas) + print("Computed cross-covariance between state and measurement:") + print(cross_cov) - model = process_model() - model.dt = 0.01 - model.mass_interia_matrix = np.array( - [ - [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], - ] - ) - model.m = 30.0 - model.r_b_bg = np.array([0.01, 0.0, 0.02]) - model.inertia = np.diag([0.68, 3.32, 3.34]) - model.damping_linear = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) - model.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) - model.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) - - model_ukf = process_model() - model_ukf.dt = 0.01 - model_ukf.mass_interia_matrix = np.array( - [ - [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], - ] - ) - model_ukf.m = 30.0 - model_ukf.r_b_bg = np.array([0.01, 0.0, 0.02]) - model_ukf.inertia = np.diag([0.68, 3.32, 3.34]) - model_ukf.damping_linear = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) - model_ukf.damping_nonlinear = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3]) - model_ukf.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) +import time +import numpy as np +import matplotlib.pyplot as plt - # Simulation parameters - simulation_time = 5 # seconds +# Import your classes and functions. +from ukf_okid_class import ( + StateQuat, + MeasModel, + iterative_quaternion_mean_statequat, + mean_set, + mean_measurement, + covariance_set, + covariance_measurement, + cross_covariance, + quaternion_super_product, + quaternion_error, + quat_norm, +) +from ukf_okid import UKF +from ukf_okid_class import process_model, okid_process_model # Your process model classes + +############################################ +# Helper function to create a StateQuat with perturbations. +############################################ +def create_statequat(base_vector, pos_noise, ori_noise, vel_noise, ang_vel_noise): + """ + Create a StateQuat object from a base vector (13 elements: + position (3), quaternion (4), velocity (3), angular_velocity (3)) + plus additive noise on each component. + + For the OKID parameters, we assume a 21-element vector: + - first 9: inertia, + - next 6: added_mass, + - last 6: damping_linear. + """ + state = StateQuat() + state.position = base_vector[0:3] + pos_noise + base_quat = base_vector[3:7] + noise_angle = np.linalg.norm(ori_noise) + if noise_angle < 1e-8: + noise_quat = np.array([1.0, 0.0, 0.0, 0.0]) + else: + noise_axis = ori_noise / noise_angle + noise_quat = np.concatenate(([np.cos(noise_angle/2)], + np.sin(noise_angle/2) * noise_axis)) + state.orientation = quat_norm(quaternion_super_product(base_quat, noise_quat)) + state.velocity = base_vector[7:10] + vel_noise + state.angular_velocity = base_vector[10:13] + ang_vel_noise + + # Set OKID parameters to exactly 21 elements (9,6,6) + state.okid_params.fill(np.concatenate((np.array([0.0, 0.0, 0.3, 0.0, 0.0, 3.3, 0.0, 0.0, 3.3]), np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0]), np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0])))) + # Set an initial covariance (33x33) for the full augmented state. + state.covariance = np.eye(33) * 0.02 + return state + +############################################ +# Full Filter Simulation Test +############################################ +def run_ukf_simulation(): + dt = 0.01 # Time step for simulation [s] + simulation_time = 10 # Total simulation time in seconds num_steps = int(simulation_time / dt) - - # Initialize a dummy StateQuat. - new_state = StateQuat() - new_state.fill_states(x0) - new_state.covariance = P0 - - test_state_x = StateQuat() - test_state_x.fill_states(x0) - test_state_x.covariance = P0 - - # Initialize a estimated state - estimated_state = StateQuat() - estimated_state.fill_states(x0) - estimated_state.covariance = P0 - - # Initialize a estimated state - noisy_state = StateQuat() - noisy_state.fill_states(x0) - noisy_state.covariance = P0 - - measurment_model = MeasModel() - measurment_model.measurement = np.array([0.0, 0.0, 0.0]) - measurment_model.covariance = R - - # Initialize arrays to store the results - positions = np.zeros((num_steps, 3)) - orientations = np.zeros((num_steps, 3)) - velocities = np.zeros((num_steps, 3)) - angular_velocities = np.zeros((num_steps, 3)) - - # Initialize arrays to store the estimates - positions_est = np.zeros((num_steps, 3)) - orientations_est = np.zeros((num_steps, 3)) - velocities_est = np.zeros((num_steps, 3)) - angular_velocities_est = np.zeros((num_steps, 3)) - - # Initialize the okid params - okid_params = np.zeros((num_steps, 21)) - - model.state_vector_prev = new_state - model.state_vector = new_state - - model_ukf.state_vector_prev = test_state_x - model_ukf.state_vector = test_state_x - - # initialize the ukf - ukf = UKF(model_ukf, x0, P0, Q, R) - - elapsed_times = [] - - u = lambda t: np.array( - [ - 2 * np.sin(1 * t), - 2 * np.sin(1 * t), - 2 * np.sin(1 * t), - 0.2 * np.cos(1 * t), - 0.2 * np.cos(1 * t), - 0.2 * np.cos(1 * t), - ] - ) - - # Run the simulation - for step in range(num_steps): - # Insert control input - model.Control_input = u(step * dt) - model_ukf.Control_input = u(step * dt) - - # Perform the unscented transform - model.model_prediction(new_state) - new_state = model.euler_forward() - - # Adding noise in the state vector - estimated_state.position = ( - estimated_state.position - ) # + np.random.normal(0, 0.01, 3) - estimated_state.orientation = ( - estimated_state.orientation - ) # add_quaternion_noise(estimated_state.orientation, 0.01) - estimated_state.velocity = ( - estimated_state.velocity - ) # + np.random.normal(0, 0.01, 3) - estimated_state.angular_velocity = ( - estimated_state.angular_velocity - ) # + np.random.normal(0, 0.01, 3) - - start_time = time.time() - estimated_state = ukf.unscented_transform(estimated_state) - print(estimated_state.as_vector()) - break - elapsed_time = time.time() - start_time - elapsed_times.append(elapsed_time) - - if step % 20 == 0: - measurment_model.measurement = ( - new_state.velocity - ) # + np.random.normal(0, 0.01, 3) - meas_update, covariance_matrix = ukf.measurement_update( - estimated_state, measurment_model - ) - estimated_state = ukf.posteriori_estimate( - estimated_state, covariance_matrix, measurment_model, meas_update - ) - - positions[step, :] = new_state.position - orientations[step, :] = quat_to_euler(new_state.orientation) - velocities[step, :] = new_state.velocity - angular_velocities[step, :] = new_state.angular_velocity - - positions_est[step, :] = estimated_state.position - orientations_est[step, :] = quat_to_euler(estimated_state.orientation) - velocities_est[step, :] = estimated_state.velocity - angular_velocities_est[step, :] = estimated_state.angular_velocity - - # Update the state for the next iteration - model.state_vector_prev = new_state - - print('Average elapsed time: ', np.mean(elapsed_times)) - print('Max elapsed time: ', np.max(elapsed_times)) - print('Min elapsed time: ', np.min(elapsed_times)) - print('median elapsed time: ', np.median(elapsed_times)) - # Plot the results - time = np.linspace(0, simulation_time, num_steps) - - # Plot positions - plt.figure() - plt.subplot(3, 1, 1) - plt.plot(time, positions[:, 0], label='True') - plt.plot(time, positions_est[:, 0], label='Estimated') - plt.title('Position X') - plt.xlabel('Time [s]') - plt.ylabel('Position X [m]') + + # Define a base state vector (13 elements: pos, quat, vel, ang_vel) + base_vector = np.zeros(13) + base_vector[0:3] = np.array([0.0, 0.0, 0.0]) + base_vector[3:7] = np.array([1.0, 0.0, 0.0, 0.0]) # identity quaternion + base_vector[7:10] = np.array([0.1, 0.0, 0.0]) # small velocity in x + base_vector[10:13] = np.array([0.0, 0.0, 0.0]) + + # Define initial covariance for state (33x33) + P0 = np.eye(33) + P0[0:3, 0:3] = np.eye(3) * 0.01 # position + P0[3:6, 3:6] = np.eye(3) * 0.01 # orientation error (quaternion) + P0[6:9, 6:9] = np.eye(3) * 0.01 # velocity + P0[9:12, 9:12] = np.eye(3) * 0.01 # angular velocity + P0[12:33, 12:33] = np.eye(21) * 0.001 # OKID parameters + + # Define process noise covariance Q (33x33) + Q = np.zeros((33, 33)) + Q[0:3, 0:3] = np.eye(3)*0.001 # for position + Q[3:6, 3:6] = np.eye(3)*0.001 # for orientation error (represented with Euler angles) + Q[6:9, 6:9] = np.eye(3)*0.001 # for velocity + Q[9:12, 9:12] = np.eye(3)*0.001 # for angular velocity + Q[12:33, 12:33] = np.eye(21) * 0.001 # OKID parameters + + + G = np.zeros((33, 12)) + G[0:3, 0:3] = np.eye(3) + G[3:6, 3:6] = np.eye(3) + G[6:9, 6:9] = np.eye(3) + G[9:12, 9:12] = np.eye(3) + + # Measurement noise covariance R (3x3), assume measurement is velocity + R = np.eye(3) * 0.01 + + # Create a simulation process model and an independent UKF process model. + sim_model = process_model() + sim_model.dt = dt + sim_model.mass_interia_matrix = np.array([ + [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], + ]) + sim_model.m = 30.0 + sim_model.r_b_bg = np.array([0.01, 0.0, 0.02]) + sim_model.inertia = np.diag([0.68, 3.32, 3.34]) + sim_model.damping_linear = np.array([0.1]*6) + sim_model.added_mass = np.array([1.0,1.0,1.0,2.0,2.0,2.0]) + + # UKF process model copy: + ukf_model = okid_process_model() + ukf_model.dt = dt + ukf_model.mass_interia_matrix = sim_model.mass_interia_matrix.copy() + ukf_model.m = sim_model.m + ukf_model.r_b_bg = sim_model.r_b_bg.copy() + ukf_model.inertia = sim_model.inertia.copy() + ukf_model.damping_linear = sim_model.damping_linear.copy() + ukf_model.added_mass = sim_model.added_mass.copy() + + # Initialize true state and filter state. + true_state = create_statequat(base_vector, + np.zeros(3), + np.zeros(3), + np.zeros(3), + np.zeros(3)) + true_state.covariance = P0.copy() + + filter_state = create_statequat(base_vector, + np.zeros(3), + np.zeros(3), + np.zeros(3), + np.zeros(3)) + filter_state.covariance = P0.copy() + + # Initialize measurement model (for example, measuring velocity only) + meas_model = MeasModel() + meas_model.covariance = R.copy() + + # Initialize UKF. + ukf = UKF(ukf_model, true_state, P0.copy(), Q.copy(), G.copy()) + + # Arrays to store time histories. + pos_true_hist = np.zeros((num_steps, 3)) + pos_est_hist = np.zeros((num_steps, 3)) + vel_true_hist = np.zeros((num_steps, 3)) + vel_est_hist = np.zeros((num_steps, 3)) + euler_true_hist = np.zeros((num_steps, 3)) + euler_est_hist = np.zeros((num_steps, 3)) + time_array = np.linspace(0, simulation_time, num_steps) + + # Control input function (example: oscillatory in all directions) + def control_input(t): + return np.array([ + 2*np.sin(t), + 2*np.sin(t+0.5), + 2*np.sin(t+1.0), + 0.2*np.cos(t), + 0.2*np.cos(t+0.5), + 0.2*np.cos(t+1.0) + ]) + + # Set previous states. + sim_model.state_vector_prev = true_state + sim_model.state_vector = true_state + ukf_model.state_vector_prev = filter_state + ukf_model.state_vector = filter_state + + # Lists for timing diagnostics. + ukf_transform_times = [] + ukf_update_times = [] + + # Simulation loop. + for i in range(num_steps): + t_current = i*dt + + # Update control inputs. + sim_model.Control_input = control_input(t_current) + ukf_model.Control_input = control_input(t_current) + + # Propagate true state using the simulation model. + sim_model.model_prediction(true_state) + true_state = sim_model.euler_forward() + + # Create a measurement from true state. + # Here we assume we measure velocity plus noise. + meas_noise = np.random.normal(0, 0.01, 3) + meas_model.measurement = true_state.velocity + meas_noise + + # UKF prediction: unscented transform. + start = time.time() + filter_state = ukf.unscented_transform(filter_state) + ukf_transform_times.append(time.time() - start) + + # UKF measurement update every few steps. + if i % 5 == 0: + try: + start = time.time() + ukf.measurement_update(filter_state, meas_model) + filter_state = ukf.posteriori_estimate(filter_state, meas_model) + ukf_update_times.append(time.time() - start) + except np.linalg.LinAlgError: + # If matrix is not PD, add jitter. + filter_state.covariance += np.eye(filter_state.covariance.shape[0])*1e-6 + + # Store true and estimated state for diagnostics. + pos_true_hist[i, :] = true_state.position + pos_est_hist[i, :] = filter_state.position + vel_true_hist[i, :] = true_state.velocity + vel_est_hist[i, :] = filter_state.velocity + # Convert quaternion to Euler angles for visualization. + # Assumes you have a function quat_to_euler. + euler_true_hist[i, :] = quat_to_euler(true_state.orientation) + euler_est_hist[i, :] = quat_to_euler(filter_state.orientation) + + # Update previous states. + sim_model.state_vector_prev = true_state + ukf_model.state_vector_prev = filter_state + + # Print timing diagnostics. + print("Average unscented transform time:", np.mean(ukf_transform_times)) + print("Average measurement update time:", np.mean(ukf_update_times)) + + # Compute error metrics. + pos_error = np.linalg.norm(pos_true_hist - pos_est_hist, axis=1) + vel_error = np.linalg.norm(vel_true_hist - vel_est_hist, axis=1) + euler_error = np.linalg.norm(euler_true_hist - euler_est_hist, axis=1) + print("Average position error:", np.mean(pos_error)) + print("Average velocity error:", np.mean(vel_error)) + print("Average orientation (Euler) error:", np.mean(euler_error)) + + # Plot estimated vs true trajectory (positions). + plt.figure(figsize=(10,8)) + plt.subplot(3,1,1) + plt.plot(time_array, pos_true_hist[:,0], label="True X") + plt.plot(time_array, pos_est_hist[:,0], label="Est X", linestyle="--") plt.legend() - - plt.subplot(3, 1, 2) - plt.plot(time, positions[:, 1], label='True') - plt.plot(time, positions_est[:, 1], label='Estimated') - plt.title('Position Y') - plt.xlabel('Time [s]') - plt.ylabel('Position Y [m]') + plt.title("Position X") + + plt.subplot(3,1,2) + plt.plot(time_array, pos_true_hist[:,1], label="True Y") + plt.plot(time_array, pos_est_hist[:,1], label="Est Y", linestyle="--") plt.legend() - - plt.subplot(3, 1, 3) - plt.plot(time, positions[:, 2], label='True') - plt.plot(time, positions_est[:, 2], label='Estimated') - plt.title('Position Z') - plt.xlabel('Time [s]') - plt.ylabel('Position Z [m]') + plt.title("Position Y") + + plt.subplot(3,1,3) + plt.plot(time_array, pos_true_hist[:,2], label="True Z") + plt.plot(time_array, pos_est_hist[:,2], label="Est Z", linestyle="--") plt.legend() - + plt.title("Position Z") plt.tight_layout() plt.show() - - # Plot orientations (Euler angles) - plt.figure() - plt.subplot(3, 1, 1) - plt.plot(time, orientations[:, 0], label='True') - plt.plot(time, orientations_est[:, 0], label='Estimated') - plt.title('Orientation Roll') - plt.xlabel('Time [s]') - plt.ylabel('Roll [rad]') - plt.legend() - - plt.subplot(3, 1, 2) - plt.plot(time, orientations[:, 1], label='True') - plt.plot(time, orientations_est[:, 1], label='Estimated') - plt.title('Orientation Pitch') - plt.xlabel('Time [s]') - plt.ylabel('Pitch [rad]') + + # Plot errors. + plt.figure(figsize=(10,4)) + plt.plot(time_array, pos_error, label="Position Error") + plt.plot(time_array, vel_error, label="Velocity Error") + plt.plot(time_array, euler_error, label="Euler Angle Error") plt.legend() - - plt.subplot(3, 1, 3) - plt.plot(time, orientations[:, 2], label='True') - plt.plot(time, orientations_est[:, 2], label='Estimated') - plt.title('Orientation Yaw') - plt.xlabel('Time [s]') - plt.ylabel('Yaw [rad]') - plt.legend() - - plt.tight_layout() + plt.title("Error Metrics over Time") + plt.xlabel("Time (s)") + plt.ylabel("Error magnitude") plt.show() - # Plot velocities - plt.figure() - plt.subplot(3, 1, 1) - plt.plot(time, velocities[:, 0], label='True') - plt.plot(time, velocities_est[:, 0], label='Estimated') - plt.title('Velocity X') - plt.xlabel('Time [s]') - plt.ylabel('Velocity X [m/s]') - plt.legend() - - plt.subplot(3, 1, 2) - plt.plot(time, velocities[:, 1], label='True') - plt.plot(time, velocities_est[:, 1], label='Estimated') - plt.title('Velocity Y') - plt.xlabel('Time [s]') - plt.ylabel('Velocity Y [m/s]') - plt.legend() +# You can also test the individual statistics functions separately: +def run_diagnostics(): + print("Testing state mean and covariance computation:") + # Call your pre-written tests: + # (Assuming these functions—test_state_statistics, test_measurement_statistics, test_cross_covariance—are defined above) + test_state_statistics() + print("\nTesting measurement mean and covariance computation:") + test_measurement_statistics() + print("\nTesting cross-covariance computation:") + test_cross_covariance() - plt.subplot(3, 1, 3) - plt.plot(time, velocities[:, 2], label='True') - plt.plot(time, velocities_est[:, 2], label='Estimated') - plt.title('Velocity Z') - plt.xlabel('Time [s]') - plt.ylabel('Velocity Z [m/s]') - plt.legend() - - plt.tight_layout() - plt.show() - - # Plot angular velocities - plt.figure() - plt.subplot(3, 1, 1) - plt.plot(time, angular_velocities[:, 0], label='True') - plt.plot(time, angular_velocities_est[:, 0], label='Estimated') - plt.title('Angular Velocity X') - plt.xlabel('Time [s]') - plt.ylabel('Angular Velocity X [rad/s]') - plt.legend() - - plt.subplot(3, 1, 2) - plt.plot(time, angular_velocities[:, 1], label='True') - plt.plot(time, angular_velocities_est[:, 1], label='Estimated') - plt.title('Angular Velocity Y') - plt.xlabel('Time [s]') - plt.ylabel('Angular Velocity Y [rad/s]') - plt.legend() +if __name__ == '__main__': + # First, run the diagnostics on the mean/covariance functions. + run_diagnostics() + + # Then run the full UKF simulation test. + print("\nRunning full UKF simulation test:") + run_ukf_simulation() - plt.subplot(3, 1, 3) - plt.plot(time, angular_velocities[:, 2], label='True') - plt.plot(time, angular_velocities_est[:, 2], label='Estimated') - plt.title('Angular Velocity Z') - plt.xlabel('Time [s]') - plt.ylabel('Angular Velocity Z [rad/s]') - plt.legend() - plt.tight_layout() - plt.show() diff --git a/navigation/ukf_okid/ukf_python/ukf_test_2.py b/navigation/ukf_okid/ukf_python/ukf_test_2.py new file mode 100644 index 000000000..bf58b7a1a --- /dev/null +++ b/navigation/ukf_okid/ukf_python/ukf_test_2.py @@ -0,0 +1,40 @@ +import numpy as np + +# Define process noise covariance Q (33x33) +Q = np.zeros((12, 12)) +Q[0:3, 0:3] = np.eye(3)*0.003 # for position +Q[3:6, 3:6] = np.eye(3)*0.003 # for orientation error (represented with Euler angles) +Q[6:9, 6:9] = np.eye(3)*0.002 # for velocity +Q[9:12, 9:12] = np.eye(3)*0.003 # for angular velocity + +G = np.zeros((33, 12)) +G[0:3, 0:3] = np.eye(3) +G[3:6, 3:6] = np.eye(3) +G[6:9, 6:9] = np.eye(3) +G[9:12, 9:12] = np.eye(3) + +GG = G @ Q @ G.T +def fancy_print_matrix(matrix, name="Matrix", precision=4): + """ + Print a matrix with fancy formatting. + + Args: + matrix: numpy array to print + name: name of the matrix to display + precision: number of decimal places to show + """ + print(f"\n{'=' * 50}") + print(f" {name} [{matrix.shape[0]}x{matrix.shape[1]}]") + print(f"{'=' * 50}") + + # Set numpy print options + with np.printoptions(precision=precision, suppress=True, linewidth=100): + # Print each row with custom formatting + for i in range(matrix.shape[0]): + row = ' '.join([f"{x:8.{precision}f}" for x in matrix[i]]) + print(f" {i:2d} | {row}") + + print(f"{'=' * 50}\n") + +# Example usage: +fancy_print_matrix(GG, name="Process Noise Covariance (GQG')", precision=3) \ No newline at end of file diff --git a/navigation/ukf_okid/ukf_python/ukf_utils.py b/navigation/ukf_okid/ukf_python/ukf_utils.py index cb92d9393..7bf7cd4e3 100644 --- a/navigation/ukf_okid/ukf_python/ukf_utils.py +++ b/navigation/ukf_okid/ukf_python/ukf_utils.py @@ -19,6 +19,7 @@ def print_StateQuat(state: StateQuat, name="StateQuat", print_covariance=True): print(f" Orientation: {state.orientation}") print(f" Velocity: {state.velocity}") print(f" Angular Velocity: {state.angular_velocity}") + print(f" okid state: {state.okid_params}") # print(f" okid_params: {state.okid_params}") if print_covariance: print_matrix(state.covariance, "Covariance") From 20280c2d22337cd780bfc840253e0c4b8f1a9b1a Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 17 Apr 2025 16:27:59 +0000 Subject: [PATCH 16/30] [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci --- navigation/eskf/include/eskf/eskf.hpp | 1 - navigation/eskf/include/eskf/typedefs.hpp | 7 +- navigation/eskf/src/eskf.cpp | 11 +- navigation/eskf/src/eskf_ros.cpp | 18 +- navigation/ukf_okid/launch/ukf.launch.py | 3 - navigation/ukf_okid/ukf_python/ukf_okid.py | 29 +- .../ukf_okid/ukf_python/ukf_okid_class.py | 43 ++- navigation/ukf_okid/ukf_python/ukf_ros.py | 102 +++++-- navigation/ukf_okid/ukf_python/ukf_test.py | 268 ++++++++++-------- navigation/ukf_okid/ukf_python/ukf_test_2.py | 22 +- 10 files changed, 293 insertions(+), 211 deletions(-) diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp index 80b086d26..5cc3e0708 100644 --- a/navigation/eskf/include/eskf/eskf.hpp +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -25,7 +25,6 @@ class ESKF { const dvl_measurement& dvl_meas); private: - // @brief Predict the nominal state // @param imu_meas: IMU measurement // @param dt: Time step diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index fac89baa7..748804be3 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -5,9 +5,9 @@ #ifndef ESKF_TYPEDEFS_H #define ESKF_TYPEDEFS_H +#include #include #include -#include namespace Eigen { typedef Eigen::Matrix Vector19d; @@ -43,9 +43,7 @@ struct state_quat { Eigen::Vector3d accel_bias = Eigen::Vector3d::Zero(); Eigen::Vector3d gravity = Eigen::Vector3d::Zero(); - state_quat() { - gravity << 0, 0, 9.81; - } + state_quat() { gravity << 0, 0, 9.81; } Eigen::Vector19d as_vector() const { Eigen::Vector19d vec; @@ -94,7 +92,6 @@ struct state_euler { struct imu_measurement { Eigen::Vector3d accel = Eigen::Vector3d::Zero(); Eigen::Vector3d gyro = Eigen::Vector3d::Zero(); - }; struct dvl_measurement { diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index bbd367c7f..84fb5e8f3 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -107,21 +107,20 @@ Eigen::Matrix3x1d ESKF::calculate_h() { return h; } - void ESKF::nominal_state_discrete(const imu_measurement& imu_meas, const double dt) { Eigen::Vector3d acc = - current_nom_state_.quat.normalized().toRotationMatrix() * imu_meas.accel + + current_nom_state_.quat.normalized().toRotationMatrix() * + imu_meas.accel + current_nom_state_.gravity; - Eigen::Vector3d gyro = imu_meas.gyro * dt/2; + Eigen::Vector3d gyro = imu_meas.gyro * dt / 2; current_nom_state_.pos = current_nom_state_.pos + current_nom_state_.vel * dt + 0.5 * sq(dt) * acc; current_nom_state_.vel = current_nom_state_.vel + dt * acc; - - current_nom_state_.quat = (current_nom_state_.quat * vector3d_to_quaternion(gyro)); - + current_nom_state_.quat = + (current_nom_state_.quat * vector3d_to_quaternion(gyro)); current_nom_state_.quat.normalize(); diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index a35273103..e805a0c39 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -42,8 +42,9 @@ void ESKFNode::set_subscribers_and_publisher() { void ESKFNode::set_parameters() { std::vector R_imu_correction; this->declare_parameter>("imu_frame"); - R_imu_correction = get_parameter("imu_rotation_matrix").as_double_array(); - R_imu_eskf_ = Eigen::Map>(R_imu_correction.data()); + R_imu_correction = get_parameter("imu_rotation_matrix").as_double_array(); + R_imu_eskf_ = Eigen::Map>( + R_imu_correction.data()); std::vector diag_Q_std; this->declare_parameter>("diag_Q_std"); @@ -81,15 +82,14 @@ void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { last_imu_time_ = current_time; Eigen::Vector3d raw_accel(msg->linear_acceleration.x, - msg->linear_acceleration.y, - msg->linear_acceleration.z); + msg->linear_acceleration.y, + msg->linear_acceleration.z); imu_meas_.accel = R_imu_eskf_ * raw_accel; - - Eigen::Vector3d raw_gyro(msg->angular_velocity.x, - msg->angular_velocity.y, - msg->angular_velocity.z); - + + Eigen::Vector3d raw_gyro(msg->angular_velocity.x, msg->angular_velocity.y, + msg->angular_velocity.z); + imu_meas_.gyro = R_imu_eskf_ * raw_gyro; std::tie(nom_state_, error_state_) = eskf_->imu_update(imu_meas_, dt); diff --git a/navigation/ukf_okid/launch/ukf.launch.py b/navigation/ukf_okid/launch/ukf.launch.py index 62a439b94..baf6fb645 100644 --- a/navigation/ukf_okid/launch/ukf.launch.py +++ b/navigation/ukf_okid/launch/ukf.launch.py @@ -1,12 +1,9 @@ -import os -from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch_ros.actions import Node def generate_launch_description() -> LaunchDescription: - ukf_node = Node( package="ukf_python", executable="ukf_ros.py", diff --git a/navigation/ukf_okid/ukf_python/ukf_okid.py b/navigation/ukf_okid/ukf_python/ukf_okid.py index af61d1a79..474b94ac6 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid.py @@ -1,5 +1,4 @@ import numpy as np -from ukf_utils import print_StateQuat from ukf_okid_class import ( MeasModel, StateQuat, @@ -8,7 +7,6 @@ cross_covariance, mean_measurement, mean_set, - process_model, okid_process_model, ) @@ -37,15 +35,17 @@ def generate_delta_matrix(self, n: float) -> np.ndarray: delta (np.ndarray): An n x 2n orthonormal transformation matrix used to generate TUKF sigma points. """ delta = np.zeros((n, 2 * n)) - k = 0.01 #Tuning parameter to ensure pos def + k = 0.01 # Tuning parameter to ensure pos def - for i in range(2 * n): + for i in range(2 * n): for j in range(n // 2): - delta[2 * j + 1, i] = np.sqrt(2) * np.sin((2 * j - 1)) * ((k * np.pi) / n) - delta[2 * j, i] = np.sqrt(2) * np.cos((2 * j - 1)) * ((k * np.pi) / n) - + delta[2 * j + 1, i] = ( + np.sqrt(2) * np.sin(2 * j - 1) * ((k * np.pi) / n) + ) + delta[2 * j, i] = np.sqrt(2) * np.cos(2 * j - 1) * ((k * np.pi) / n) + if (n % 2) == 1: - delta[n-1, i] = (-1)**i + delta[n - 1, i] = (-1) ** i return delta def sigma_points(self, current_state: StateQuat) -> list[StateQuat]: @@ -96,10 +96,15 @@ def measurement_update( self.measurement_updated.measurement = mean_measurement(z_i) - self.measurement_updated.covariance = covariance_measurement(z_i, self.measurement_updated.measurement) + self.measurement_updated.covariance = covariance_measurement( + z_i, self.measurement_updated.measurement + ) self.cross_correlation = cross_covariance( - self.y_i, current_state.as_vector(), z_i, self.measurement_updated.measurement + self.y_i, + current_state.as_vector(), + z_i, + self.measurement_updated.measurement, ) def posteriori_estimate( @@ -109,7 +114,9 @@ def posteriori_estimate( ) -> StateQuat: """Calculates the posteriori estimate using measurement and the prior estimate.""" nu_k = MeasModel() - nu_k.measurement = measurement.measurement - self.measurement_updated.measurement + nu_k.measurement = ( + measurement.measurement - self.measurement_updated.measurement + ) nu_k.covariance = self.measurement_updated.covariance + measurement.covariance K_k = np.dot(self.cross_correlation, np.linalg.inv(nu_k.covariance)) diff --git a/navigation/ukf_okid/ukf_python/ukf_okid_class.py b/navigation/ukf_okid/ukf_python/ukf_okid_class.py index 5558ad754..0b329cb84 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid_class.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid_class.py @@ -2,13 +2,22 @@ import numpy as np + @dataclass class okid: """A class to represent the parameters for the OKID algorithm.""" - inertia: np.ndarray = field(default_factory=lambda: np.array([0.68, 0.0, 0.0, 0.0, 3.32, 0.0, 0.0, 0.0, 3.34])) - added_mass: np.ndarray = field(default_factory=lambda: np.array([1.0,1.0,1.0,2.0,2.0,2.0])) - damping_linear: np.ndarray = field(default_factory=lambda: np.array([1.0,1.0,1.0,1.0,1.0,1.0])) + inertia: np.ndarray = field( + default_factory=lambda: np.array( + [0.68, 0.0, 0.0, 0.0, 3.32, 0.0, 0.0, 0.0, 3.34] + ) + ) + added_mass: np.ndarray = field( + default_factory=lambda: np.array([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) + ) + damping_linear: np.ndarray = field( + default_factory=lambda: np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0]) + ) def fill(self, state: np.ndarray) -> None: """Fills the okid_params object with values from a numpy array.""" @@ -27,6 +36,7 @@ def __add__(self, other: 'okid') -> 'okid': result.added_mass = self.added_mass + other.added_mass result.damping_linear = self.damping_linear + other.damping_linear return result + def __sub__(self, other: 'okid') -> 'okid': """Defines the subtraction operation between two okid_params objects.""" result = okid() @@ -34,22 +44,23 @@ def __sub__(self, other: 'okid') -> 'okid': result.added_mass = self.added_mass - other.added_mass result.damping_linear = self.damping_linear - other.damping_linear return result - + def __sub__(self, other: np.ndarray) -> 'okid': - """ Defines sub between okid_params and np.ndarray.""" + """Defines sub between okid_params and np.ndarray.""" result = okid() result.inertia = self.inertia - other[0:9] result.added_mass = self.added_mass - other[9:15] result.damping_linear = self.damping_linear - other[15:] return result - + def __rmul__(self, scalar: float) -> 'okid': """Defines the multiplication operation between a scalar and okid_params object.""" result = okid() result.inertia = scalar * self.inertia result.added_mass = scalar * self.added_mass result.damping_linear = scalar * self.damping_linear - return result + return result + @dataclass class StateQuat: @@ -65,8 +76,15 @@ class StateQuat: def as_vector(self) -> np.ndarray: """Returns the StateVector as a numpy array.""" return np.concatenate( - [self.position, self.orientation, self.velocity, self.angular_velocity, self.okid_params.as_vector()] + [ + self.position, + self.orientation, + self.velocity, + self.angular_velocity, + self.okid_params.as_vector(), + ] ) + def dynamic_part(self) -> np.ndarray: """Returns the dynamic part of the state vector.""" return np.concatenate( @@ -108,7 +126,7 @@ def fill_states(self, state: np.ndarray) -> None: self.velocity = state[7:10] self.angular_velocity = state[10:13] self.okid_params.fill(state[13:]) - + def fill_dynamic_states(self, state: np.ndarray, state_euler: np.ndarray) -> None: """Fills only the dynamic part of the state vector with the values from a numpy array.""" self.position = state[0:3] + state_euler[0:3] @@ -334,6 +352,8 @@ def euler_forward(self) -> StateQuat: + self.state_vector_dot.angular_velocity * self.dt ) return self.state_vector + + @dataclass class okid_process_model: state_vector: StateQuat = field(default_factory=StateQuat) @@ -396,8 +416,8 @@ def D(self) -> np.ndarray: """Calculates the damping matrix.""" D_l = -np.diag(self.damping_linear) - return D_l - + return D_l + def model_prediction(self, state: StateQuat) -> None: """Calculates the model of the system.""" self.state_vector = state @@ -438,6 +458,7 @@ def euler_forward(self) -> None: ) return self.state_vector + def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: """Converts Euler angles to a quaternion.""" psi, theta, phi = euler_angles diff --git a/navigation/ukf_okid/ukf_python/ukf_ros.py b/navigation/ukf_okid/ukf_python/ukf_ros.py index 66d01175c..a40c2f7c3 100755 --- a/navigation/ukf_okid/ukf_python/ukf_ros.py +++ b/navigation/ukf_okid/ukf_python/ukf_ros.py @@ -1,13 +1,13 @@ #!/usr/bin/env python3 +import numpy as np import rclpy from geometry_msgs.msg import TwistWithCovarianceStamped, WrenchStamped from nav_msgs.msg import Odometry from rclpy.node import Node from rclpy.qos import HistoryPolicy, QoSProfile, ReliabilityPolicy -from std_msgs.msg import Bool, String from ukf_okid import UKF -from ukf_okid_class import StateQuat, process_model, MeasModel -import numpy as np +from ukf_okid_class import MeasModel, StateQuat, process_model + class UKFNode(Node): def __init__(self): @@ -19,16 +19,24 @@ def __init__(self): depth=1, ) - #subcribers - self.dvl_subscriber = self.create_subscription(TwistWithCovarianceStamped, + # subscribers + self.dvl_subscriber = self.create_subscription( + TwistWithCovarianceStamped, "/orca/twist", self.dvl_callback, qos_profile=best_effort_qos, ) - self.control_input = self.create_subscription(WrenchStamped,"/orca/wrench_input", self.control_callback, qos_profile=best_effort_qos,) + self.control_input = self.create_subscription( + WrenchStamped, + "/orca/wrench_input", + self.control_callback, + qos_profile=best_effort_qos, + ) - self.odom_publish = self.create_publisher(Odometry, "/orca/odometry", qos_profile=best_effort_qos) + self.odom_publish = self.create_publisher( + Odometry, "/orca/odometry", qos_profile=best_effort_qos + ) dt = self.declare_parameter("dt", 0.01).get_parameter_value().double_value self.control_timer = self.create_timer(dt, self.odom_publisher) @@ -38,24 +46,23 @@ def __init__(self): P0 = np.eye(12) * 0.5 self.ukf_model = process_model() self.ukf_model.dt = 0.01 - self.ukf_model.mass_interia_matrix = np.array([ - [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], - ]) + self.ukf_model.mass_interia_matrix = np.array( + [ + [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], + ] + ) self.ukf_model.m = 30.0 self.ukf_model.r_b_bg = np.array([0.01, 0.0, 0.02]) self.ukf_model.inertia = np.diag([0.68, 3.32, 3.34]) self.ukf_model.damping_linear = np.array([0.01] * 6) # self.ukf_model.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) - Q = np.diag([0.02, 0.02, 0.02, - 0.02, 0.02, 0.02, - 0.1, 0.1, 0.1, - 0.1, 0.1, 0.1]) + Q = np.diag([0.02, 0.02, 0.02, 0.02, 0.02, 0.02, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) self.ukf = UKF(self.ukf_model, x0, P0, Q) self.ukf_flagg = False @@ -65,18 +72,51 @@ def dvl_callback(self, msg: TwistWithCovarianceStamped): dvl_measurement = MeasModel() # Print received DVL data to console # self.get_logger().info(f"DVL data received: x={msg.twist.twist.linear.x}, y={msg.twist.twist.linear.y}, z={msg.twist.twist.linear.z}") - dvl_measurement.measurement = np.array([msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z]) - dvl_measurement.covariance = np.array([[msg.twist.covariance[0], msg.twist.covariance[1], msg.twist.covariance[3]], - [msg.twist.covariance[6], msg.twist.covariance[7], msg.twist.covariance[8]], - [msg.twist.covariance[12], msg.twist.covariance[13], msg.twist.covariance[14]]]) - + dvl_measurement.measurement = np.array( + [ + msg.twist.twist.linear.x, + msg.twist.twist.linear.y, + msg.twist.twist.linear.z, + ] + ) + dvl_measurement.covariance = np.array( + [ + [ + msg.twist.covariance[0], + msg.twist.covariance[1], + msg.twist.covariance[3], + ], + [ + msg.twist.covariance[6], + msg.twist.covariance[7], + msg.twist.covariance[8], + ], + [ + msg.twist.covariance[12], + msg.twist.covariance[13], + msg.twist.covariance[14], + ], + ] + ) + self.ukf.measurement_update(self.current_state, dvl_measurement) - self.current_state = self.ukf.posteriori_estimate(self.current_state, dvl_measurement) + self.current_state = self.ukf.posteriori_estimate( + self.current_state, dvl_measurement + ) self.ukf_flagg = True - - def control_callback(self, msg:WrenchStamped): + + def control_callback(self, msg: WrenchStamped): # unpack message - control_array = np.array([msg.wrench.force.x, msg.wrench.force.y, msg.wrench.force.z, msg.wrench.torque.x, msg.wrench.torque.y, msg.wrench.torque.z]) + control_array = np.array( + [ + msg.wrench.force.x, + msg.wrench.force.y, + msg.wrench.force.z, + msg.wrench.torque.x, + msg.wrench.torque.y, + msg.wrench.torque.z, + ] + ) self.ukf_model.Control_input = control_array def odom_publisher(self): @@ -90,7 +130,7 @@ def odom_publisher(self): msg.header.stamp = self.get_clock().now().to_msg() msg.header.frame_id = "odom" msg.child_frame_id = "base_link" - + msg.pose.pose.position.x = self.current_state.position[0] msg.pose.pose.position.y = self.current_state.position[1] msg.pose.pose.position.z = self.current_state.position[2] @@ -107,11 +147,13 @@ def odom_publisher(self): self.odom_publish.publish(msg) + def main(args=None): rclpy.init(args=args) ukf_node = UKFNode() rclpy.spin(ukf_node) rclpy.shutdown() + if __name__ == "__main__": - main() \ No newline at end of file + main() diff --git a/navigation/ukf_okid/ukf_python/ukf_test.py b/navigation/ukf_okid/ukf_python/ukf_test.py index 80ca90e86..d80427364 100644 --- a/navigation/ukf_okid/ukf_python/ukf_test.py +++ b/navigation/ukf_okid/ukf_python/ukf_test.py @@ -1,27 +1,31 @@ -import numpy as np import matplotlib.pyplot as plt -from ukf_utils import print_StateQuat +import numpy as np + # Import your classes and functions. # Adjust the import paths as necessary based on your module organization. from ukf_okid_class import ( - StateQuat, MeasModel, - iterative_quaternion_mean_statequat, - mean_set, - mean_measurement, - covariance_set, + StateQuat, covariance_measurement, + covariance_set, cross_covariance, - quaternion_super_product, - quaternion_error, - quat_to_euler, + mean_measurement, + mean_set, quat_norm, + quat_to_euler, + quaternion_super_product, ) + # For testing, define a function to create a StateQuat with small perturbations. -def create_statequat(base_vector, position_perturbation, orientation_perturbation, velocity_perturbation, angular_velocity_perturbation): - """ - Creates a StateQuat object. +def create_statequat( + base_vector, + position_perturbation, + orientation_perturbation, + velocity_perturbation, + angular_velocity_perturbation, +): + """Creates a StateQuat object. - base_vector: 1D numpy array for base state (13 elements: position (3), quaternion (4), velocity (3), angular_velocity (3)) - ..._perturbation: small perturbation vector to be added to each respective component. @@ -37,19 +41,22 @@ def create_statequat(base_vector, position_perturbation, orientation_perturbatio noise_quat = np.array([1.0, 0.0, 0.0, 0.0]) else: noise_axis = orientation_perturbation / noise_angle - noise_quat = np.concatenate(([np.cos(noise_angle/2)], np.sin(noise_angle/2) * noise_axis)) + noise_quat = np.concatenate( + ([np.cos(noise_angle / 2)], np.sin(noise_angle / 2) * noise_axis) + ) state.orientation = quat_norm(quaternion_super_product(base_quat, noise_quat)) state.velocity = base_vector[7:10] + velocity_perturbation state.angular_velocity = base_vector[10:13] + angular_velocity_perturbation - - # For the augmented parameters (OKID parameters), set a 21-element vector: + + # For the augmented parameters (OKID parameters), set a 21-element vector: # 9 for inertia, 6 for added_mass, and 6 for damping_linear. state.okid_params.fill(np.concatenate((np.zeros(9), np.zeros(6), np.zeros(6)))) - + # Set a default covariance (33x33 for the extended state) state.covariance = np.eye(33) * 0.01 return state + # Test functions for state statistics def test_state_statistics(): # Define a base state vector (13 elements: position, quaternion, velocity, angular_velocity) @@ -58,7 +65,7 @@ def test_state_statistics(): base_vector[3:7] = np.array([1.0, 0.0, 0.0, 0.0]) # identity quaternion base_vector[7:10] = np.array([0.1, 0.2, 0.3]) base_vector[10:13] = np.array([0.01, 0.02, 0.03]) - + # Create a list of StateQuat objects with small random perturbations. np.random.seed(42) state_list = [] @@ -68,27 +75,32 @@ def test_state_statistics(): ori_noise = np.random.normal(0, 0.01, 3) vel_noise = np.random.normal(0, 0.02, 3) ang_vel_noise = np.random.normal(0, 0.005, 3) - state_list.append(create_statequat(base_vector, pos_noise, ori_noise, vel_noise, ang_vel_noise)) - + state_list.append( + create_statequat( + base_vector, pos_noise, ori_noise, vel_noise, ang_vel_noise + ) + ) + # Compute the state mean using mean_set. mean_state_vec = mean_set(state_list) print("Computed mean state vector:") print(mean_state_vec) - + # Compute the covariance of the states. cov_state = covariance_set(state_list, mean_state_vec) print("Computed state covariance matrix:") print(cov_state) - + # Check symmetry of the covariance: asym_error = np.linalg.norm(cov_state - cov_state.T) print("Covariance symmetry error (should be near 0):", asym_error) - + # Check eigenvalues for positive semidefiniteness: eigvals = np.linalg.eigvals(cov_state) print("Eigenvalues of state covariance:") print(eigvals) - + + def test_measurement_statistics(): # Create a list of measurement objects (MeasModel) with measurements in R^3. np.random.seed(24) @@ -100,17 +112,17 @@ def test_measurement_statistics(): meas = MeasModel() meas.measurement = base_meas + noise meas_list.append(meas) - + # Compute the measurement mean. mean_meas = mean_measurement(meas_list) print("Computed measurement mean:") print(mean_meas) - + # Compute the measurement covariance. cov_meas = covariance_measurement(meas_list, mean_meas) print("Computed measurement covariance:") print(cov_meas) - + # Check symmetry and eigenvalues. asym_error = np.linalg.norm(cov_meas - cov_meas.T) print("Measurement covariance symmetry error:", asym_error) @@ -118,6 +130,7 @@ def test_measurement_statistics(): print("Eigenvalues of measurement covariance:") print(eigvals) + def test_cross_covariance(): # Create a set of StateQuat and corresponding MeasModel objects. np.random.seed(99) @@ -129,58 +142,50 @@ def test_cross_covariance(): base_vector[3:7] = np.array([1.0, 0.0, 0.0, 0.0]) base_vector[7:10] = np.array([0.05, 0.1, 0.15]) base_vector[10:13] = np.array([0.005, 0.01, 0.015]) - + for _ in range(num): pos_noise = np.random.normal(0, 0.02, 3) ori_noise = np.random.normal(0, 0.005, 3) vel_noise = np.random.normal(0, 0.01, 3) ang_vel_noise = np.random.normal(0, 0.002, 3) - state = create_statequat(base_vector, pos_noise, ori_noise, vel_noise, ang_vel_noise) + state = create_statequat( + base_vector, pos_noise, ori_noise, vel_noise, ang_vel_noise + ) state_list.append(state) - + # Generate a measurement from each state (e.g., state velocity plus noise). meas = MeasModel() meas.measurement = state.velocity + np.random.normal(0, 0.01, 3) meas_list.append(meas) - + # Compute the state mean and measurement mean as vectors. mean_state_vec = mean_set(state_list) mean_meas = mean_measurement(meas_list) - + cross_cov = cross_covariance(state_list, mean_state_vec, meas_list, mean_meas) print("Computed cross-covariance between state and measurement:") print(cross_cov) + import time -import numpy as np -import matplotlib.pyplot as plt + +from ukf_okid import UKF # Import your classes and functions. from ukf_okid_class import ( - StateQuat, - MeasModel, - iterative_quaternion_mean_statequat, - mean_set, - mean_measurement, - covariance_set, - covariance_measurement, - cross_covariance, - quaternion_super_product, - quaternion_error, - quat_norm, -) -from ukf_okid import UKF -from ukf_okid_class import process_model, okid_process_model # Your process model classes + okid_process_model, + process_model, +) # Your process model classes + ############################################ # Helper function to create a StateQuat with perturbations. ############################################ def create_statequat(base_vector, pos_noise, ori_noise, vel_noise, ang_vel_noise): - """ - Create a StateQuat object from a base vector (13 elements: + """Create a StateQuat object from a base vector (13 elements: position (3), quaternion (4), velocity (3), angular_velocity (3)) plus additive noise on each component. - + For the OKID parameters, we assume a 21-element vector: - first 9: inertia, - next 6: added_mass, @@ -194,49 +199,60 @@ def create_statequat(base_vector, pos_noise, ori_noise, vel_noise, ang_vel_noise noise_quat = np.array([1.0, 0.0, 0.0, 0.0]) else: noise_axis = ori_noise / noise_angle - noise_quat = np.concatenate(([np.cos(noise_angle/2)], - np.sin(noise_angle/2) * noise_axis)) + noise_quat = np.concatenate( + ([np.cos(noise_angle / 2)], np.sin(noise_angle / 2) * noise_axis) + ) state.orientation = quat_norm(quaternion_super_product(base_quat, noise_quat)) state.velocity = base_vector[7:10] + vel_noise state.angular_velocity = base_vector[10:13] + ang_vel_noise # Set OKID parameters to exactly 21 elements (9,6,6) - state.okid_params.fill(np.concatenate((np.array([0.0, 0.0, 0.3, 0.0, 0.0, 3.3, 0.0, 0.0, 3.3]), np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0]), np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0])))) + state.okid_params.fill( + np.concatenate( + ( + np.array([0.0, 0.0, 0.3, 0.0, 0.0, 3.3, 0.0, 0.0, 3.3]), + np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0]), + np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0]), + ) + ) + ) # Set an initial covariance (33x33) for the full augmented state. state.covariance = np.eye(33) * 0.02 return state + ############################################ # Full Filter Simulation Test ############################################ def run_ukf_simulation(): - dt = 0.01 # Time step for simulation [s] - simulation_time = 10 # Total simulation time in seconds + dt = 0.01 # Time step for simulation [s] + simulation_time = 10 # Total simulation time in seconds num_steps = int(simulation_time / dt) - + # Define a base state vector (13 elements: pos, quat, vel, ang_vel) base_vector = np.zeros(13) - base_vector[0:3] = np.array([0.0, 0.0, 0.0]) + base_vector[0:3] = np.array([0.0, 0.0, 0.0]) base_vector[3:7] = np.array([1.0, 0.0, 0.0, 0.0]) # identity quaternion - base_vector[7:10] = np.array([0.1, 0.0, 0.0]) # small velocity in x + base_vector[7:10] = np.array([0.1, 0.0, 0.0]) # small velocity in x base_vector[10:13] = np.array([0.0, 0.0, 0.0]) - + # Define initial covariance for state (33x33) P0 = np.eye(33) P0[0:3, 0:3] = np.eye(3) * 0.01 # position P0[3:6, 3:6] = np.eye(3) * 0.01 # orientation error (quaternion) P0[6:9, 6:9] = np.eye(3) * 0.01 # velocity - P0[9:12, 9:12] = np.eye(3) * 0.01 # angular velocity - P0[12:33, 12:33] = np.eye(21) * 0.001 # OKID parameters + P0[9:12, 9:12] = np.eye(3) * 0.01 # angular velocity + P0[12:33, 12:33] = np.eye(21) * 0.001 # OKID parameters # Define process noise covariance Q (33x33) Q = np.zeros((33, 33)) - Q[0:3, 0:3] = np.eye(3)*0.001 # for position - Q[3:6, 3:6] = np.eye(3)*0.001 # for orientation error (represented with Euler angles) - Q[6:9, 6:9] = np.eye(3)*0.001 # for velocity - Q[9:12, 9:12] = np.eye(3)*0.001 # for angular velocity - Q[12:33, 12:33] = np.eye(21) * 0.001 # OKID parameters - + Q[0:3, 0:3] = np.eye(3) * 0.001 # for position + Q[3:6, 3:6] = ( + np.eye(3) * 0.001 + ) # for orientation error (represented with Euler angles) + Q[6:9, 6:9] = np.eye(3) * 0.001 # for velocity + Q[9:12, 9:12] = np.eye(3) * 0.001 # for angular velocity + Q[12:33, 12:33] = np.eye(21) * 0.001 # OKID parameters G = np.zeros((33, 12)) G[0:3, 0:3] = np.eye(3) @@ -250,19 +266,21 @@ def run_ukf_simulation(): # Create a simulation process model and an independent UKF process model. sim_model = process_model() sim_model.dt = dt - sim_model.mass_interia_matrix = np.array([ - [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], - ]) + sim_model.mass_interia_matrix = np.array( + [ + [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], + [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], + [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], + [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], + [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], + [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], + ] + ) sim_model.m = 30.0 sim_model.r_b_bg = np.array([0.01, 0.0, 0.02]) sim_model.inertia = np.diag([0.68, 3.32, 3.34]) - sim_model.damping_linear = np.array([0.1]*6) - sim_model.added_mass = np.array([1.0,1.0,1.0,2.0,2.0,2.0]) + sim_model.damping_linear = np.array([0.1] * 6) + sim_model.added_mass = np.array([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) # UKF process model copy: ukf_model = okid_process_model() @@ -275,18 +293,14 @@ def run_ukf_simulation(): ukf_model.added_mass = sim_model.added_mass.copy() # Initialize true state and filter state. - true_state = create_statequat(base_vector, - np.zeros(3), - np.zeros(3), - np.zeros(3), - np.zeros(3)) + true_state = create_statequat( + base_vector, np.zeros(3), np.zeros(3), np.zeros(3), np.zeros(3) + ) true_state.covariance = P0.copy() - - filter_state = create_statequat(base_vector, - np.zeros(3), - np.zeros(3), - np.zeros(3), - np.zeros(3)) + + filter_state = create_statequat( + base_vector, np.zeros(3), np.zeros(3), np.zeros(3), np.zeros(3) + ) filter_state.covariance = P0.copy() # Initialize measurement model (for example, measuring velocity only) @@ -307,14 +321,16 @@ def run_ukf_simulation(): # Control input function (example: oscillatory in all directions) def control_input(t): - return np.array([ - 2*np.sin(t), - 2*np.sin(t+0.5), - 2*np.sin(t+1.0), - 0.2*np.cos(t), - 0.2*np.cos(t+0.5), - 0.2*np.cos(t+1.0) - ]) + return np.array( + [ + 2 * np.sin(t), + 2 * np.sin(t + 0.5), + 2 * np.sin(t + 1.0), + 0.2 * np.cos(t), + 0.2 * np.cos(t + 0.5), + 0.2 * np.cos(t + 1.0), + ] + ) # Set previous states. sim_model.state_vector_prev = true_state @@ -325,19 +341,19 @@ def control_input(t): # Lists for timing diagnostics. ukf_transform_times = [] ukf_update_times = [] - + # Simulation loop. for i in range(num_steps): - t_current = i*dt - + t_current = i * dt + # Update control inputs. sim_model.Control_input = control_input(t_current) ukf_model.Control_input = control_input(t_current) - + # Propagate true state using the simulation model. sim_model.model_prediction(true_state) true_state = sim_model.euler_forward() - + # Create a measurement from true state. # Here we assume we measure velocity plus noise. meas_noise = np.random.normal(0, 0.01, 3) @@ -347,7 +363,7 @@ def control_input(t): start = time.time() filter_state = ukf.unscented_transform(filter_state) ukf_transform_times.append(time.time() - start) - + # UKF measurement update every few steps. if i % 5 == 0: try: @@ -357,8 +373,10 @@ def control_input(t): ukf_update_times.append(time.time() - start) except np.linalg.LinAlgError: # If matrix is not PD, add jitter. - filter_state.covariance += np.eye(filter_state.covariance.shape[0])*1e-6 - + filter_state.covariance += ( + np.eye(filter_state.covariance.shape[0]) * 1e-6 + ) + # Store true and estimated state for diagnostics. pos_true_hist[i, :] = true_state.position pos_est_hist[i, :] = filter_state.position @@ -368,7 +386,7 @@ def control_input(t): # Assumes you have a function quat_to_euler. euler_true_hist[i, :] = quat_to_euler(true_state.orientation) euler_est_hist[i, :] = quat_to_euler(filter_state.orientation) - + # Update previous states. sim_model.state_vector_prev = true_state ukf_model.state_vector_prev = filter_state @@ -376,7 +394,7 @@ def control_input(t): # Print timing diagnostics. print("Average unscented transform time:", np.mean(ukf_transform_times)) print("Average measurement update time:", np.mean(ukf_update_times)) - + # Compute error metrics. pos_error = np.linalg.norm(pos_true_hist - pos_est_hist, axis=1) vel_error = np.linalg.norm(vel_true_hist - vel_est_hist, axis=1) @@ -384,31 +402,31 @@ def control_input(t): print("Average position error:", np.mean(pos_error)) print("Average velocity error:", np.mean(vel_error)) print("Average orientation (Euler) error:", np.mean(euler_error)) - + # Plot estimated vs true trajectory (positions). - plt.figure(figsize=(10,8)) - plt.subplot(3,1,1) - plt.plot(time_array, pos_true_hist[:,0], label="True X") - plt.plot(time_array, pos_est_hist[:,0], label="Est X", linestyle="--") + plt.figure(figsize=(10, 8)) + plt.subplot(3, 1, 1) + plt.plot(time_array, pos_true_hist[:, 0], label="True X") + plt.plot(time_array, pos_est_hist[:, 0], label="Est X", linestyle="--") plt.legend() plt.title("Position X") - - plt.subplot(3,1,2) - plt.plot(time_array, pos_true_hist[:,1], label="True Y") - plt.plot(time_array, pos_est_hist[:,1], label="Est Y", linestyle="--") + + plt.subplot(3, 1, 2) + plt.plot(time_array, pos_true_hist[:, 1], label="True Y") + plt.plot(time_array, pos_est_hist[:, 1], label="Est Y", linestyle="--") plt.legend() plt.title("Position Y") - - plt.subplot(3,1,3) - plt.plot(time_array, pos_true_hist[:,2], label="True Z") - plt.plot(time_array, pos_est_hist[:,2], label="Est Z", linestyle="--") + + plt.subplot(3, 1, 3) + plt.plot(time_array, pos_true_hist[:, 2], label="True Z") + plt.plot(time_array, pos_est_hist[:, 2], label="Est Z", linestyle="--") plt.legend() plt.title("Position Z") plt.tight_layout() plt.show() - + # Plot errors. - plt.figure(figsize=(10,4)) + plt.figure(figsize=(10, 4)) plt.plot(time_array, pos_error, label="Position Error") plt.plot(time_array, vel_error, label="Velocity Error") plt.plot(time_array, euler_error, label="Euler Angle Error") @@ -418,6 +436,7 @@ def control_input(t): plt.ylabel("Error magnitude") plt.show() + # You can also test the individual statistics functions separately: def run_diagnostics(): print("Testing state mean and covariance computation:") @@ -429,12 +448,11 @@ def run_diagnostics(): print("\nTesting cross-covariance computation:") test_cross_covariance() + if __name__ == '__main__': # First, run the diagnostics on the mean/covariance functions. run_diagnostics() - + # Then run the full UKF simulation test. print("\nRunning full UKF simulation test:") run_ukf_simulation() - - diff --git a/navigation/ukf_okid/ukf_python/ukf_test_2.py b/navigation/ukf_okid/ukf_python/ukf_test_2.py index bf58b7a1a..d3a75313b 100644 --- a/navigation/ukf_okid/ukf_python/ukf_test_2.py +++ b/navigation/ukf_okid/ukf_python/ukf_test_2.py @@ -2,10 +2,10 @@ # Define process noise covariance Q (33x33) Q = np.zeros((12, 12)) -Q[0:3, 0:3] = np.eye(3)*0.003 # for position -Q[3:6, 3:6] = np.eye(3)*0.003 # for orientation error (represented with Euler angles) -Q[6:9, 6:9] = np.eye(3)*0.002 # for velocity -Q[9:12, 9:12] = np.eye(3)*0.003 # for angular velocity +Q[0:3, 0:3] = np.eye(3) * 0.003 # for position +Q[3:6, 3:6] = np.eye(3) * 0.003 # for orientation error (represented with Euler angles) +Q[6:9, 6:9] = np.eye(3) * 0.002 # for velocity +Q[9:12, 9:12] = np.eye(3) * 0.003 # for angular velocity G = np.zeros((33, 12)) G[0:3, 0:3] = np.eye(3) @@ -14,10 +14,11 @@ G[9:12, 9:12] = np.eye(3) GG = G @ Q @ G.T + + def fancy_print_matrix(matrix, name="Matrix", precision=4): - """ - Print a matrix with fancy formatting. - + """Print a matrix with fancy formatting. + Args: matrix: numpy array to print name: name of the matrix to display @@ -26,15 +27,16 @@ def fancy_print_matrix(matrix, name="Matrix", precision=4): print(f"\n{'=' * 50}") print(f" {name} [{matrix.shape[0]}x{matrix.shape[1]}]") print(f"{'=' * 50}") - + # Set numpy print options with np.printoptions(precision=precision, suppress=True, linewidth=100): # Print each row with custom formatting for i in range(matrix.shape[0]): row = ' '.join([f"{x:8.{precision}f}" for x in matrix[i]]) print(f" {i:2d} | {row}") - + print(f"{'=' * 50}\n") + # Example usage: -fancy_print_matrix(GG, name="Process Noise Covariance (GQG')", precision=3) \ No newline at end of file +fancy_print_matrix(GG, name="Process Noise Covariance (GQG')", precision=3) From 65e846764553db49185f2c13a3e3af664a063d53 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Thu, 8 May 2025 20:19:53 +0200 Subject: [PATCH 17/30] feat: added NIS plots --- navigation/eskf/config/eskf_params.yaml | 2 +- navigation/eskf/include/eskf/eskf.hpp | 8 ++++++++ navigation/eskf/include/eskf/eskf_ros.hpp | 3 +++ navigation/eskf/src/eskf.cpp | 6 ++++++ navigation/eskf/src/eskf_ros.cpp | 9 +++++++-- 5 files changed, 25 insertions(+), 3 deletions(-) diff --git a/navigation/eskf/config/eskf_params.yaml b/navigation/eskf/config/eskf_params.yaml index 639af1fc9..961575447 100644 --- a/navigation/eskf/config/eskf_params.yaml +++ b/navigation/eskf/config/eskf_params.yaml @@ -5,4 +5,4 @@ eskf_node: odom_topic: odom diag_Q_std: [0.027293, 0.028089, 0.029067, 0.00255253, 0.00270035, 0.00280294, 0.000001, 0.000001, 0.000001, 0.00001, 0.00001, 0.00001] diag_p_init: [1.0, 1.0, 0.5, 0.5, 0.5, 1.0, 0.1, 0.1, 0.1, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] - imu_frame: [0, 0, -1, 0, -1, 0, -1, 0, 0 ] + imu_frame: [0.0, 0.0, -1.0, 0.0, -1.0, 0.0, -1.0, 0.0, 0.0] diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp index 5cc3e0708..214f462c4 100644 --- a/navigation/eskf/include/eskf/eskf.hpp +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -24,6 +24,9 @@ class ESKF { std::pair dvl_update( const dvl_measurement& dvl_meas); + // NIS + double NIS_; + private: // @brief Predict the nominal state // @param imu_meas: IMU measurement @@ -39,6 +42,11 @@ class ESKF { void error_state_prediction(const imu_measurement& imu_meas, const double dt); + // @brief Calculate the NIS + // @param innovation: Innovation vector + // @param S: Innovation covariance matrix + void NIS(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S); + // @brief Update the error state // @param dvl_meas: DVL measurement void measurement_update(const dvl_measurement& dvl_meas); diff --git a/navigation/eskf/include/eskf/eskf_ros.hpp b/navigation/eskf/include/eskf/eskf_ros.hpp index e0b777c86..44743fd75 100644 --- a/navigation/eskf/include/eskf/eskf_ros.hpp +++ b/navigation/eskf/include/eskf/eskf_ros.hpp @@ -8,6 +8,7 @@ #include #include #include +#include #include #include #include @@ -45,6 +46,8 @@ class ESKFNode : public rclcpp::Node { rclcpp::Publisher::SharedPtr odom_pub_; + rclcpp::Publisher::SharedPtr nis_pub_; + std::chrono::milliseconds time_step; rclcpp::TimerBase::SharedPtr odom_pub_timer_; diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index 84fb5e8f3..c02bf57df 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -159,6 +159,11 @@ void ESKF::error_state_prediction(const imu_measurement& imu_meas, A_d * current_error_state_.covariance * A_d.transpose() + GQG_d; } +void ESKF::NIS(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S) { + Eigen::Matrix3d S_inv = S.inverse(); + NIS_ = innovation.transpose() * S_inv * innovation; +} + void ESKF::measurement_update(const dvl_measurement& dvl_meas) { Eigen::Matrix3x18d H = calculate_h_jacobian(); Eigen::Matrix18d P = current_error_state_.covariance; @@ -167,6 +172,7 @@ void ESKF::measurement_update(const dvl_measurement& dvl_meas) { Eigen::Matrix3d S = H * P * H.transpose() + R; Eigen::Matrix18x3d K = P * H.transpose() * S.inverse(); Eigen::Vector3d innovation = dvl_meas.vel - calculate_h(); + NIS(innovation, S); current_error_state_.set_from_vector(K * innovation); Eigen::Matrix18d I_KH = Eigen::Matrix18d::Identity() - K * H; diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index e805a0c39..9d46969d9 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -37,12 +37,14 @@ void ESKFNode::set_subscribers_and_publisher() { std::string odom_topic = this->get_parameter("odom_topic").as_string(); odom_pub_ = this->create_publisher( odom_topic, qos_sensor_data); + + nis_pub_ = create_publisher("dvl/nis", 10); } void ESKFNode::set_parameters() { std::vector R_imu_correction; this->declare_parameter>("imu_frame"); - R_imu_correction = get_parameter("imu_rotation_matrix").as_double_array(); + R_imu_correction = get_parameter("imu_frame").as_double_array(); R_imu_eskf_ = Eigen::Map>( R_imu_correction.data()); @@ -53,7 +55,6 @@ void ESKFNode::set_parameters() { Eigen::Matrix12d Q; Q.setZero(); - spdlog::info("Q diagonal: {}", diag_Q_std[0]); Q.diagonal() << sq(diag_Q_std[0]), sq(diag_Q_std[1]), sq(diag_Q_std[2]), sq(diag_Q_std[3]), sq(diag_Q_std[4]), sq(diag_Q_std[5]), sq(diag_Q_std[6]), sq(diag_Q_std[7]), sq(diag_Q_std[8]), @@ -106,6 +107,10 @@ void ESKFNode::dvl_callback( msg->twist.covariance[14]; std::tie(nom_state_, error_state_) = eskf_->dvl_update(dvl_meas_); + + std_msgs::msg::Float64 nis_msg; + nis_msg.data = eskf_->NIS_; + nis_pub_->publish(nis_msg); } void ESKFNode::publish_odom() { From dd0f97a9d6f9ecf70b88a702180871bff1759f19 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Wed, 14 May 2025 00:00:00 +0200 Subject: [PATCH 18/30] fix: issues in innovation and jacobian of the measurement --- navigation/eskf/CMakeLists.txt | 2 + navigation/eskf/config/eskf_params.yaml | 6 +- navigation/eskf/include/eskf/eskf.hpp | 8 ++ navigation/eskf/include/eskf/eskf_ros.hpp | 21 +++- navigation/eskf/include/eskf/eskf_utils.hpp | 3 + navigation/eskf/include/eskf/typedefs.hpp | 18 +++- navigation/eskf/src/eskf.cpp | 103 ++++++++++++-------- navigation/eskf/src/eskf_ros.cpp | 67 +++++++++++-- navigation/eskf/src/eskf_utils.cpp | 5 + 9 files changed, 172 insertions(+), 61 deletions(-) diff --git a/navigation/eskf/CMakeLists.txt b/navigation/eskf/CMakeLists.txt index 6c8167609..c431c235f 100644 --- a/navigation/eskf/CMakeLists.txt +++ b/navigation/eskf/CMakeLists.txt @@ -18,6 +18,7 @@ find_package(tf2 REQUIRED) find_package(vortex_msgs REQUIRED) find_package(spdlog REQUIRED) find_package(fmt REQUIRED) +find_package(stonefish_ros2 REQUIRED) if(NOT DEFINED EIGEN3_INCLUDE_DIR) set(EIGEN3_INCLUDE_DIR ${EIGEN3_INCLUDE_DIRS}) @@ -42,6 +43,7 @@ ament_target_dependencies(eskf_node vortex_msgs spdlog fmt + stonefish_ros2 ) target_link_libraries(eskf_node diff --git a/navigation/eskf/config/eskf_params.yaml b/navigation/eskf/config/eskf_params.yaml index 961575447..98be8e789 100644 --- a/navigation/eskf/config/eskf_params.yaml +++ b/navigation/eskf/config/eskf_params.yaml @@ -1,8 +1,8 @@ eskf_node: ros__parameters: imu_topic: imu/data_raw - dvl_topic: /orca/twist + dvl_topic: /dvl/sim odom_topic: odom - diag_Q_std: [0.027293, 0.028089, 0.029067, 0.00255253, 0.00270035, 0.00280294, 0.000001, 0.000001, 0.000001, 0.00001, 0.00001, 0.00001] + diag_Q_std: [0.05, 0.05, 0.05, 0.00001, 0.00001, 0.00001, 0.000001, 0.000000001, 0.000000001, 0.000000001, 0.00000001, 0.00000001] diag_p_init: [1.0, 1.0, 0.5, 0.5, 0.5, 1.0, 0.1, 0.1, 0.1, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] - imu_frame: [0.0, 0.0, -1.0, 0.0, -1.0, 0.0, -1.0, 0.0, 0.0] + imu_frame: [0.0, 0.0, -1.0, 0.0, -1.0, 0.0, -1.0, 0.0, 0.0] diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp index 214f462c4..6d8d33bd5 100644 --- a/navigation/eskf/include/eskf/eskf.hpp +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -27,6 +27,12 @@ class ESKF { // NIS double NIS_; + // NEES + double NEES_; + + // ground truth + state_quat ground_truth_; + private: // @brief Predict the nominal state // @param imu_meas: IMU measurement @@ -47,6 +53,8 @@ class ESKF { // @param S: Innovation covariance matrix void NIS(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S); + void NEES(); + // @brief Update the error state // @param dvl_meas: DVL measurement void measurement_update(const dvl_measurement& dvl_meas); diff --git a/navigation/eskf/include/eskf/eskf_ros.hpp b/navigation/eskf/include/eskf/eskf_ros.hpp index 44743fd75..8cb32b173 100644 --- a/navigation/eskf/include/eskf/eskf_ros.hpp +++ b/navigation/eskf/include/eskf/eskf_ros.hpp @@ -7,11 +7,11 @@ #include #include #include +#include #include #include #include #include -#include #include "eskf/eskf.hpp" #include "eskf/typedefs.hpp" #include "spdlog/spdlog.h" @@ -21,14 +21,18 @@ class ESKFNode : public rclcpp::Node { explicit ESKFNode(); private: + + void pose_callback(const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); + + void twist_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); + // @brief Callback function for the imu topic // @param msg: Imu message containing the imu data void imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg); // @brief Callback function for the dvl topic // @param msg: TwistWithCovarianceStamped message containing the dvl data - void dvl_callback( - const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); + void dvl_callback(const stonefish_ros2::msg::DVL::SharedPtr msg); // @brief Publish the odometry message void publish_odom(); @@ -41,19 +45,26 @@ class ESKFNode : public rclcpp::Node { rclcpp::Subscription::SharedPtr imu_sub_; - rclcpp::Subscription< - geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr dvl_sub_; + rclcpp::Subscription::SharedPtr dvl_sub_; + + rclcpp::Subscription::SharedPtr pose_sub_; + + rclcpp::Subscription::SharedPtr twist_sub_; rclcpp::Publisher::SharedPtr odom_pub_; rclcpp::Publisher::SharedPtr nis_pub_; + rclcpp::Publisher::SharedPtr nees_pub_; + std::chrono::milliseconds time_step; rclcpp::TimerBase::SharedPtr odom_pub_timer_; state_quat nom_state_; + state_quat g_truth_; + state_euler error_state_; imu_measurement imu_meas_; diff --git a/navigation/eskf/include/eskf/eskf_utils.hpp b/navigation/eskf/include/eskf/eskf_utils.hpp index 100f7673d..0cc2f6887 100644 --- a/navigation/eskf/include/eskf/eskf_utils.hpp +++ b/navigation/eskf/include/eskf/eskf_utils.hpp @@ -3,11 +3,14 @@ #include "eigen3/Eigen/Dense" #include "eskf/typedefs.hpp" +#include Eigen::Matrix3d skew(const Eigen::Vector3d& v); double sq(const double& value); +double ssa(const double& angle); + Eigen::Quaterniond vector3d_to_quaternion(const Eigen::Vector3d& vector); Eigen::Quaterniond euler_to_quaternion(const Eigen::Vector3d& euler); diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index 748804be3..ab86b0a6c 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -48,7 +48,22 @@ struct state_quat { Eigen::Vector19d as_vector() const { Eigen::Vector19d vec; vec << pos, vel, quat.w(), quat.x(), quat.y(), quat.z(), gyro_bias, - accel_bias; + accel_bias, gravity; + return vec; + } + + Eigen::Vector18d nees_error(const state_quat& other) const { + Eigen::Vector18d vec; + Eigen::Vector3d euler_diff; + + euler_diff = (quat * other.quat.inverse()).toRotationMatrix().eulerAngles(0, 1, 2); + + vec << pos - other.pos, + vel - other.vel, + euler_diff, + gyro_bias - other.gyro_bias, + accel_bias - other.accel_bias, + gravity - other.gravity; return vec; } @@ -59,6 +74,7 @@ struct state_quat { diff.quat = quat * other.quat.inverse(); diff.gyro_bias = gyro_bias - other.gyro_bias; diff.accel_bias = accel_bias - other.accel_bias; + diff.gravity = gravity - other.gravity; return diff; } }; diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index c02bf57df..9325378bb 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -5,6 +5,7 @@ #include #include "eskf/eskf_utils.hpp" #include "eskf/typedefs.hpp" +#include "iostream" ESKF::ESKF(const eskf_params& params) : Q_(params.Q) {} @@ -50,37 +51,38 @@ Eigen::Matrix3x19d ESKF::calculate_hx() { Eigen::Vector3d v_n = current_nom_state_.vel; - Hx.block<3, 3>(0, 3) = R_bn; + Hx.block<3, 3>(0, 3) = R_bn.transpose(); - Eigen::Matrix dR_dq; double qw = q.w(); double qx = q.x(); double qy = q.y(); double qz = q.z(); - Eigen::Vector3d epsilon(qx, qy, qz); + Eigen::Matrix3d I3 = Eigen::Matrix3d::Identity(); - Eigen::Vector3d e_1(1, 0, 0); - Eigen::Vector3d e_2(0, 1, 0); - Eigen::Vector3d e_3(0, 0, 1); + Eigen::Vector3d eps(qx, qy, qz); - dR_dq.col(0) = - ((4 * qw * Eigen::Matrix3d::Identity()) + (2 * skew(epsilon))) * v_n; + Eigen::Matrix3d dR_deta = 2*qw * I3 - 2*skew(eps); - dR_dq.col(1) = 2 * - ((e_1 * epsilon.transpose()) + (epsilon * e_1.transpose()) + - (qw * skew(e_1))) * - v_n; + Eigen::Vector3d e1_vec(1,0,0), e2_vec(0,1,0), e3_vec(0,0,1); - dR_dq.col(2) = 2 * - ((e_2 * epsilon.transpose()) + (epsilon * e_2.transpose()) + - (qw * skew(e_2))) * - v_n; + Eigen::Matrix3d dR_dqx = -2*qx*I3 + + 2*(e1_vec*eps.transpose() + eps*e1_vec.transpose()) + - 2*qw*skew(e1_vec); - dR_dq.col(3) = 2 * - ((e_3 * epsilon.transpose()) + (epsilon * e_3.transpose()) + - (qw * skew(e_3))) * - v_n; + Eigen::Matrix3d dR_dqy = -2*qy*I3 + + 2*(e2_vec*eps.transpose() + eps*e2_vec.transpose()) + - 2*qw*skew(e2_vec); + + Eigen::Matrix3d dR_dqz = -2*qz*I3 + + 2*(e3_vec*eps.transpose() + eps*e3_vec.transpose()) + - 2*qw*skew(e3_vec); + + Eigen::Matrix dR_dq; + dR_dq.col(0) = dR_deta * v_n; + dR_dq.col(1) = dR_dqx * v_n; + dR_dq.col(2) = dR_dqy * v_n; + dR_dq.col(3) = dR_dqz * v_n; Hx.block<3, 4>(0, 6) = dR_dq; @@ -100,7 +102,7 @@ Eigen::Matrix3x18d ESKF::calculate_h_jacobian() { Eigen::Matrix3x1d ESKF::calculate_h() { Eigen::Matrix3x1d h; Eigen::Matrix3d R_bn = - current_nom_state_.quat.normalized().toRotationMatrix(); + current_nom_state_.quat.normalized().toRotationMatrix().transpose(); h = R_bn * current_nom_state_.vel; @@ -109,19 +111,13 @@ Eigen::Matrix3x1d ESKF::calculate_h() { void ESKF::nominal_state_discrete(const imu_measurement& imu_meas, const double dt) { - Eigen::Vector3d acc = - current_nom_state_.quat.normalized().toRotationMatrix() * - imu_meas.accel + - current_nom_state_.gravity; - Eigen::Vector3d gyro = imu_meas.gyro * dt / 2; - - current_nom_state_.pos = current_nom_state_.pos + - current_nom_state_.vel * dt + 0.5 * sq(dt) * acc; - current_nom_state_.vel = current_nom_state_.vel + dt * acc; + Eigen::Vector3d acc = current_nom_state_.quat.normalized().toRotationMatrix() * (imu_meas.accel - current_nom_state_.accel_bias) + current_nom_state_.gravity; + Eigen::Vector3d gyro = (imu_meas.gyro - current_nom_state_.gyro_bias) * dt; - current_nom_state_.quat = - (current_nom_state_.quat * vector3d_to_quaternion(gyro)); + current_nom_state_.pos = current_nom_state_.pos + current_nom_state_.vel * dt + 0.5 * sq(dt) * acc; + current_nom_state_.vel = current_nom_state_.vel + dt * acc; + current_nom_state_.quat = (current_nom_state_.quat * vector3d_to_quaternion(gyro)); current_nom_state_.quat.normalize(); current_nom_state_.gyro_bias = current_nom_state_.gyro_bias; @@ -132,8 +128,8 @@ void ESKF::nominal_state_discrete(const imu_measurement& imu_meas, void ESKF::error_state_prediction(const imu_measurement& imu_meas, const double dt) { Eigen::Matrix3d R = current_nom_state_.quat.normalized().toRotationMatrix(); - Eigen::Vector3d acc = imu_meas.accel; - Eigen::Vector3d gyro = imu_meas.gyro; + Eigen::Vector3d acc = (imu_meas.accel - current_nom_state_.accel_bias); + Eigen::Vector3d gyro = (imu_meas.gyro - current_nom_state_.gyro_bias); Eigen::Matrix18d A_c = Eigen::Matrix18d::Zero(); A_c.block<3, 3>(0, 3) = Eigen::Matrix3d::Identity(); @@ -164,6 +160,30 @@ void ESKF::NIS(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S) { NIS_ = innovation.transpose() * S_inv * innovation; } +void ESKF::NEES() { + + Eigen::Vector18d error_state = current_nom_state_.nees_error(ground_truth_); + + // Use SVD-based pseudo-inverse for better numerical stability + Eigen::JacobiSVD svd(current_error_state_.covariance, + Eigen::ComputeThinU | Eigen::ComputeThinV); + const double epsilon = 1e-10; // Threshold for singular values + Eigen::VectorXd singular_values = svd.singularValues(); + Eigen::VectorXd singular_values_inv(singular_values.size()); + + for (int i = 0; i < singular_values.size(); ++i) { + if (singular_values(i) > epsilon) { + singular_values_inv(i) = 1.0 / singular_values(i); + } else { + singular_values_inv(i) = 0.0; + } + } + + Eigen::MatrixXd cov_inv = svd.matrixV() * singular_values_inv.asDiagonal() * svd.matrixU().transpose(); + + NEES_ = error_state.transpose() * cov_inv * error_state; +} + void ESKF::measurement_update(const dvl_measurement& dvl_meas) { Eigen::Matrix3x18d H = calculate_h_jacobian(); Eigen::Matrix18d P = current_error_state_.covariance; @@ -179,21 +199,18 @@ void ESKF::measurement_update(const dvl_measurement& dvl_meas) { current_error_state_.covariance = I_KH * P * I_KH.transpose() + K * R * K.transpose(); // Used joseph form for more stable calculations + + NEES(); } void ESKF::injection_and_reset() { current_nom_state_.pos = current_nom_state_.pos + current_error_state_.pos; current_nom_state_.vel = current_nom_state_.vel + current_error_state_.vel; - current_nom_state_.quat = - current_nom_state_.quat * - vector3d_to_quaternion(current_error_state_.euler); + current_nom_state_.quat = current_nom_state_.quat * vector3d_to_quaternion(current_error_state_.euler); current_nom_state_.quat.normalize(); - current_nom_state_.gyro_bias = - current_nom_state_.gyro_bias + current_error_state_.gyro_bias; - current_nom_state_.accel_bias = - current_nom_state_.accel_bias + current_error_state_.accel_bias; - current_nom_state_.gravity = - current_nom_state_.gravity + current_error_state_.gravity; + current_nom_state_.gyro_bias = current_nom_state_.gyro_bias + current_error_state_.gyro_bias; + current_nom_state_.accel_bias = current_nom_state_.accel_bias + current_error_state_.accel_bias; + current_nom_state_.gravity = current_nom_state_.gravity + current_error_state_.gravity; Eigen::Matrix18d G = Eigen::Matrix18d::Identity(); diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index 9d46969d9..04b6dd9c6 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -20,6 +20,16 @@ void ESKFNode::set_subscribers_and_publisher() { auto qos_sensor_data = rclcpp::QoS( rclcpp::QoSInitialization(qos_profile.history, 1), qos_profile); + pose_sub_ = this->create_subscription< + geometry_msgs::msg::PoseWithCovarianceStamped>( + "/orca/pose", qos_sensor_data, + std::bind(&ESKFNode::pose_callback, this, std::placeholders::_1)); + + twist_sub_ = this->create_subscription< + geometry_msgs::msg::TwistWithCovarianceStamped>( + "/orca/twist", qos_sensor_data, + std::bind(&ESKFNode::twist_callback, this, std::placeholders::_1)); + this->declare_parameter("imu_topic"); std::string imu_topic = this->get_parameter("imu_topic").as_string(); imu_sub_ = this->create_subscription( @@ -29,7 +39,7 @@ void ESKFNode::set_subscribers_and_publisher() { this->declare_parameter("dvl_topic"); std::string dvl_topic = this->get_parameter("dvl_topic").as_string(); dvl_sub_ = this->create_subscription< - geometry_msgs::msg::TwistWithCovarianceStamped>( + stonefish_ros2::msg::DVL>( dvl_topic, qos_sensor_data, std::bind(&ESKFNode::dvl_callback, this, std::placeholders::_1)); @@ -39,6 +49,7 @@ void ESKFNode::set_subscribers_and_publisher() { odom_topic, qos_sensor_data); nis_pub_ = create_publisher("dvl/nis", 10); + nees_pub_ = create_publisher("dvl/nees", 10); } void ESKFNode::set_parameters() { @@ -70,6 +81,20 @@ void ESKFNode::set_parameters() { error_state_.covariance = P; } +void ESKFNode::pose_callback(const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg) { + g_truth_.pos << msg->pose.pose.position.x, + msg->pose.pose.position.y, msg->pose.pose.position.z; + g_truth_.quat.w() = msg->pose.pose.orientation.w; + g_truth_.quat.x() = msg->pose.pose.orientation.x; + g_truth_.quat.y() = msg->pose.pose.orientation.y; + g_truth_.quat.z() = msg->pose.pose.orientation.z; +} + +void ESKFNode::twist_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { + g_truth_.vel << msg->twist.twist.linear.x, + msg->twist.twist.linear.y, msg->twist.twist.linear.z; +} + void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { rclcpp::Time current_time = msg->header.stamp; @@ -97,20 +122,44 @@ void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { } void ESKFNode::dvl_callback( - const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { - dvl_meas_.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, - msg->twist.twist.linear.z; - dvl_meas_.cov << msg->twist.covariance[0], msg->twist.covariance[1], - msg->twist.covariance[2], msg->twist.covariance[6], - msg->twist.covariance[7], msg->twist.covariance[8], - msg->twist.covariance[12], msg->twist.covariance[13], - msg->twist.covariance[14]; + const stonefish_ros2::msg::DVL::SharedPtr msg) { + dvl_meas_.vel << msg->velocity.x, + msg->velocity.y, msg->velocity.z; + dvl_meas_.cov << 0.001, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.001; + + // msg->velocity_covariance[0], msg->velocity_covariance[1], msg->velocity_covariance[2], + // msg->velocity_covariance[3], msg->velocity_covariance[4], msg->velocity_covariance[5], + // msg->velocity_covariance[6], msg->velocity_covariance[7], msg->velocity_covariance[8]; + + + // Set biases and gravity as float values + float gyro_bias_x = 0.00001; + float gyro_bias_y = 0.00001; + float gyro_bias_z = 0.00001; + + float accel_bias_x = 0.00001; + float accel_bias_y = 0.00001; + float accel_bias_z = 0.00001; + + float gravity_x = 0.0; + float gravity_y = 0.0; + float gravity_z = -9.81; + + g_truth_.gyro_bias << gyro_bias_x, gyro_bias_y, gyro_bias_z; + g_truth_.accel_bias << accel_bias_x, accel_bias_y, accel_bias_z; + g_truth_.gravity << gravity_x, gravity_y, gravity_z; + + eskf_->ground_truth_ = g_truth_; std::tie(nom_state_, error_state_) = eskf_->dvl_update(dvl_meas_); std_msgs::msg::Float64 nis_msg; nis_msg.data = eskf_->NIS_; nis_pub_->publish(nis_msg); + + std_msgs::msg::Float64 nees_msg; + nees_msg.data = eskf_->NEES_; + nees_pub_->publish(nees_msg); } void ESKFNode::publish_odom() { diff --git a/navigation/eskf/src/eskf_utils.cpp b/navigation/eskf/src/eskf_utils.cpp index a07f3acda..88d04c3d5 100644 --- a/navigation/eskf/src/eskf_utils.cpp +++ b/navigation/eskf/src/eskf_utils.cpp @@ -11,6 +11,11 @@ Eigen::Matrix3d skew(const Eigen::Vector3d& v) { double sq(const double& value) { return value * value; } +double ssa(const double& angle) { + double result = fmod(angle + M_PI, 2 * M_PI); + double angle_ssa = result < 0 ? result + M_PI : result - M_PI; + return angle_ssa; +} Eigen::Quaterniond vector3d_to_quaternion(const Eigen::Vector3d& vector) { double angle = vector.norm(); From 103a057f0b2a90894e6eac149ad6bc10ab9685e5 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 13 May 2025 22:01:55 +0000 Subject: [PATCH 19/30] [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci --- navigation/eskf/include/eskf/eskf.hpp | 4 +- navigation/eskf/include/eskf/eskf_ros.hpp | 17 ++-- navigation/eskf/include/eskf/eskf_utils.hpp | 2 +- navigation/eskf/include/eskf/typedefs.hpp | 11 ++- navigation/eskf/src/eskf.cpp | 86 ++++++++++++--------- navigation/eskf/src/eskf_ros.cpp | 45 +++++------ navigation/ukf_okid/launch/ukf.launch.py | 1 - navigation/ukf_okid/ukf_python/ukf_okid.py | 4 +- 8 files changed, 92 insertions(+), 78 deletions(-) diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp index 6d8d33bd5..d9b7d4fa0 100644 --- a/navigation/eskf/include/eskf/eskf.hpp +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -27,7 +27,7 @@ class ESKF { // NIS double NIS_; - // NEES + // NEEDS double NEES_; // ground truth @@ -53,7 +53,7 @@ class ESKF { // @param S: Innovation covariance matrix void NIS(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S); - void NEES(); + void NEEDS(); // @brief Update the error state // @param dvl_meas: DVL measurement diff --git a/navigation/eskf/include/eskf/eskf_ros.hpp b/navigation/eskf/include/eskf/eskf_ros.hpp index 8cb32b173..c3d09e820 100644 --- a/navigation/eskf/include/eskf/eskf_ros.hpp +++ b/navigation/eskf/include/eskf/eskf_ros.hpp @@ -7,11 +7,11 @@ #include #include #include -#include #include #include #include #include +#include #include "eskf/eskf.hpp" #include "eskf/typedefs.hpp" #include "spdlog/spdlog.h" @@ -21,10 +21,11 @@ class ESKFNode : public rclcpp::Node { explicit ESKFNode(); private: + void pose_callback( + const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); - void pose_callback(const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); - - void twist_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); + void twist_callback( + const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); // @brief Callback function for the imu topic // @param msg: Imu message containing the imu data @@ -47,9 +48,11 @@ class ESKFNode : public rclcpp::Node { rclcpp::Subscription::SharedPtr dvl_sub_; - rclcpp::Subscription::SharedPtr pose_sub_; - - rclcpp::Subscription::SharedPtr twist_sub_; + rclcpp::Subscription< + geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr pose_sub_; + + rclcpp::Subscription< + geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr twist_sub_; rclcpp::Publisher::SharedPtr odom_pub_; diff --git a/navigation/eskf/include/eskf/eskf_utils.hpp b/navigation/eskf/include/eskf/eskf_utils.hpp index 0cc2f6887..4fcaed412 100644 --- a/navigation/eskf/include/eskf/eskf_utils.hpp +++ b/navigation/eskf/include/eskf/eskf_utils.hpp @@ -1,9 +1,9 @@ #ifndef ESKF_UTILS_HPP #define ESKF_UTILS_HPP +#include #include "eigen3/Eigen/Dense" #include "eskf/typedefs.hpp" -#include Eigen::Matrix3d skew(const Eigen::Vector3d& v); diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index ab86b0a6c..47dfe06e1 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -56,13 +56,12 @@ struct state_quat { Eigen::Vector18d vec; Eigen::Vector3d euler_diff; - euler_diff = (quat * other.quat.inverse()).toRotationMatrix().eulerAngles(0, 1, 2); + euler_diff = (quat * other.quat.inverse()) + .toRotationMatrix() + .eulerAngles(0, 1, 2); - vec << pos - other.pos, - vel - other.vel, - euler_diff, - gyro_bias - other.gyro_bias, - accel_bias - other.accel_bias, + vec << pos - other.pos, vel - other.vel, euler_diff, + gyro_bias - other.gyro_bias, accel_bias - other.accel_bias, gravity - other.gravity; return vec; } diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index 9325378bb..e0e7c7a98 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -58,31 +58,34 @@ Eigen::Matrix3x19d ESKF::calculate_hx() { double qy = q.y(); double qz = q.z(); - Eigen::Matrix3d I3 = Eigen::Matrix3d::Identity(); + Eigen::Matrix3d I3 = Eigen::Matrix3d::Identity(); Eigen::Vector3d eps(qx, qy, qz); - Eigen::Matrix3d dR_deta = 2*qw * I3 - 2*skew(eps); + Eigen::Matrix3d dR_deta = 2 * qw * I3 - 2 * skew(eps); - Eigen::Vector3d e1_vec(1,0,0), e2_vec(0,1,0), e3_vec(0,0,1); + Eigen::Vector3d e1_vec(1, 0, 0), e2_vec(0, 1, 0), e3_vec(0, 0, 1); - Eigen::Matrix3d dR_dqx = -2*qx*I3 - + 2*(e1_vec*eps.transpose() + eps*e1_vec.transpose()) - - 2*qw*skew(e1_vec); + Eigen::Matrix3d dR_dqx = + -2 * qx * I3 + + 2 * (e1_vec * eps.transpose() + eps * e1_vec.transpose()) - + 2 * qw * skew(e1_vec); - Eigen::Matrix3d dR_dqy = -2*qy*I3 - + 2*(e2_vec*eps.transpose() + eps*e2_vec.transpose()) - - 2*qw*skew(e2_vec); + Eigen::Matrix3d dR_dqy = + -2 * qy * I3 + + 2 * (e2_vec * eps.transpose() + eps * e2_vec.transpose()) - + 2 * qw * skew(e2_vec); - Eigen::Matrix3d dR_dqz = -2*qz*I3 - + 2*(e3_vec*eps.transpose() + eps*e3_vec.transpose()) - - 2*qw*skew(e3_vec); + Eigen::Matrix3d dR_dqz = + -2 * qz * I3 + + 2 * (e3_vec * eps.transpose() + eps * e3_vec.transpose()) - + 2 * qw * skew(e3_vec); - Eigen::Matrix dR_dq; - dR_dq.col(0) = dR_deta * v_n; - dR_dq.col(1) = dR_dqx * v_n; - dR_dq.col(2) = dR_dqy * v_n; - dR_dq.col(3) = dR_dqz * v_n; + Eigen::Matrix dR_dq; + dR_dq.col(0) = dR_deta * v_n; + dR_dq.col(1) = dR_dqx * v_n; + dR_dq.col(2) = dR_dqy * v_n; + dR_dq.col(3) = dR_dqz * v_n; Hx.block<3, 4>(0, 6) = dR_dq; @@ -111,13 +114,18 @@ Eigen::Matrix3x1d ESKF::calculate_h() { void ESKF::nominal_state_discrete(const imu_measurement& imu_meas, const double dt) { - Eigen::Vector3d acc = current_nom_state_.quat.normalized().toRotationMatrix() * (imu_meas.accel - current_nom_state_.accel_bias) + current_nom_state_.gravity; + Eigen::Vector3d acc = + current_nom_state_.quat.normalized().toRotationMatrix() * + (imu_meas.accel - current_nom_state_.accel_bias) + + current_nom_state_.gravity; Eigen::Vector3d gyro = (imu_meas.gyro - current_nom_state_.gyro_bias) * dt; - current_nom_state_.pos = current_nom_state_.pos + current_nom_state_.vel * dt + 0.5 * sq(dt) * acc; + current_nom_state_.pos = current_nom_state_.pos + + current_nom_state_.vel * dt + 0.5 * sq(dt) * acc; current_nom_state_.vel = current_nom_state_.vel + dt * acc; - current_nom_state_.quat = (current_nom_state_.quat * vector3d_to_quaternion(gyro)); + current_nom_state_.quat = + (current_nom_state_.quat * vector3d_to_quaternion(gyro)); current_nom_state_.quat.normalize(); current_nom_state_.gyro_bias = current_nom_state_.gyro_bias; @@ -160,17 +168,17 @@ void ESKF::NIS(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S) { NIS_ = innovation.transpose() * S_inv * innovation; } -void ESKF::NEES() { - +void ESKF::NEEDS() { Eigen::Vector18d error_state = current_nom_state_.nees_error(ground_truth_); - + // Use SVD-based pseudo-inverse for better numerical stability - Eigen::JacobiSVD svd(current_error_state_.covariance, - Eigen::ComputeThinU | Eigen::ComputeThinV); - const double epsilon = 1e-10; // Threshold for singular values + Eigen::JacobiSVD svd( + current_error_state_.covariance, + Eigen::ComputeThinU | Eigen::ComputeThinV); + const double epsilon = 1e-10; // Threshold for singular values Eigen::VectorXd singular_values = svd.singularValues(); Eigen::VectorXd singular_values_inv(singular_values.size()); - + for (int i = 0; i < singular_values.size(); ++i) { if (singular_values(i) > epsilon) { singular_values_inv(i) = 1.0 / singular_values(i); @@ -178,9 +186,10 @@ void ESKF::NEES() { singular_values_inv(i) = 0.0; } } - - Eigen::MatrixXd cov_inv = svd.matrixV() * singular_values_inv.asDiagonal() * svd.matrixU().transpose(); - + + Eigen::MatrixXd cov_inv = svd.matrixV() * singular_values_inv.asDiagonal() * + svd.matrixU().transpose(); + NEES_ = error_state.transpose() * cov_inv * error_state; } @@ -199,18 +208,23 @@ void ESKF::measurement_update(const dvl_measurement& dvl_meas) { current_error_state_.covariance = I_KH * P * I_KH.transpose() + K * R * K.transpose(); // Used joseph form for more stable calculations - - NEES(); + + NEEDS(); } void ESKF::injection_and_reset() { current_nom_state_.pos = current_nom_state_.pos + current_error_state_.pos; current_nom_state_.vel = current_nom_state_.vel + current_error_state_.vel; - current_nom_state_.quat = current_nom_state_.quat * vector3d_to_quaternion(current_error_state_.euler); + current_nom_state_.quat = + current_nom_state_.quat * + vector3d_to_quaternion(current_error_state_.euler); current_nom_state_.quat.normalize(); - current_nom_state_.gyro_bias = current_nom_state_.gyro_bias + current_error_state_.gyro_bias; - current_nom_state_.accel_bias = current_nom_state_.accel_bias + current_error_state_.accel_bias; - current_nom_state_.gravity = current_nom_state_.gravity + current_error_state_.gravity; + current_nom_state_.gyro_bias = + current_nom_state_.gyro_bias + current_error_state_.gyro_bias; + current_nom_state_.accel_bias = + current_nom_state_.accel_bias + current_error_state_.accel_bias; + current_nom_state_.gravity = + current_nom_state_.gravity + current_error_state_.gravity; Eigen::Matrix18d G = Eigen::Matrix18d::Identity(); diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index 04b6dd9c6..54daadb4c 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -24,7 +24,7 @@ void ESKFNode::set_subscribers_and_publisher() { geometry_msgs::msg::PoseWithCovarianceStamped>( "/orca/pose", qos_sensor_data, std::bind(&ESKFNode::pose_callback, this, std::placeholders::_1)); - + twist_sub_ = this->create_subscription< geometry_msgs::msg::TwistWithCovarianceStamped>( "/orca/twist", qos_sensor_data, @@ -38,8 +38,7 @@ void ESKFNode::set_subscribers_and_publisher() { this->declare_parameter("dvl_topic"); std::string dvl_topic = this->get_parameter("dvl_topic").as_string(); - dvl_sub_ = this->create_subscription< - stonefish_ros2::msg::DVL>( + dvl_sub_ = this->create_subscription( dvl_topic, qos_sensor_data, std::bind(&ESKFNode::dvl_callback, this, std::placeholders::_1)); @@ -49,7 +48,7 @@ void ESKFNode::set_subscribers_and_publisher() { odom_topic, qos_sensor_data); nis_pub_ = create_publisher("dvl/nis", 10); - nees_pub_ = create_publisher("dvl/nees", 10); + nees_pub_ = create_publisher("dvl/needs", 10); } void ESKFNode::set_parameters() { @@ -81,18 +80,20 @@ void ESKFNode::set_parameters() { error_state_.covariance = P; } -void ESKFNode::pose_callback(const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg) { - g_truth_.pos << msg->pose.pose.position.x, - msg->pose.pose.position.y, msg->pose.pose.position.z; +void ESKFNode::pose_callback( + const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg) { + g_truth_.pos << msg->pose.pose.position.x, msg->pose.pose.position.y, + msg->pose.pose.position.z; g_truth_.quat.w() = msg->pose.pose.orientation.w; g_truth_.quat.x() = msg->pose.pose.orientation.x; g_truth_.quat.y() = msg->pose.pose.orientation.y; g_truth_.quat.z() = msg->pose.pose.orientation.z; } -void ESKFNode::twist_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { - g_truth_.vel << msg->twist.twist.linear.x, - msg->twist.twist.linear.y, msg->twist.twist.linear.z; +void ESKFNode::twist_callback( + const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { + g_truth_.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, + msg->twist.twist.linear.z; } void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { @@ -121,30 +122,30 @@ void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { std::tie(nom_state_, error_state_) = eskf_->imu_update(imu_meas_, dt); } -void ESKFNode::dvl_callback( - const stonefish_ros2::msg::DVL::SharedPtr msg) { - dvl_meas_.vel << msg->velocity.x, - msg->velocity.y, msg->velocity.z; +void ESKFNode::dvl_callback(const stonefish_ros2::msg::DVL::SharedPtr msg) { + dvl_meas_.vel << msg->velocity.x, msg->velocity.y, msg->velocity.z; dvl_meas_.cov << 0.001, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.001; - - // msg->velocity_covariance[0], msg->velocity_covariance[1], msg->velocity_covariance[2], - // msg->velocity_covariance[3], msg->velocity_covariance[4], msg->velocity_covariance[5], - // msg->velocity_covariance[6], msg->velocity_covariance[7], msg->velocity_covariance[8]; - + + // msg->velocity_covariance[0], msg->velocity_covariance[1], + // msg->velocity_covariance[2], + // msg->velocity_covariance[3], msg->velocity_covariance[4], + // msg->velocity_covariance[5], + // msg->velocity_covariance[6], msg->velocity_covariance[7], + // msg->velocity_covariance[8]; // Set biases and gravity as float values float gyro_bias_x = 0.00001; float gyro_bias_y = 0.00001; float gyro_bias_z = 0.00001; - + float accel_bias_x = 0.00001; float accel_bias_y = 0.00001; float accel_bias_z = 0.00001; - + float gravity_x = 0.0; float gravity_y = 0.0; float gravity_z = -9.81; - + g_truth_.gyro_bias << gyro_bias_x, gyro_bias_y, gyro_bias_z; g_truth_.accel_bias << accel_bias_x, accel_bias_y, accel_bias_z; g_truth_.gravity << gravity_x, gravity_y, gravity_z; diff --git a/navigation/ukf_okid/launch/ukf.launch.py b/navigation/ukf_okid/launch/ukf.launch.py index baf6fb645..5d075259f 100644 --- a/navigation/ukf_okid/launch/ukf.launch.py +++ b/navigation/ukf_okid/launch/ukf.launch.py @@ -1,4 +1,3 @@ - from launch import LaunchDescription from launch_ros.actions import Node diff --git a/navigation/ukf_okid/ukf_python/ukf_okid.py b/navigation/ukf_okid/ukf_python/ukf_okid.py index 474b94ac6..e50c65c3a 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid.py @@ -39,9 +39,7 @@ def generate_delta_matrix(self, n: float) -> np.ndarray: for i in range(2 * n): for j in range(n // 2): - delta[2 * j + 1, i] = ( - np.sqrt(2) * np.sin(2 * j - 1) * ((k * np.pi) / n) - ) + delta[2 * j + 1, i] = np.sqrt(2) * np.sin(2 * j - 1) * ((k * np.pi) / n) delta[2 * j, i] = np.sqrt(2) * np.cos(2 * j - 1) * ((k * np.pi) / n) if (n % 2) == 1: From 124f33772dfa2edfc07f88641cabceab6d3bc4eb Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Wed, 14 May 2025 11:22:07 +0200 Subject: [PATCH 20/30] feat: Adding in the TUKF and the UKF --- navigation/tukf/test_tukf.py | 347 +++++++++++++ navigation/tukf/tukf.py | 126 +++++ navigation/tukf/tukf_class.py | 437 ++++++++++++++++ navigation/ukf_okid/ukf_python/ukf_okid.py | 25 +- .../ukf_okid/ukf_python/ukf_okid_class.py | 186 ++++++- navigation/ukf_okid/ukf_python/ukf_test.py | 471 +----------------- navigation/ukf_okid/ukf_python/ukf_test_2.py | 249 +++++++-- 7 files changed, 1331 insertions(+), 510 deletions(-) create mode 100644 navigation/tukf/test_tukf.py create mode 100644 navigation/tukf/tukf.py create mode 100644 navigation/tukf/tukf_class.py diff --git a/navigation/tukf/test_tukf.py b/navigation/tukf/test_tukf.py new file mode 100644 index 000000000..2998855ea --- /dev/null +++ b/navigation/tukf/test_tukf.py @@ -0,0 +1,347 @@ +import numpy as np +from tukf import TUKF +import tukf_class as ukf +from mpl_toolkits.mplot3d import Axes3D +import time +import math + +import matplotlib.pyplot as plt + +# Initialize UKF with StateQuat +initial_position = np.array([0.0, 0.0, 0.0]) # x, y, z +initial_velocity = np.array([0.0, 0.0, 0.0]) # vx, vy, vz +initial_quaternion = np.array([0.0, 0.0, 0.0]) # w, x, y, z (identity quaternion) +initial_angular_velocity = np.array([0.0, 0.0, 0.0]) # wx, wy, wz +initial_g_eta = np.array([1.2, 0.3, 0.3, 0.3]) # g_eta parameters +initial_intertia = np.array([0.68, 0.2, 0.1, + 0.2, 3.32, 0.2, + 0.1, 0.2, 3.34]) +initial_damping = np.array([0.01, 0.01, 0.01, + 0.01, 0.01, 0.01]) +initla_added_mass = np.array([0.02, 0.02, 0.02, + 0.02, 0.02, 0.02]) + +p_diag = np.concatenate([ + 2*np.ones(3), # x position + 2*np.ones(3), # orientation + 2*np.ones(3), # velocity + 2*np.ones(3), # angular velocity + 2*np.ones(9), # inertia + 2*np.ones(6), # added mass + 2*np.ones(6), # damping + 2*np.ones(4) # g_eta +]) + +initial_covariance = np.diag(p_diag) + +state = ukf.AUVState(initial_position.copy(), initial_quaternion.copy(), initial_velocity.copy(), initial_angular_velocity.copy()) +state.covariance = initial_covariance.copy() +state.inertia = np.array([0.58, 0.1, 0.05, + 0.1, 2.32, 0.1, + 0.01, 0.1, 2.34]) +state.g_eta = np.array([1.1, 0.1, 0.1, 0.1]) +state.damping = np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0]) +state.added_mass = np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0]) + +real_state = ukf.AUVState(initial_position.copy(), initial_quaternion.copy(), initial_velocity.copy(), initial_angular_velocity.copy()) +real_state.inertia = initial_intertia.copy() +real_state.g_eta = initial_g_eta.copy() +real_state.damping = initial_damping.copy() +real_state.added_mass = initla_added_mass.copy() + +Q_diag = np.concatenate([ + 0.01*np.ones(3), # position + 0.2*np.ones(9), # kinematic (η & ν) + 0.8*np.ones(9), # inertia + 0.8*np.ones(6), # added mass + 0.8*np.ones(6), # damping + 0.8*np.ones(4), # g_eta +]) + +UKF_model = TUKF(state, np.diag(Q_diag)) # Process noise covariance + +def dvl_h(state: ukf.AUVState) -> 'ukf.MeasModel': + H_matrix = np.zeros((3, 12)) + H_matrix[:, 6:9] = np.eye(3) + z_i = ukf.MeasModel() + z_i.measurement = np.dot(H_matrix, state.dynamic_part()) + return z_i + +dvl_measurement = ukf.MeasModel(H=dvl_h) + +def ang_h(state: ukf.AUVState) -> 'ukf.MeasModel': + H_matrix = np.zeros((3, 12)) + H_matrix[:, 9:12] = np.eye(3) + z_i = ukf.MeasModel() + z_i.measurement = np.dot(H_matrix, state.dynamic_part()) + return z_i + +ang_measurement = ukf.MeasModel(H=ang_h) + +# UKF parameters +dt = 0.01 # time step +sim_time = 50.0 # total simulation time +steps = int(sim_time / dt) + +# Storage for trajectory +positions = np.zeros((steps, 3)) +velocities = np.zeros((steps, 3)) +quaternions = np.zeros((steps, 3)) +angular_velocities = np.zeros((steps, 3)) +okid_params = np.zeros((steps, 25)) + +# Storage for trajectory +positions_est = np.zeros((steps, 3)) +velocities_est = np.zeros((steps, 3)) +quaternions_est = np.zeros((steps, 3)) +angular_velocities_est = np.zeros((steps, 3)) +okid_params_est = np.zeros((steps, 25)) + +# ---------- user‑tunable manoeuvre parameters ----------------------------- +SEG_DUR = 10.0 # [s] duration of each phase +A_F_TRANSL = 2.0 # [N] translational force amplitude +A_T_ROT = 1.0 # [N·m] rotational torque amplitude +# -------------------------------------------------------------------------- + +# Helper: build the scripted sequence as (kind, axis_idx, sign) +# kind = 'F' for force, 'T' for torque +# axes: 0‑x (surge/roll), 1‑y (sway/pitch), 2‑z (heave/yaw) +sequence = [ + ('F', 2, +1), # +z (up) + ('F', 2, -1), # –z (down) + ('F', 1, +1), # +y (right) + ('F', 1, -1), # –y (left / “back” sideways) + ('F', 0, +1), # +x (forward) + ('F', 0, -1), # –x (backward) + ('T', 2, +1), # +yaw (turn right) + ('T', 2, -1), # –yaw (turn left) + ('T', 1, +1), # +pitch (nose up) + ('T', 1, -1), # –pitch (nose down) + ('T', 0, +1), # +roll (starboard roll) + ('T', 0, -1) # –roll (port roll) +] + +TOTAL_TIME = len(sequence) * SEG_DUR # handy if you need it + +def _half_sine(local_t: float, duration: float) -> float: + """Smooth window: 0 → 1 → 0 over `duration` (half‑sine).""" + return np.sin(np.pi * local_t / duration) + +def control_inputs(t: float) -> tuple[np.ndarray, np.ndarray]: + """ + Piecewise scripted test signal: + – translations along z, y, x + – rotations about z (yaw), y (pitch), x (roll) + """ + # Default: no actuation + F = np.zeros(3) + T = np.zeros(3) + + # Past the last segment? keep everything zero + idx = int(t // SEG_DUR) + if idx >= len(sequence): + return F, T + + # Time inside current segment + tau = t - idx * SEG_DUR + window = _half_sine(tau, SEG_DUR) # 0‑to‑1‑to‑0 shape + + kind, axis, sgn = sequence[idx] + + if kind == 'F': + F[axis] = sgn * A_F_TRANSL * window + else: # 'T' + T[axis] = sgn * A_T_ROT * window + + return F, T + +# Simulation loop +for i in range(steps): + t = i * dt + + control_force, control_torque = control_inputs(t) + + control_input = np.concatenate((control_force, control_torque)) + + # Propagate state using UKF prediction + real_state = ukf.F_dynamics(real_state, dt, control_input) + state = UKF_model.unscented_transform(state, control_input) + + if UKF_model.filter_failed: + print("Filter failed, stopping simulation.") + break + + if i % 5 == 0: + # Simulate measurement update every 5 steps + ang_measurement.measurement = np.array([ + real_state.angular_velocity[0], + real_state.angular_velocity[1], + real_state.angular_velocity[2] + ]) + np.random.normal(0, 0.04, 3) + + ang_measurement.covariance = np.eye(3) * (0.03**2) # Measurement noise covariance + + UKF_model.measurement_update(state, ang_measurement) + state = UKF_model.posteriori_estimate(state, ang_measurement) + + if i % 10 == 0: + # Simulate measurement update every 10 steps + dvl_measurement.measurement = np.array([ + real_state.velocity[0], + real_state.velocity[1], + real_state.velocity[2] + ]) + np.random.normal(0, 0.04, 3) # Simulated measurement with noise + + # Simulate measurement covariance + dvl_measurement.covariance = np.eye(3) * (0.03**2) # Measurement noise covariance + + # Update UKF with measurement + UKF_model.measurement_update(state, dvl_measurement) + state = UKF_model.posteriori_estimate(state, dvl_measurement) + + # Store state for plotting + positions[i] = real_state.position + velocities[i] = real_state.velocity + quaternions[i] = real_state.orientation + angular_velocities[i] = real_state.angular_velocity + okid_params[i] = real_state.okid_part() + + # Store estimated state for plotting + positions_est[i] = state.position + velocities_est[i] = state.velocity + quaternions_est[i] = state.orientation + angular_velocities_est[i] = state.angular_velocity + okid_params_est[i] = state.okid_part() + + # Add small delay to simulate real-time execution + time.sleep(0.001) +print(state.as_vector()) +# Plotting +time_points = np.arange(0, sim_time, dt) + +# 3D trajectory plot +fig = plt.figure(figsize=(12, 10)) +ax = fig.add_subplot(111, projection='3d') +ax.plot(positions[:, 0], positions[:, 1], positions[:, 2], 'b-', label='True Trajectory') +ax.plot(positions_est[:, 0], positions_est[:, 1], positions_est[:, 2], 'r--', label='Estimated Trajectory') +ax.scatter(positions[0, 0], positions[0, 1], positions[0, 2], c='g', marker='o', s=100, label='Start') +ax.scatter(positions[-1, 0], positions[-1, 1], positions[-1, 2], c='r', marker='o', s=100, label='End') +ax.set_xlabel('X Position') +ax.set_ylabel('Y Position') +ax.set_zlabel('Z Position') +ax.set_title('3D Trajectory') +ax.legend() + +# Position plot +plt.figure(figsize=(12, 6)) +plt.subplot(311) +plt.plot(time_points, positions[:, 0], 'b-', label='True') +plt.plot(time_points, positions_est[:, 0], 'r--', label='Estimated') +plt.ylabel('X Position') +plt.legend() +plt.subplot(312) +plt.plot(time_points, positions[:, 1], 'b-', label='True') +plt.plot(time_points, positions_est[:, 1], 'r--', label='Estimated') +plt.ylabel('Y Position') +plt.legend() +plt.subplot(313) +plt.plot(time_points, positions[:, 2], 'b-', label='True') +plt.plot(time_points, positions_est[:, 2], 'r--', label='Estimated') +plt.ylabel('Z Position') +plt.xlabel('Time (s)') +plt.legend() +plt.tight_layout() + +# Velocity plot +plt.figure(figsize=(12, 6)) +plt.subplot(311) +plt.plot(time_points, velocities[:, 0], 'b-', label='True') +plt.plot(time_points, velocities_est[:, 0], 'r--', label='Estimated') +plt.ylabel('X Velocity') +plt.legend() +plt.subplot(312) +plt.plot(time_points, velocities[:, 1], 'b-', label='True') +plt.plot(time_points, velocities_est[:, 1], 'r--', label='Estimated') +plt.ylabel('Y Velocity') +plt.legend() +plt.subplot(313) +plt.plot(time_points, velocities[:, 2], 'b-', label='True') +plt.plot(time_points, velocities_est[:, 2], 'r--', label='Estimated') +plt.ylabel('Z Velocity') +plt.xlabel('Time (s)') +plt.legend() +plt.tight_layout() + +# Angular velocity plot +plt.figure(figsize=(12, 6)) +plt.subplot(311) +plt.plot(time_points, angular_velocities[:, 0], 'b-', label='True') +plt.plot(time_points, angular_velocities_est[:, 0], 'r--', label='Estimated') +plt.ylabel('Roll Rate') +plt.legend() +plt.subplot(312) +plt.plot(time_points, angular_velocities[:, 1], 'b-', label='True') +plt.plot(time_points, angular_velocities_est[:, 1], 'r--', label='Estimated') +plt.ylabel('Pitch Rate') +plt.legend() +plt.subplot(313) +plt.plot(time_points, angular_velocities[:, 2], 'b-', label='True') +plt.plot(time_points, angular_velocities_est[:, 2], 'r--', label='Estimated') +plt.ylabel('Yaw Rate') +plt.xlabel('Time (s)') +plt.legend() +plt.tight_layout() + +# OKID Inertia parameters plot (9 parameters) +plt.figure(figsize=(15, 10)) +plt.suptitle('Inertia Parameters', fontsize=16) +for i in range(9): + plt.subplot(3, 3, i+1) + plt.plot(time_points, okid_params[:, i], 'b-', label='True') + plt.plot(time_points, okid_params_est[:, i], 'r--', label='Estimated') + plt.ylabel(f'Inertia[{i}]') + if i >= 6: # Add x-label only to bottom row + plt.xlabel('Time (s)') + plt.legend() +plt.tight_layout(rect=[0, 0, 1, 0.96]) # Adjust for suptitle + +# OKID Added Mass parameters plot (6 parameters) +plt.figure(figsize=(15, 8)) +plt.suptitle('Added Mass Parameters', fontsize=16) +for i in range(6): + plt.subplot(2, 3, i+1) + plt.plot(time_points, okid_params[:, i+9], 'b-', label='True') + plt.plot(time_points, okid_params_est[:, i+9], 'r--', label='Estimated') + plt.ylabel(f'Added Mass[{i}]') + if i >= 3: # Add x-label only to bottom row + plt.xlabel('Time (s)') + plt.legend() +plt.tight_layout(rect=[0, 0, 1, 0.96]) # Adjust for suptitle + +# OKID Damping parameters plot (6 parameters) +plt.figure(figsize=(15, 8)) +plt.suptitle('Damping Parameters', fontsize=16) +for i in range(6): + plt.subplot(2, 3, i+1) + plt.plot(time_points, okid_params[:, i+15], 'b-', label='True') + plt.plot(time_points, okid_params_est[:, i+15], 'r--', label='Estimated') + plt.ylabel(f'Damping[{i}]') + if i >= 3: # Add x-label only to bottom row + plt.xlabel('Time (s)') + plt.legend() +plt.tight_layout(rect=[0, 0, 1, 0.96]) # Adjust for suptitle + +# OKID g_eta parameters plot (4 parameters) +plt.figure(figsize=(12, 8)) +plt.suptitle('g_eta Parameters', fontsize=16) +for i in range(4): + plt.subplot(2, 2, i+1) + plt.plot(time_points, okid_params[:, i+21], 'b-', label='True') + plt.plot(time_points, okid_params_est[:, i+21], 'r--', label='Estimated') + plt.ylabel(f'g_eta[{i}]') + plt.xlabel('Time (s)') + plt.legend() +plt.tight_layout(rect=[0, 0, 1, 0.96]) # Adjust for suptitle + +plt.show() + diff --git a/navigation/tukf/tukf.py b/navigation/tukf/tukf.py new file mode 100644 index 000000000..a4badd887 --- /dev/null +++ b/navigation/tukf/tukf.py @@ -0,0 +1,126 @@ +import numpy as np +from tukf_class import ( + MeasModel, + AUVState, + covariance_measurement, + covariance_set, + cross_covariance, + mean_measurement, + mean_set, + F_dynamics, + generate_delta_matrix, +) + +def print_matrix(matrix, name="Matrix"): + """Custom print function to print matrices in a formatted form.""" + print(f"{name}: {matrix.shape}") + if isinstance(matrix, np.ndarray): + for row in matrix: + print(" ".join(f"{val:.2f}" for val in row)) + else: + print(matrix) + +class TUKF: + def __init__(self, x_0: AUVState, Q): + self.x = x_0 + self.Q = Q + self.delta = generate_delta_matrix(len(x_0.as_vector())) / np.sqrt(len(x_0.as_vector())) + self.sigma_points_list = None + self.measurement_updated = MeasModel() + self.dt = 0.01 # Time step for dynamics + self.flagg = 0 + self.filter_failed = False + + def sigma_points(self, current_state: AUVState) -> list[AUVState]: + """Functions that generate the sigma points for the UKF.""" + n = len(current_state.covariance) + self.flagg += 1 + try: + S = np.linalg.cholesky(current_state.covariance) + except np.linalg.LinAlgError: + print("Cholesky decomposition failed!") + print("flagg", self.flagg) + print_matrix(current_state.covariance, "Current State Covariance") + print_matrix(self.Q, "Process Noise Covariance (Q)") + + # Set flag to indicate filter has failed + self.filter_failed = True + + # Create a valid but minimal S matrix to avoid crashing + # This allows the simulation to continue to the next step where it can be checked + S = np.eye(n) * 1e-6 + + self.sigma_points_list = [AUVState() for _ in range(2 * n)] + + for index, state in enumerate(self.sigma_points_list): + state.fill_states(current_state.as_vector() + S @ self.delta[:, index]) + + return self.sigma_points_list + + def unscented_transform(self, current_state: AUVState, control_force: np.ndarray) -> AUVState: + """The unscented transform function generates the priori state estimate.""" + self.sigma_points(current_state) + n = len(current_state.covariance) + + self.y_i = [AUVState() for _ in range(2 * n)] + + for i, sp in enumerate(self.sigma_points_list): + self.y_i[i] = F_dynamics(sp, self.dt, control_force) + + state_estimate = AUVState() + x = mean_set(self.y_i) + + state_estimate.fill_states(x) + state_estimate.covariance = covariance_set(self.y_i, x) + + self.Q + return state_estimate + + def measurement_update( + self, current_state: AUVState, measurement: MeasModel + ) -> None: + """Function that updates the state estimate with a measurement. + + Hopefully this is the DVL or GNSS + """ + n = len(current_state.covariance) + z_i = [MeasModel() for _ in range(2 * n)] + + for i, state in enumerate(self.y_i): + z_i[i] = measurement.H(state) + + self.measurement_updated.measurement = mean_measurement(z_i) + + self.measurement_updated.covariance = covariance_measurement( + z_i, self.measurement_updated.measurement + ) + + self.cross_correlation = cross_covariance( + self.y_i, + current_state.as_vector(), + z_i, + self.measurement_updated.measurement, + ) + + def posteriori_estimate( + self, + current_state: AUVState, + measurement: MeasModel, + ) -> AUVState: + """Calculates the posteriori estimate using measurement and the prior estimate.""" + nu_k = MeasModel() + nu_k.measurement = ( + measurement.measurement - self.measurement_updated.measurement + ) + nu_k.covariance = self.measurement_updated.covariance + measurement.covariance + + K_k = np.dot(self.cross_correlation, np.linalg.inv(nu_k.covariance)) + + posteriori_estimate = AUVState() + + posteriori_estimate.fill_states( + current_state.as_vector() + np.dot(K_k, nu_k.measurement) + ) + posteriori_estimate.covariance = current_state.covariance - np.dot( + K_k, np.dot(nu_k.covariance, np.transpose(K_k)) + ) + + return posteriori_estimate diff --git a/navigation/tukf/tukf_class.py b/navigation/tukf/tukf_class.py new file mode 100644 index 000000000..e3ec138fb --- /dev/null +++ b/navigation/tukf/tukf_class.py @@ -0,0 +1,437 @@ +import numpy as np +from dataclasses import dataclass, field +from typing import Callable + +@dataclass +class AUVState: + position: np.ndarray = field(default_factory=lambda: np.zeros(3)) + orientation: np.ndarray = field(default_factory=lambda: np.array(3)) + velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) + angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) + inertia: np.ndarray = field(default_factory=lambda: np.zeros((9))) + added_mass: np.ndarray = field(default_factory=lambda: np.zeros((6))) + damping: np.ndarray = field(default_factory=lambda: np.zeros((6))) + g_eta: np.ndarray = field(default_factory=lambda: np.zeros((4))) + covariance: np.ndarray = field(default_factory=lambda: np.zeros((37, 37))) + + def dynamic_part(self) -> np.ndarray: + """Get the dynamic part of the AUV state.""" + return np.concatenate([ + self.position, + self.orientation, + self.velocity, + self.angular_velocity + ]) + def okid_part(self) -> np.ndarray: + """Get the OKID part of the AUV state.""" + return np.concatenate([ + self.inertia, + self.added_mass, + self.damping, + self.g_eta + ]) + def as_vector(self) -> np.ndarray: + """Convert the AUV state to a vector representation.""" + return np.concatenate([ + self.position, + self.orientation, + self.velocity, + self.angular_velocity, + self.inertia.flatten(), + self.added_mass.flatten(), + self.damping.flatten(), + self.g_eta + ]) + + def __add__(self, other: 'AUVState') -> 'AUVState': + """Add two AUV states together.""" + return AUVState( + position=self.position + other.position, + orientation=self.orientation + other.orientation, + velocity=self.velocity + other.velocity, + angular_velocity=self.angular_velocity + other.angular_velocity, + inertia=self.inertia + other.inertia, + added_mass=self.added_mass + other.added_mass, + damping=self.damping + other.damping, + g_eta=self.g_eta + other.g_eta + ) + def __sub__(self, other: 'AUVState') -> 'AUVState': + """Subtract two AUV states.""" + return AUVState( + position=self.position - other.position, + orientation=self.orientation - other.orientation, + velocity=self.velocity - other.velocity, + angular_velocity=self.angular_velocity - other.angular_velocity, + inertia=self.inertia - other.inertia, + added_mass=self.added_mass - other.added_mass, + damping=self.damping - other.damping, + g_eta=self.g_eta - other.g_eta + ) + def fill_states(self, x: np.ndarray) -> None: + """Fill the AUV state with a vector representation.""" + self.position = x[0:3] + self.orientation = x[3:6] + self.velocity = x[6:9] + self.angular_velocity = x[9:12] + self.inertia = x[12:21] + self.added_mass = x[21:27] + self.damping = x[27:33] + self.g_eta = x[33:37] + + +@dataclass +class MeasModel: + """A class defined for a general measurement model.""" + measurement: np.ndarray = field(default_factory=lambda: np.zeros(3)) + covariance: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) + H: Callable[["AUVState"], "MeasModel"] | None = None + + def __post_init__(self): + """Initialize H with a default measurement function if none provided.""" + if self.H is None: + self.H = self._default_H + + def _default_H(self, state: AUVState) -> 'MeasModel': + """Default measurement function that returns velocity.""" + H_matrix = np.zeros((3, 12)) + H_matrix[:, 6:9] = np.eye(3) + z_i = MeasModel() + z_i.measurement = np.dot(H_matrix, state.dynamic_part()) + return z_i + + def __add__(self, other: 'MeasModel') -> 'MeasModel': + """Defines the addition operation between two MeasModel objects.""" + result = MeasModel() + result.measurement = self.measurement + other.measurement + return result + + def __rmul__(self, scalar: float) -> 'MeasModel': + """Defines multiplication between scalar value and MeasModel object.""" + result = MeasModel() + result.measurement = scalar * self.measurement + return result + + def __sub__(self, other: 'MeasModel') -> 'MeasModel': + """Defines the subtraction between two MeasModel objects.""" + result = MeasModel() + result.measurement = self.measurement - other.measurement + return result + +def generate_delta_matrix_2(n: float) -> np.ndarray: + """Generates the weight matrix used in the TUKF sigma point generation. + + Parameters: + n (int): The state dimension. + + Returns: + delta (np.ndarray): An n x 2n orthonormal transformation matrix used to generate TUKF sigma points. + """ + delta = np.zeros((n, 2 * n)) + k = 0.001 # Tuning parameter to ensure pos def + + for i in range(2 * n): + for j in range(n // 2): + delta[2 * j + 1, i] = ( + np.sqrt(2) * np.sin(2 * j - 1) * ((k * np.pi) / n) + ) + delta[2 * j, i] = np.sqrt(2) * np.cos(2 * j - 1) * ((k * np.pi) / n) + + if (n % 2) == 1: + delta[n - 1, i] = np.sqrt(2) * np.cos(2 * j - 1) * ((k * np.pi) / n) + + return delta + +def generate_delta_matrix(n: int) -> np.ndarray: + if n < 1: + raise ValueError("n must be a positive integer") + + delta = np.zeros((n, 2 * n)) + r_max = n // 2 # floor(n/2) + sq2 = np.sqrt(2.0) + + for k in range(1, 2 * n + 1): # k = 1 … 2n + for r in range(1, r_max + 1): + row_cos = 2 * r - 2 # 0‑based index for γ_{k,2r‑1} + row_sin = 2 * r - 1 # 0‑based index for γ_{k,2r} + angle = (2 * r - 1) * k * np.pi / n + delta[row_cos, k - 1] = sq2 * np.cos(angle) + delta[row_sin, k - 1] = sq2 * np.sin(angle) + + if n % 2 == 1: # extra entry when n is odd + delta[n - 1, k - 1] = (-1) ** k + + return delta + +def skew_symmetric(vector: np.ndarray) -> np.ndarray: + """Calculates the skew symmetric matrix of a vector. + + Args: + vector (np.ndarray): The vector. + + Returns: + np.ndarray: The skew symmetric matrix. + """ + return np.array( + [ + [0, -vector[2], vector[1]], + [vector[2], 0, -vector[0]], + [-vector[1], vector[0], 0], + ] + ) + +def mean_set(set_points: list[AUVState]) -> np.ndarray: + """Function calculates the mean vector of a set of points. + + Args: + set_points (list[AUVState]): List of AUVState objects + + Returns: + np.ndarray: The mean vector + """ + n = len(set_points) + mean_value = np.zeros(set_points[0].as_vector().shape) + + for state in set_points: + mean_value = mean_value + state.as_vector() + + mean_value = (1 / n) * mean_value + + return mean_value + + +def mean_measurement(set_points: list[MeasModel]) -> np.ndarray: + """Function that calculates the mean of a set of points.""" + n = len(set_points) + mean_value = MeasModel() + + for state in set_points: + mean_value = mean_value + state + + mean_value = (1 / n) * mean_value + + return mean_value.measurement + + +def covariance_set(set_points: list[AUVState], mean: np.ndarray) -> np.ndarray: + """Function that calculates the covariance of a set of points.""" + n = len(set_points) + covariance = np.zeros(set_points[0].covariance.shape) + + for state in set_points: + W_i = state.as_vector() - mean + + covariance += np.outer(W_i, W_i) + + covariance = (1 / n) * covariance + + return covariance + + +def covariance_measurement(set_points: list[MeasModel], mean: np.ndarray) -> np.ndarray: + """Function that calculates the covariance of a set of points.""" + n = len(set_points) + co_size = len(set_points[0].measurement) + covariance = np.zeros((co_size, co_size)) + + mean_meas = MeasModel() + mean_meas.measurement = mean + + for state in set_points: + temp_state = state - mean_meas + covariance += np.outer(temp_state.measurement, temp_state.measurement) + + covariance = (1 / n) * covariance + + return covariance + + +def cross_covariance( + set_y: list[AUVState], + mean_y: np.ndarray, + set_z: list[MeasModel], + mean_z: np.ndarray, +) -> np.ndarray: + """Calculates the cross covariance between the measurement and state prediction.""" + n = len(set_y) + + cross_covariance = np.zeros((len(mean_y), len(mean_z))) + + for i in range(n): + state_diff = set_y[i].as_vector() - mean_y + meas_diff = set_z[i].measurement - mean_z + + cross_covariance += np.outer(state_diff, meas_diff) + + cross_covariance = (1 / n) * cross_covariance + + return cross_covariance + + +# ----------------------------------------------------------- + +def rotation_matrix(euler_angles: np.ndarray) -> np.ndarray: + """Calculates the rotation matrix from Euler angles (roll, pitch, yaw).""" + roll, pitch, yaw = euler_angles + + # Roll rotation + Rx = np.array([ + [1, 0, 0], + [0, np.cos(roll), -np.sin(roll)], + [0, np.sin(roll), np.cos(roll)] + ]) + + # Pitch rotation + Ry = np.array([ + [np.cos(pitch), 0, np.sin(pitch)], + [0, 1, 0], + [-np.sin(pitch), 0, np.cos(pitch)] + ]) + + # Yaw rotation + Rz = np.array([ + [np.cos(yaw), -np.sin(yaw), 0], + [np.sin(yaw), np.cos(yaw), 0], + [0, 0, 1] + ]) + + # Complete rotation matrix + R = Rz @ Ry @ Rx + return R + +def angular_velocity_transformation(euler_angles: np.ndarray) -> np.ndarray: + """Transformation matrix relating Euler rates to angular velocities.""" + roll, pitch, yaw = euler_angles + + T = np.array([ + [1, 0, -np.sin(pitch)], + [0, np.cos(roll), np.cos(pitch) * np.sin(roll)], + [0, -np.sin(roll), np.cos(pitch) * np.cos(roll)] + ]) + + return T + +def M_rb(inertia: np.ndarray) -> np.ndarray: + m = 30.0 + inertia = inertia.reshape((3, 3)) + r_b_bg = np.array([0.01, 0.0, 0.02]) + M_rb = np.zeros((6, 6)) + M_rb[0:3, 0:3] = m * np.eye(3) + M_rb[3:6, 3:6] = inertia + M_rb[0:3, 3:6] = -m * skew_symmetric(r_b_bg) + M_rb[3:6, 0:3] = m * skew_symmetric(r_b_bg) + return M_rb + +def M_a(added_mass: np.ndarray) -> np.ndarray: + """Calculates the added mass matrix.""" + M_a = np.zeros((6, 6)) + M_a[0:3, 0:3] = np.diag(added_mass[0:3]) + M_a[3:6, 3:6] = np.diag(added_mass[3:6]) + return M_a + +def C_rb(inertia: np.ndarray, angular_velocity: np.ndarray) -> np.ndarray: + """Calculates the Coriolis matrix.""" + m = 30.0 + r_b_bg = np.array([0.01, 0.0, 0.02]) + inertia = inertia.reshape((3, 3)) + C_rb = np.zeros((6, 6)) + + C_rb[0:3, 0:3] = m * skew_symmetric(angular_velocity) + C_rb[3:6, 3:6] = -skew_symmetric(np.dot(inertia, angular_velocity)) + C_rb[0:3, 3:6] = -m * skew_symmetric(angular_velocity) @ skew_symmetric(r_b_bg) + C_rb[3:6, 0:3] = m * skew_symmetric(r_b_bg) @ skew_symmetric(angular_velocity) + return C_rb + +def C_a(added_mass: np.ndarray, angular_velocity: np.ndarray, velocity: np.ndarray) -> np.ndarray: + """Calculates the added mass Coriolis matrix.""" + C_a = np.zeros((6, 6)) + A11 = np.diag(added_mass[0:3]) + A22 = np.diag(added_mass[3:6]) + C_a[3:6,3:6] = - skew_symmetric(A22 @ angular_velocity) + C_a[0:3,3:6] = - skew_symmetric(A11 @ velocity) + C_a[3:6,0:3] = - skew_symmetric(A11 @ velocity) + return C_a + +def D_linear(damping_linear: np.ndarray) -> np.ndarray: + """Calculates the linear damping matrix.""" + D = np.zeros((6, 6)) + D[0:3, 0:3] = -np.diag(damping_linear[0:3]) + D[3:6, 3:6] = -np.diag(damping_linear[3:6]) + return D + +def g_eta(g_eta: np.ndarray, orientation: np.ndarray) -> np.ndarray: + """Calculates the g_eta matrix using Euler angles.""" + Delta_WB = g_eta[0] + M_x = g_eta[1] + M_y = g_eta[2] + M_z = g_eta[3] + + # Get rotation matrix using Euler angles + R = rotation_matrix(orientation) + + G_eta = np.zeros((6,1)) + # Gravitational forces + G_eta[0:3] = -Delta_WB * R[:, 2].reshape(3, 1) + + # Buoyancy moments + G_eta[3] = -M_y * R[2, 2] + M_z * R[1, 2] + G_eta[4] = -M_z * R[0, 2] + M_x * R[2, 2] + G_eta[5] = -M_x * R[1, 2] + M_y * R[0, 2] + + return G_eta + +def F_dynamics( + state: AUVState, + dt: float, + control_input: np.ndarray) -> AUVState: + + """Calculates the dynamics of the system.""" + m_rb = M_rb(state.inertia) + m_a = M_a(state.added_mass) + c_rb = C_rb(state.inertia, state.angular_velocity) + c_a = C_a(state.added_mass, state.angular_velocity, state.velocity) + D_l = D_linear(state.damping) + g_eta_ = g_eta(state.g_eta, state.orientation) + + # Get rotation and transformation matrices + r = rotation_matrix(state.orientation) + t = angular_velocity_transformation(state.orientation) + + Crb = c_rb + c_a + Mrb = m_rb + m_a + M_inv = np.linalg.inv(Mrb) + + # Create a vector of velocity and angular velocity + nu = np.concatenate([state.velocity, state.angular_velocity]) + + # Calculate the new state + state_dot = AUVState() + state_dot.position = np.dot(r, state.velocity) + + # Calculate Euler angle rates from angular velocities + t_inv = np.linalg.inv(t) + euler_rates = np.dot(t_inv, state.angular_velocity) + state_dot.orientation = euler_rates + + Nu = M_inv @ (control_input - np.dot(Crb, nu) - np.dot(D_l, nu) - g_eta_.flatten()) + + state_dot.velocity = Nu[:3] + state_dot.angular_velocity = Nu[3:6] + + # Update the inertia, added mass, damping, and g_eta + state_dot.inertia = np.zeros_like(state.inertia) + state_dot.added_mass = np.zeros_like(state.added_mass) + state_dot.damping = np.zeros_like(state.damping) + state_dot.g_eta = np.zeros_like(state.g_eta) + + new_state = AUVState() + new_state.position = state.position + state_dot.position * dt + new_state.orientation = state.orientation + state_dot.orientation * dt + new_state.velocity = state.velocity + state_dot.velocity * dt + new_state.angular_velocity = state.angular_velocity + state_dot.angular_velocity * dt + new_state.inertia = state.inertia + state_dot.inertia * dt + new_state.added_mass = state.added_mass + state_dot.added_mass * dt + new_state.damping = state.damping + state_dot.damping * dt + new_state.g_eta = state.g_eta + state_dot.g_eta * dt + + return new_state +# ----------------------------------------------------------- diff --git a/navigation/ukf_okid/ukf_python/ukf_okid.py b/navigation/ukf_okid/ukf_python/ukf_okid.py index e50c65c3a..240ca42bb 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid.py @@ -7,23 +7,22 @@ cross_covariance, mean_measurement, mean_set, - okid_process_model, + F_dynamics, ) class UKF: - def __init__(self, process_model: okid_process_model, x_0, P_0, Q, G): + def __init__(self, x_0: StateQuat, Q): self.x = x_0 - self.P = P_0 self.Q = Q - self.G = G - self.process_model = process_model + # self.G = G self.sigma_points_list = None self.measurement_updated = MeasModel() self.y_i = None self.weight = None self.delta = self.generate_delta_matrix(len(x_0.as_vector()) - 1) self.cross_correlation = None + self.dt = 0.01 # Time step for dynamics def generate_delta_matrix(self, n: float) -> np.ndarray: """Generates the weight matrix used in the TUKF sigma point generation. @@ -35,12 +34,14 @@ def generate_delta_matrix(self, n: float) -> np.ndarray: delta (np.ndarray): An n x 2n orthonormal transformation matrix used to generate TUKF sigma points. """ delta = np.zeros((n, 2 * n)) - k = 0.01 # Tuning parameter to ensure pos def + k = 0.00000001 # Tuning parameter to ensure pos def for i in range(2 * n): for j in range(n // 2): - delta[2 * j + 1, i] = np.sqrt(2) * np.sin(2 * j - 1) * ((k * np.pi) / n) - delta[2 * j, i] = np.sqrt(2) * np.cos(2 * j - 1) * ((k * np.pi) / n) + delta[2 * j + 1, i] = ( + np.sqrt(2) * np.sin((2 * j - 1) * ((k * np.pi) / n)) + ) + delta[2 * j, i] = np.sqrt(2) * np.cos((2 * j - 1) * ((k * np.pi) / n)) if (n % 2) == 1: delta[n - 1, i] = (-1) ** i @@ -60,17 +61,15 @@ def sigma_points(self, current_state: StateQuat) -> list[StateQuat]: return self.sigma_points_list - def unscented_transform(self, current_state: StateQuat) -> StateQuat: + def unscented_transform(self, current_state: StateQuat, control_force: np.ndarray) -> StateQuat: """The unscented transform function generates the priori state estimate.""" self.sigma_points(current_state) n = len(current_state.covariance) self.y_i = [StateQuat() for _ in range(2 * n)] - for i, state in enumerate(self.sigma_points_list): - self.process_model.model_prediction(state) - self.process_model.state_vector_prev = state - self.y_i[i] = self.process_model.euler_forward() + for i, sp in enumerate(self.sigma_points_list): + self.y_i[i] = F_dynamics(sp, self.dt, control_force) state_estimate = StateQuat() x = mean_set(self.y_i) diff --git a/navigation/ukf_okid/ukf_python/ukf_okid_class.py b/navigation/ukf_okid/ukf_python/ukf_okid_class.py index 0b329cb84..f494e3280 100644 --- a/navigation/ukf_okid/ukf_python/ukf_okid_class.py +++ b/navigation/ukf_okid/ukf_python/ukf_okid_class.py @@ -1,5 +1,5 @@ from dataclasses import dataclass, field - +from typing import Callable import numpy as np @@ -13,21 +13,25 @@ class okid: ) ) added_mass: np.ndarray = field( - default_factory=lambda: np.array([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) + default_factory=lambda: np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0]) ) damping_linear: np.ndarray = field( - default_factory=lambda: np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0]) + default_factory=lambda: np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0]) + ) + g_eta: np.ndarray = field( + default_factory=lambda: np.array([0.0, 0.0, 0.0, 0.0]) ) def fill(self, state: np.ndarray) -> None: """Fills the okid_params object with values from a numpy array.""" self.inertia = state[0:9] self.added_mass = state[9:15] - self.damping_linear = state[15:] + self.damping_linear = state[15:21] + self.g_eta = state[21:25] def as_vector(self) -> np.ndarray: """Returns the okid_params as a numpy array.""" - return np.concatenate([self.inertia, self.added_mass, self.damping_linear]) + return np.concatenate([self.inertia, self.added_mass, self.damping_linear, self.g_eta]) def __add__(self, other: 'okid') -> 'okid': """Defines the addition operation between two okid_params objects.""" @@ -35,6 +39,7 @@ def __add__(self, other: 'okid') -> 'okid': result.inertia = self.inertia + other.inertia result.added_mass = self.added_mass + other.added_mass result.damping_linear = self.damping_linear + other.damping_linear + result.g_eta = self.g_eta + other.g_eta return result def __sub__(self, other: 'okid') -> 'okid': @@ -43,6 +48,7 @@ def __sub__(self, other: 'okid') -> 'okid': result.inertia = self.inertia - other.inertia result.added_mass = self.added_mass - other.added_mass result.damping_linear = self.damping_linear - other.damping_linear + result.g_eta = self.g_eta - other.g_eta return result def __sub__(self, other: np.ndarray) -> 'okid': @@ -50,7 +56,8 @@ def __sub__(self, other: np.ndarray) -> 'okid': result = okid() result.inertia = self.inertia - other[0:9] result.added_mass = self.added_mass - other[9:15] - result.damping_linear = self.damping_linear - other[15:] + result.damping_linear = self.damping_linear - other[15:21] + result.g_eta = self.g_eta - other[21:25] return result def __rmul__(self, scalar: float) -> 'okid': @@ -59,6 +66,7 @@ def __rmul__(self, scalar: float) -> 'okid': result.inertia = scalar * self.inertia result.added_mass = scalar * self.added_mass result.damping_linear = scalar * self.damping_linear + result.g_eta = scalar * self.g_eta return result @@ -71,7 +79,7 @@ class StateQuat: velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) okid_params: okid = field(default_factory=okid) - covariance: np.ndarray = field(default_factory=lambda: np.zeros((33, 33))) + covariance: np.ndarray = field(default_factory=lambda: np.zeros((37, 37))) def as_vector(self) -> np.ndarray: """Returns the StateVector as a numpy array.""" @@ -135,6 +143,7 @@ def fill_dynamic_states(self, state: np.ndarray, state_euler: np.ndarray) -> Non ) self.velocity = state[7:10] + state_euler[6:9] self.angular_velocity = state[10:13] + state_euler[9:12] + self.okid_params.fill(state[13:] + state_euler[12:]) def fill_states_different_dim( self, state: np.ndarray, state_euler: np.ndarray @@ -218,16 +227,21 @@ def add_without_quaternions(self, other: 'StateQuat') -> None: @dataclass class MeasModel: """A class defined for a general measurement model.""" - measurement: np.ndarray = field(default_factory=lambda: np.zeros(3)) covariance: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) - - def H(self, state: StateQuat) -> 'MeasModel': - """Calculates the measurement matrix.""" - H = np.zeros((3, 13)) - H[:, 7:10] = np.eye(3) + H: Callable[["StateQuat"], "MeasModel"] | None = None + + def __post_init__(self): + """Initialize H with a default measurement function if none provided.""" + if self.H is None: + self.H = self._default_H + + def _default_H(self, state: StateQuat) -> 'MeasModel': + """Default measurement function that returns velocity.""" + H_matrix = np.zeros((3, 13)) + H_matrix[:, 7:10] = np.eye(3) z_i = MeasModel() - z_i.measurement = np.dot(H, state.dynamic_part()) + z_i.measurement = np.dot(H_matrix, state.dynamic_part()) return z_i def __add__(self, other: 'MeasModel') -> 'MeasModel': @@ -459,6 +473,149 @@ def euler_forward(self) -> None: return self.state_vector +# ----------------------------------------------------------- + +def R_q(orientation: np.ndarray) -> np.ndarray: + """Calculates the rotation matrix from the orientation quaternion.""" + q0, q1, q2, q3 = orientation + R = np.array( + [ + [1 - 2 * q2**2 - 2 * q3**2, 2 * (q1 * q2 - q0 * q3), 2 * (q0 * q2 + q1 * q3)], + [2 * (q1 * q2 + q0 * q3), 1 - 2 * q1**2 - 2 * q3**2, 2 * (q2 * q3 - q0 * q1)], + [2 * (q1 * q3 - q0 * q2), 2 * (q0 * q1 + q2 * q3), 1 - 2 * q1**2 - 2 * q2**2], + ] + ) + return R + +def T_q(orientation: np.ndarray) -> np.ndarray: + """Calculates the transformation matrix from the orientation quaternion.""" + q0, q1, q2, q3 = orientation + T = 0.5 * np.array( + [[-q1, -q2, -q3], [q0, -q3, q2], [q3, q0, -q1], [-q2, q1, q0]] + ) + return T + +def M_rb(inertia: np.ndarray) -> np.ndarray: + m = 30.0 + inertia = inertia.reshape((3, 3)) + r_b_bg = np.array([0.01, 0.0, 0.02]) + M_rb = np.zeros((6, 6)) + M_rb[0:3, 0:3] = m * np.eye(3) + M_rb[3:6, 3:6] = inertia + M_rb[0:3, 3:6] = -m * skew_symmetric(r_b_bg) + M_rb[3:6, 0:3] = m * skew_symmetric(r_b_bg) + return M_rb + +def M_a(added_mass: np.ndarray) -> np.ndarray: + """Calculates the added mass matrix.""" + M_a = np.zeros((6, 6)) + M_a[0:3, 0:3] = np.diag(added_mass[0:3]) + M_a[3:6, 3:6] = np.diag(added_mass[3:6]) + return M_a + +def C_rb(inertia: np.ndarray, angular_velocity: np.ndarray) -> np.ndarray: + """Calculates the Coriolis matrix.""" + m = 30.0 + r_b_bg = np.array([0.01, 0.0, 0.02]) + inertia = inertia.reshape((3, 3)) + C_rb = np.zeros((6, 6)) + + C_rb[0:3, 0:3] = m * skew_symmetric(angular_velocity) + C_rb[3:6, 3:6] = -skew_symmetric(np.dot(inertia, angular_velocity)) + C_rb[0:3, 3:6] = -m * skew_symmetric(angular_velocity) @ skew_symmetric(r_b_bg) + C_rb[3:6, 0:3] = m * skew_symmetric(r_b_bg) @ skew_symmetric(angular_velocity) + return C_rb + +def C_a(added_mass: np.ndarray, angular_velocity: np.ndarray, velocity: np.ndarray) -> np.ndarray: + """Calculates the added mass Coriolis matrix.""" + C_a = np.zeros((6, 6)) + A11 = np.diag(added_mass[0:3]) + A22 = np.diag(added_mass[3:6]) + C_a[3:6,3:6] = - skew_symmetric(A22 @ angular_velocity) + C_a[0:3,3:6] = - skew_symmetric(A11 @ velocity) + C_a[3:6,0:3] = - skew_symmetric(A11 @ velocity) + return C_a + +def D_linear(damping_linear: np.ndarray) -> np.ndarray: + """Calculates the linear damping matrix.""" + D = np.zeros((6, 6)) + D[0:3, 0:3] = -np.diag(damping_linear[0:3]) + D[3:6, 3:6] = -np.diag(damping_linear[3:6]) + return D + +def g_eta(g_eta: np.ndarray, orientation: np.ndarray) -> np.ndarray: + """Calculates the g_eta matrix.""" + Delta_WB = g_eta[0] + M_x = g_eta[1] + M_y = g_eta[2] + M_z = g_eta[3] + + q_0 = orientation[0] + q_1 = orientation[1] + q_2 = orientation[2] + q_3 = orientation[3] + + R1 = (2*(q_1*q_3 - q_0*q_2)) + R2 = (2*(q_2*q_3 + q_0*q_1)) + R3 = (1 - 2*(q_1**2 + q_2**2)) + G_eta = np.zeros((6,1)) + G_eta[0] = - Delta_WB * R1 + G_eta[1] = - Delta_WB * R2 + G_eta[2] = - Delta_WB * R3 + + G_eta[3] = -M_y * R3 + M_z * R2 + G_eta[4] = -M_z * R1 + M_x * R3 + G_eta[5] = -M_x * R2 + M_y * R1 + + return G_eta + +def F_dynamics( + state: StateQuat, + dt: float, + control_input: np.ndarray) -> np.ndarray: + + """Calculates the dynamics of the system.""" + m_rb = M_rb(state.okid_params.inertia) + m_a = M_a(state.okid_params.added_mass) + c_rb = C_rb(state.okid_params.inertia, state.angular_velocity) + c_a = C_a(state.okid_params.added_mass, state.angular_velocity, state.velocity) + D_l = D_linear(state.okid_params.damping_linear) + g_eta_ = g_eta(state.okid_params.g_eta, state.orientation) + r_q = R_q(state.orientation) + t_q = T_q(state.orientation) + Crb = c_rb + c_a + Mrb = m_rb + m_a + M_inv = np.linalg.inv(Mrb) + + + # Calculate the new state + state_dot = StateQuat() + state_dot.position = np.dot(r_q, state.velocity) + state_dot.orientation = np.dot(t_q, state.angular_velocity) + Nu = M_inv @ (control_input - np.dot(Crb, state.nu()) - np.dot(D_l, state.nu()) - g_eta_.flatten()) + + state_dot.velocity = Nu[:3] + state_dot.angular_velocity = Nu[3:6] + state_dot.okid_params.added_mass = state.okid_params.added_mass + state_dot.okid_params.damping_linear = state.okid_params.damping_linear + state_dot.okid_params.inertia = state.okid_params.inertia + state_dot.okid_params.g_eta = state.okid_params.g_eta + + # Update the state using Euler integration + state.position += state_dot.position * dt + state.orientation = quat_norm( + state.orientation + state_dot.orientation * dt + ) + state.velocity += state_dot.velocity * dt + state.angular_velocity += state_dot.angular_velocity * dt + state.okid_params.added_mass = state.okid_params.added_mass + state.okid_params.damping_linear = state.okid_params.damping_linear + state.okid_params.inertia = state.okid_params.inertia + state.okid_params.g_eta = state.okid_params.g_eta + return state +# ----------------------------------------------------------- + + def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: """Converts Euler angles to a quaternion.""" psi, theta, phi = euler_angles @@ -624,7 +781,6 @@ def mean_set(set_points: list[StateQuat]) -> np.ndarray: mean_value.okid_params = (1 / n) * mean_value.okid_params mean_value.orientation = iterative_quaternion_mean_statequat(set_points) - return mean_value.as_vector() diff --git a/navigation/ukf_okid/ukf_python/ukf_test.py b/navigation/ukf_okid/ukf_python/ukf_test.py index d80427364..e664bd848 100644 --- a/navigation/ukf_okid/ukf_python/ukf_test.py +++ b/navigation/ukf_okid/ukf_python/ukf_test.py @@ -1,458 +1,27 @@ -import matplotlib.pyplot as plt import numpy as np +def generate_delta_matrix(n: int) -> np.ndarray: + if n < 1: + raise ValueError("n must be a positive integer") -# Import your classes and functions. -# Adjust the import paths as necessary based on your module organization. -from ukf_okid_class import ( - MeasModel, - StateQuat, - covariance_measurement, - covariance_set, - cross_covariance, - mean_measurement, - mean_set, - quat_norm, - quat_to_euler, - quaternion_super_product, -) + delta = np.zeros((n, 2 * n)) + r_max = n // 2 # floor(n/2) + sq2 = np.sqrt(2.0) + for k in range(1, 2 * n + 1): # k = 1 … 2n + for r in range(1, r_max + 1): + row_cos = 2 * r - 2 # 0‑based index for γ_{k,2r‑1} + row_sin = 2 * r - 1 # 0‑based index for γ_{k,2r} + angle = (2 * r - 1) * k * np.pi / n + delta[row_cos, k - 1] = sq2 * np.cos(angle) + delta[row_sin, k - 1] = sq2 * np.sin(angle) -# For testing, define a function to create a StateQuat with small perturbations. -def create_statequat( - base_vector, - position_perturbation, - orientation_perturbation, - velocity_perturbation, - angular_velocity_perturbation, -): - """Creates a StateQuat object. - - base_vector: 1D numpy array for base state (13 elements: - position (3), quaternion (4), velocity (3), angular_velocity (3)) - - ..._perturbation: small perturbation vector to be added to each respective component. - Returns a StateQuat. - """ - state = StateQuat() - # Base state - state.position = base_vector[0:3] + position_perturbation - # For orientation, perturb by adding a small rotation: - base_quat = base_vector[3:7] - noise_angle = np.linalg.norm(orientation_perturbation) - if noise_angle < 1e-8: - noise_quat = np.array([1.0, 0.0, 0.0, 0.0]) - else: - noise_axis = orientation_perturbation / noise_angle - noise_quat = np.concatenate( - ([np.cos(noise_angle / 2)], np.sin(noise_angle / 2) * noise_axis) - ) - state.orientation = quat_norm(quaternion_super_product(base_quat, noise_quat)) - state.velocity = base_vector[7:10] + velocity_perturbation - state.angular_velocity = base_vector[10:13] + angular_velocity_perturbation + if n % 2 == 1: # extra entry when n is odd + delta[n - 1, k - 1] = (-1) ** k - # For the augmented parameters (OKID parameters), set a 21-element vector: - # 9 for inertia, 6 for added_mass, and 6 for damping_linear. - state.okid_params.fill(np.concatenate((np.zeros(9), np.zeros(6), np.zeros(6)))) + return delta - # Set a default covariance (33x33 for the extended state) - state.covariance = np.eye(33) * 0.01 - return state +a1 = np.array([1, 0, 1]) +a2 = np.array([1, 1, 0]) - -# Test functions for state statistics -def test_state_statistics(): - # Define a base state vector (13 elements: position, quaternion, velocity, angular_velocity) - base_vector = np.zeros(13) - base_vector[0:3] = np.array([1.0, 2.0, 3.0]) - base_vector[3:7] = np.array([1.0, 0.0, 0.0, 0.0]) # identity quaternion - base_vector[7:10] = np.array([0.1, 0.2, 0.3]) - base_vector[10:13] = np.array([0.01, 0.02, 0.03]) - - # Create a list of StateQuat objects with small random perturbations. - np.random.seed(42) - state_list = [] - num_states = 10 - for _ in range(num_states): - pos_noise = np.random.normal(0, 0.05, 3) - ori_noise = np.random.normal(0, 0.01, 3) - vel_noise = np.random.normal(0, 0.02, 3) - ang_vel_noise = np.random.normal(0, 0.005, 3) - state_list.append( - create_statequat( - base_vector, pos_noise, ori_noise, vel_noise, ang_vel_noise - ) - ) - - # Compute the state mean using mean_set. - mean_state_vec = mean_set(state_list) - print("Computed mean state vector:") - print(mean_state_vec) - - # Compute the covariance of the states. - cov_state = covariance_set(state_list, mean_state_vec) - print("Computed state covariance matrix:") - print(cov_state) - - # Check symmetry of the covariance: - asym_error = np.linalg.norm(cov_state - cov_state.T) - print("Covariance symmetry error (should be near 0):", asym_error) - - # Check eigenvalues for positive semidefiniteness: - eigvals = np.linalg.eigvals(cov_state) - print("Eigenvalues of state covariance:") - print(eigvals) - - -def test_measurement_statistics(): - # Create a list of measurement objects (MeasModel) with measurements in R^3. - np.random.seed(24) - meas_list = [] - num_meas = 10 - base_meas = np.array([1.0, 2.0, 3.0]) - for _ in range(num_meas): - noise = np.random.normal(0, 0.1, 3) - meas = MeasModel() - meas.measurement = base_meas + noise - meas_list.append(meas) - - # Compute the measurement mean. - mean_meas = mean_measurement(meas_list) - print("Computed measurement mean:") - print(mean_meas) - - # Compute the measurement covariance. - cov_meas = covariance_measurement(meas_list, mean_meas) - print("Computed measurement covariance:") - print(cov_meas) - - # Check symmetry and eigenvalues. - asym_error = np.linalg.norm(cov_meas - cov_meas.T) - print("Measurement covariance symmetry error:", asym_error) - eigvals = np.linalg.eigvals(cov_meas) - print("Eigenvalues of measurement covariance:") - print(eigvals) - - -def test_cross_covariance(): - # Create a set of StateQuat and corresponding MeasModel objects. - np.random.seed(99) - num = 10 - state_list = [] - meas_list = [] - base_vector = np.zeros(13) - base_vector[0:3] = np.array([0.5, 1.0, -0.5]) - base_vector[3:7] = np.array([1.0, 0.0, 0.0, 0.0]) - base_vector[7:10] = np.array([0.05, 0.1, 0.15]) - base_vector[10:13] = np.array([0.005, 0.01, 0.015]) - - for _ in range(num): - pos_noise = np.random.normal(0, 0.02, 3) - ori_noise = np.random.normal(0, 0.005, 3) - vel_noise = np.random.normal(0, 0.01, 3) - ang_vel_noise = np.random.normal(0, 0.002, 3) - state = create_statequat( - base_vector, pos_noise, ori_noise, vel_noise, ang_vel_noise - ) - state_list.append(state) - - # Generate a measurement from each state (e.g., state velocity plus noise). - meas = MeasModel() - meas.measurement = state.velocity + np.random.normal(0, 0.01, 3) - meas_list.append(meas) - - # Compute the state mean and measurement mean as vectors. - mean_state_vec = mean_set(state_list) - mean_meas = mean_measurement(meas_list) - - cross_cov = cross_covariance(state_list, mean_state_vec, meas_list, mean_meas) - print("Computed cross-covariance between state and measurement:") - print(cross_cov) - - -import time - -from ukf_okid import UKF - -# Import your classes and functions. -from ukf_okid_class import ( - okid_process_model, - process_model, -) # Your process model classes - - -############################################ -# Helper function to create a StateQuat with perturbations. -############################################ -def create_statequat(base_vector, pos_noise, ori_noise, vel_noise, ang_vel_noise): - """Create a StateQuat object from a base vector (13 elements: - position (3), quaternion (4), velocity (3), angular_velocity (3)) - plus additive noise on each component. - - For the OKID parameters, we assume a 21-element vector: - - first 9: inertia, - - next 6: added_mass, - - last 6: damping_linear. - """ - state = StateQuat() - state.position = base_vector[0:3] + pos_noise - base_quat = base_vector[3:7] - noise_angle = np.linalg.norm(ori_noise) - if noise_angle < 1e-8: - noise_quat = np.array([1.0, 0.0, 0.0, 0.0]) - else: - noise_axis = ori_noise / noise_angle - noise_quat = np.concatenate( - ([np.cos(noise_angle / 2)], np.sin(noise_angle / 2) * noise_axis) - ) - state.orientation = quat_norm(quaternion_super_product(base_quat, noise_quat)) - state.velocity = base_vector[7:10] + vel_noise - state.angular_velocity = base_vector[10:13] + ang_vel_noise - - # Set OKID parameters to exactly 21 elements (9,6,6) - state.okid_params.fill( - np.concatenate( - ( - np.array([0.0, 0.0, 0.3, 0.0, 0.0, 3.3, 0.0, 0.0, 3.3]), - np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0]), - np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0]), - ) - ) - ) - # Set an initial covariance (33x33) for the full augmented state. - state.covariance = np.eye(33) * 0.02 - return state - - -############################################ -# Full Filter Simulation Test -############################################ -def run_ukf_simulation(): - dt = 0.01 # Time step for simulation [s] - simulation_time = 10 # Total simulation time in seconds - num_steps = int(simulation_time / dt) - - # Define a base state vector (13 elements: pos, quat, vel, ang_vel) - base_vector = np.zeros(13) - base_vector[0:3] = np.array([0.0, 0.0, 0.0]) - base_vector[3:7] = np.array([1.0, 0.0, 0.0, 0.0]) # identity quaternion - base_vector[7:10] = np.array([0.1, 0.0, 0.0]) # small velocity in x - base_vector[10:13] = np.array([0.0, 0.0, 0.0]) - - # Define initial covariance for state (33x33) - P0 = np.eye(33) - P0[0:3, 0:3] = np.eye(3) * 0.01 # position - P0[3:6, 3:6] = np.eye(3) * 0.01 # orientation error (quaternion) - P0[6:9, 6:9] = np.eye(3) * 0.01 # velocity - P0[9:12, 9:12] = np.eye(3) * 0.01 # angular velocity - P0[12:33, 12:33] = np.eye(21) * 0.001 # OKID parameters - - # Define process noise covariance Q (33x33) - Q = np.zeros((33, 33)) - Q[0:3, 0:3] = np.eye(3) * 0.001 # for position - Q[3:6, 3:6] = ( - np.eye(3) * 0.001 - ) # for orientation error (represented with Euler angles) - Q[6:9, 6:9] = np.eye(3) * 0.001 # for velocity - Q[9:12, 9:12] = np.eye(3) * 0.001 # for angular velocity - Q[12:33, 12:33] = np.eye(21) * 0.001 # OKID parameters - - G = np.zeros((33, 12)) - G[0:3, 0:3] = np.eye(3) - G[3:6, 3:6] = np.eye(3) - G[6:9, 6:9] = np.eye(3) - G[9:12, 9:12] = np.eye(3) - - # Measurement noise covariance R (3x3), assume measurement is velocity - R = np.eye(3) * 0.01 - - # Create a simulation process model and an independent UKF process model. - sim_model = process_model() - sim_model.dt = dt - sim_model.mass_interia_matrix = np.array( - [ - [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], - ] - ) - sim_model.m = 30.0 - sim_model.r_b_bg = np.array([0.01, 0.0, 0.02]) - sim_model.inertia = np.diag([0.68, 3.32, 3.34]) - sim_model.damping_linear = np.array([0.1] * 6) - sim_model.added_mass = np.array([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) - - # UKF process model copy: - ukf_model = okid_process_model() - ukf_model.dt = dt - ukf_model.mass_interia_matrix = sim_model.mass_interia_matrix.copy() - ukf_model.m = sim_model.m - ukf_model.r_b_bg = sim_model.r_b_bg.copy() - ukf_model.inertia = sim_model.inertia.copy() - ukf_model.damping_linear = sim_model.damping_linear.copy() - ukf_model.added_mass = sim_model.added_mass.copy() - - # Initialize true state and filter state. - true_state = create_statequat( - base_vector, np.zeros(3), np.zeros(3), np.zeros(3), np.zeros(3) - ) - true_state.covariance = P0.copy() - - filter_state = create_statequat( - base_vector, np.zeros(3), np.zeros(3), np.zeros(3), np.zeros(3) - ) - filter_state.covariance = P0.copy() - - # Initialize measurement model (for example, measuring velocity only) - meas_model = MeasModel() - meas_model.covariance = R.copy() - - # Initialize UKF. - ukf = UKF(ukf_model, true_state, P0.copy(), Q.copy(), G.copy()) - - # Arrays to store time histories. - pos_true_hist = np.zeros((num_steps, 3)) - pos_est_hist = np.zeros((num_steps, 3)) - vel_true_hist = np.zeros((num_steps, 3)) - vel_est_hist = np.zeros((num_steps, 3)) - euler_true_hist = np.zeros((num_steps, 3)) - euler_est_hist = np.zeros((num_steps, 3)) - time_array = np.linspace(0, simulation_time, num_steps) - - # Control input function (example: oscillatory in all directions) - def control_input(t): - return np.array( - [ - 2 * np.sin(t), - 2 * np.sin(t + 0.5), - 2 * np.sin(t + 1.0), - 0.2 * np.cos(t), - 0.2 * np.cos(t + 0.5), - 0.2 * np.cos(t + 1.0), - ] - ) - - # Set previous states. - sim_model.state_vector_prev = true_state - sim_model.state_vector = true_state - ukf_model.state_vector_prev = filter_state - ukf_model.state_vector = filter_state - - # Lists for timing diagnostics. - ukf_transform_times = [] - ukf_update_times = [] - - # Simulation loop. - for i in range(num_steps): - t_current = i * dt - - # Update control inputs. - sim_model.Control_input = control_input(t_current) - ukf_model.Control_input = control_input(t_current) - - # Propagate true state using the simulation model. - sim_model.model_prediction(true_state) - true_state = sim_model.euler_forward() - - # Create a measurement from true state. - # Here we assume we measure velocity plus noise. - meas_noise = np.random.normal(0, 0.01, 3) - meas_model.measurement = true_state.velocity + meas_noise - - # UKF prediction: unscented transform. - start = time.time() - filter_state = ukf.unscented_transform(filter_state) - ukf_transform_times.append(time.time() - start) - - # UKF measurement update every few steps. - if i % 5 == 0: - try: - start = time.time() - ukf.measurement_update(filter_state, meas_model) - filter_state = ukf.posteriori_estimate(filter_state, meas_model) - ukf_update_times.append(time.time() - start) - except np.linalg.LinAlgError: - # If matrix is not PD, add jitter. - filter_state.covariance += ( - np.eye(filter_state.covariance.shape[0]) * 1e-6 - ) - - # Store true and estimated state for diagnostics. - pos_true_hist[i, :] = true_state.position - pos_est_hist[i, :] = filter_state.position - vel_true_hist[i, :] = true_state.velocity - vel_est_hist[i, :] = filter_state.velocity - # Convert quaternion to Euler angles for visualization. - # Assumes you have a function quat_to_euler. - euler_true_hist[i, :] = quat_to_euler(true_state.orientation) - euler_est_hist[i, :] = quat_to_euler(filter_state.orientation) - - # Update previous states. - sim_model.state_vector_prev = true_state - ukf_model.state_vector_prev = filter_state - - # Print timing diagnostics. - print("Average unscented transform time:", np.mean(ukf_transform_times)) - print("Average measurement update time:", np.mean(ukf_update_times)) - - # Compute error metrics. - pos_error = np.linalg.norm(pos_true_hist - pos_est_hist, axis=1) - vel_error = np.linalg.norm(vel_true_hist - vel_est_hist, axis=1) - euler_error = np.linalg.norm(euler_true_hist - euler_est_hist, axis=1) - print("Average position error:", np.mean(pos_error)) - print("Average velocity error:", np.mean(vel_error)) - print("Average orientation (Euler) error:", np.mean(euler_error)) - - # Plot estimated vs true trajectory (positions). - plt.figure(figsize=(10, 8)) - plt.subplot(3, 1, 1) - plt.plot(time_array, pos_true_hist[:, 0], label="True X") - plt.plot(time_array, pos_est_hist[:, 0], label="Est X", linestyle="--") - plt.legend() - plt.title("Position X") - - plt.subplot(3, 1, 2) - plt.plot(time_array, pos_true_hist[:, 1], label="True Y") - plt.plot(time_array, pos_est_hist[:, 1], label="Est Y", linestyle="--") - plt.legend() - plt.title("Position Y") - - plt.subplot(3, 1, 3) - plt.plot(time_array, pos_true_hist[:, 2], label="True Z") - plt.plot(time_array, pos_est_hist[:, 2], label="Est Z", linestyle="--") - plt.legend() - plt.title("Position Z") - plt.tight_layout() - plt.show() - - # Plot errors. - plt.figure(figsize=(10, 4)) - plt.plot(time_array, pos_error, label="Position Error") - plt.plot(time_array, vel_error, label="Velocity Error") - plt.plot(time_array, euler_error, label="Euler Angle Error") - plt.legend() - plt.title("Error Metrics over Time") - plt.xlabel("Time (s)") - plt.ylabel("Error magnitude") - plt.show() - - -# You can also test the individual statistics functions separately: -def run_diagnostics(): - print("Testing state mean and covariance computation:") - # Call your pre-written tests: - # (Assuming these functions—test_state_statistics, test_measurement_statistics, test_cross_covariance—are defined above) - test_state_statistics() - print("\nTesting measurement mean and covariance computation:") - test_measurement_statistics() - print("\nTesting cross-covariance computation:") - test_cross_covariance() - - -if __name__ == '__main__': - # First, run the diagnostics on the mean/covariance functions. - run_diagnostics() - - # Then run the full UKF simulation test. - print("\nRunning full UKF simulation test:") - run_ukf_simulation() +a3 = np.outer(a1, a2) +print(a3) \ No newline at end of file diff --git a/navigation/ukf_okid/ukf_python/ukf_test_2.py b/navigation/ukf_okid/ukf_python/ukf_test_2.py index d3a75313b..0a2d5b2fe 100644 --- a/navigation/ukf_okid/ukf_python/ukf_test_2.py +++ b/navigation/ukf_okid/ukf_python/ukf_test_2.py @@ -1,42 +1,229 @@ import numpy as np +import ukf_okid_class as ukf +from ukf_okid import UKF +from mpl_toolkits.mplot3d import Axes3D +import time +import math +from ukf_utils import print_StateQuat, print_matrix -# Define process noise covariance Q (33x33) -Q = np.zeros((12, 12)) -Q[0:3, 0:3] = np.eye(3) * 0.003 # for position -Q[3:6, 3:6] = np.eye(3) * 0.003 # for orientation error (represented with Euler angles) -Q[6:9, 6:9] = np.eye(3) * 0.002 # for velocity -Q[9:12, 9:12] = np.eye(3) * 0.003 # for angular velocity +import matplotlib.pyplot as plt -G = np.zeros((33, 12)) -G[0:3, 0:3] = np.eye(3) -G[3:6, 3:6] = np.eye(3) -G[6:9, 6:9] = np.eye(3) -G[9:12, 9:12] = np.eye(3) +# Initialize UKF with StateQuat +initial_position = np.array([0.0, 0.0, 0.0]) # x, y, z +initial_velocity = np.array([0.0, 0.0, 0.0]) # vx, vy, vz +initial_quaternion = np.array([1.0, 0.0, 0.0, 0.0]) # w, x, y, z (identity quaternion) +initial_angular_velocity = np.array([0.0, 0.0, 0.0]) # wx, wy, wz +initial_g_eta = np.array([1.2, 0.3, 0.3, 0.3]) # g_eta parameters +initial_covariance = np.eye(37) * 20.0 # Initial covariance matrix -GG = G @ Q @ G.T +# Create StateQuat object +state = ukf.StateQuat(initial_position, initial_quaternion, initial_velocity, initial_angular_velocity) +state.okid_params.g_eta = initial_g_eta +state.covariance = initial_covariance +real_state = ukf.StateQuat(initial_position, initial_quaternion, initial_velocity, initial_angular_velocity) +real_state.okid_params.g_eta = np.array([1.2, 0.3, 0.3, 0.3]) -def fancy_print_matrix(matrix, name="Matrix", precision=4): - """Print a matrix with fancy formatting. +UKF_model = UKF(state, Q=10.0 * np.eye(37)) # Process noise covariance +dvl_measurement = ukf.MeasModel() - Args: - matrix: numpy array to print - name: name of the matrix to display - precision: number of decimal places to show - """ - print(f"\n{'=' * 50}") - print(f" {name} [{matrix.shape[0]}x{matrix.shape[1]}]") - print(f"{'=' * 50}") +def ang_h(state: ukf.StateQuat) -> 'ukf.MeasModel': + H_matrix = np.zeros((3, 13)) + H_matrix[:, 10:13] = np.eye(3) + z_i = ukf.MeasModel() + z_i.measurement = np.dot(H_matrix, state.dynamic_part()) + return z_i - # Set numpy print options - with np.printoptions(precision=precision, suppress=True, linewidth=100): - # Print each row with custom formatting - for i in range(matrix.shape[0]): - row = ' '.join([f"{x:8.{precision}f}" for x in matrix[i]]) - print(f" {i:2d} | {row}") +ang_measurement = ukf.MeasModel(H=ang_h) - print(f"{'=' * 50}\n") +# UKF parameters +dt = 0.01 # time step +sim_time = 1.0 # total simulation time +steps = int(sim_time / dt) +# Storage for trajectory +positions = np.zeros((steps, 3)) +velocities = np.zeros((steps, 3)) +quaternions = np.zeros((steps, 4)) +angular_velocities = np.zeros((steps, 3)) +okid_params = np.zeros((steps, 4)) + +# Storage for trajectory +positions_est = np.zeros((steps, 3)) +velocities_est = np.zeros((steps, 3)) +quaternions_est = np.zeros((steps, 4)) +angular_velocities_est = np.zeros((steps, 3)) +okid_params_est = np.zeros((steps, 4)) + +# Simulation loop +for i in range(steps): + t = i * dt + + # Generate control input (slow sinusoidal signals) + control_force = np.array([ + 5 * np.sin(4.0 * t), + 10 * np.sin(3.0 * t), + 10 * np.sin(2.0 * t) + ]) + + control_torque = np.array([ + 10 * np.sin(4.0 * t), + 10 * np.sin(4.0 * t), + 10 * np.sin(4.0 * t) + ]) + + control_input = np.concatenate((control_force, control_torque)) + + # Propagate state using UKF prediction + real_state = ukf.F_dynamics(real_state, dt, control_input) + state = UKF_model.unscented_transform(state, control_input) + if i % 5 == 0: + # Simulate measurement update every 5 steps + ang_measurement.measurement = np.array([ + real_state.angular_velocity[0], + real_state.angular_velocity[1], + real_state.angular_velocity[2] + ]) + np.random.normal(0, 0.03, 3) + # Simulate measurement covariance + ang_measurement.covariance = np.eye(3) * 0.04 # Measurement noise covariance + # Update UKF with measurement + UKF_model.measurement_update(state, ang_measurement) + state = UKF_model.posteriori_estimate(state, ang_measurement) + + if i % 10 == 0: + # Simulate measurement update every 10 steps + dvl_measurement.measurement = np.array([ + real_state.velocity[0], + real_state.velocity[1], + real_state.velocity[2] + ]) + np.random.normal(0, 0.03, 3) # Simulated measurement with noise + + # Simulate measurement covariance + dvl_measurement.covariance = np.eye(3) * 0.04 # Measurement noise covariance + + # Update UKF with measurement + UKF_model.measurement_update(state, dvl_measurement) + state = UKF_model.posteriori_estimate(state, dvl_measurement) + print_matrix(state.covariance) + + print("Determinant of covariance matrix:", np.linalg.det(state.covariance)) + # Store state for plotting + positions[i] = real_state.position + velocities[i] = real_state.velocity + quaternions[i] = real_state.orientation + angular_velocities[i] = real_state.angular_velocity + okid_params[i] = real_state.okid_params.g_eta + + # Store estimated state for plotting + positions_est[i] = state.position + velocities_est[i] = state.velocity + quaternions_est[i] = state.orientation + angular_velocities_est[i] = state.angular_velocity + okid_params_est[i] = state.okid_params.g_eta + + # Add small delay to simulate real-time execution + time.sleep(0.001) +print(state.as_vector()) +# Plotting +time_points = np.arange(0, sim_time, dt) + +# 3D trajectory plot +fig = plt.figure(figsize=(12, 10)) +ax = fig.add_subplot(111, projection='3d') +ax.plot(positions[:, 0], positions[:, 1], positions[:, 2], 'b-', label='True Trajectory') +ax.plot(positions_est[:, 0], positions_est[:, 1], positions_est[:, 2], 'r--', label='Estimated Trajectory') +ax.scatter(positions[0, 0], positions[0, 1], positions[0, 2], c='g', marker='o', s=100, label='Start') +ax.scatter(positions[-1, 0], positions[-1, 1], positions[-1, 2], c='r', marker='o', s=100, label='End') +ax.set_xlabel('X Position') +ax.set_ylabel('Y Position') +ax.set_zlabel('Z Position') +ax.set_title('3D Trajectory') +ax.legend() + +# Position plot +plt.figure(figsize=(12, 6)) +plt.subplot(311) +plt.plot(time_points, positions[:, 0], 'b-', label='True') +plt.plot(time_points, positions_est[:, 0], 'r--', label='Estimated') +plt.ylabel('X Position') +plt.legend() +plt.subplot(312) +plt.plot(time_points, positions[:, 1], 'b-', label='True') +plt.plot(time_points, positions_est[:, 1], 'r--', label='Estimated') +plt.ylabel('Y Position') +plt.legend() +plt.subplot(313) +plt.plot(time_points, positions[:, 2], 'b-', label='True') +plt.plot(time_points, positions_est[:, 2], 'r--', label='Estimated') +plt.ylabel('Z Position') +plt.xlabel('Time (s)') +plt.legend() +plt.tight_layout() + +# Velocity plot +plt.figure(figsize=(12, 6)) +plt.subplot(311) +plt.plot(time_points, velocities[:, 0], 'b-', label='True') +plt.plot(time_points, velocities_est[:, 0], 'r--', label='Estimated') +plt.ylabel('X Velocity') +plt.legend() +plt.subplot(312) +plt.plot(time_points, velocities[:, 1], 'b-', label='True') +plt.plot(time_points, velocities_est[:, 1], 'r--', label='Estimated') +plt.ylabel('Y Velocity') +plt.legend() +plt.subplot(313) +plt.plot(time_points, velocities[:, 2], 'b-', label='True') +plt.plot(time_points, velocities_est[:, 2], 'r--', label='Estimated') +plt.ylabel('Z Velocity') +plt.xlabel('Time (s)') +plt.legend() +plt.tight_layout() + +# Angular velocity plot +plt.figure(figsize=(12, 6)) +plt.subplot(311) +plt.plot(time_points, angular_velocities[:, 0], 'b-', label='True') +plt.plot(time_points, angular_velocities_est[:, 0], 'r--', label='Estimated') +plt.ylabel('Roll Rate') +plt.legend() +plt.subplot(312) +plt.plot(time_points, angular_velocities[:, 1], 'b-', label='True') +plt.plot(time_points, angular_velocities_est[:, 1], 'r--', label='Estimated') +plt.ylabel('Pitch Rate') +plt.legend() +plt.subplot(313) +plt.plot(time_points, angular_velocities[:, 2], 'b-', label='True') +plt.plot(time_points, angular_velocities_est[:, 2], 'r--', label='Estimated') +plt.ylabel('Yaw Rate') +plt.xlabel('Time (s)') +plt.legend() +plt.tight_layout() + +# OKID g_eta plot +plt.figure(figsize=(12, 6)) +plt.subplot(411) +plt.plot(time_points, okid_params[:, 0], 'b-', label='True') +plt.plot(time_points, okid_params_est[:, 0], 'r--', label='Estimated') +plt.ylabel('g_eta[0]') +plt.legend() +plt.subplot(412) +plt.plot(time_points, okid_params[:, 1], 'b-', label='True') +plt.plot(time_points, okid_params_est[:, 1], 'r--', label='Estimated') +plt.ylabel('g_eta[1]') +plt.legend() +plt.subplot(413) +plt.plot(time_points, okid_params[:, 2], 'b-', label='True') +plt.plot(time_points, okid_params_est[:, 2], 'r--', label='Estimated') +plt.ylabel('g_eta[2]') +plt.legend() +plt.subplot(414) +plt.plot(time_points, okid_params[:, 3], 'b-', label='True') +plt.plot(time_points, okid_params_est[:, 3], 'r--', label='Estimated') +plt.ylabel('g_eta[3]') +plt.xlabel('Time (s)') +plt.legend() +plt.tight_layout() + +plt.show() -# Example usage: -fancy_print_matrix(GG, name="Process Noise Covariance (GQG')", precision=3) From 3da7c44b6d700903072e6fa2117b756d1f6dd05f Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Sun, 18 May 2025 16:40:56 +0200 Subject: [PATCH 21/30] fix: added tukf and simulation --- navigation/eskf/config/eskf_params.yaml | 6 +- navigation/eskf/include/eskf/typedefs.hpp | 6 +- navigation/eskf/src/eskf.cpp | 56 ++--- navigation/eskf/src/eskf_ros.cpp | 8 +- navigation/tukf/simulation.py | 155 +++++++++++++ navigation/tukf/simulation_re.ipynb | 265 ++++++++++++++++++++++ 6 files changed, 451 insertions(+), 45 deletions(-) create mode 100644 navigation/tukf/simulation.py create mode 100644 navigation/tukf/simulation_re.ipynb diff --git a/navigation/eskf/config/eskf_params.yaml b/navigation/eskf/config/eskf_params.yaml index 98be8e789..3b9fcdc0b 100644 --- a/navigation/eskf/config/eskf_params.yaml +++ b/navigation/eskf/config/eskf_params.yaml @@ -1,8 +1,8 @@ eskf_node: ros__parameters: - imu_topic: imu/data_raw + imu_topic: /imu/data_raw dvl_topic: /dvl/sim odom_topic: odom - diag_Q_std: [0.05, 0.05, 0.05, 0.00001, 0.00001, 0.00001, 0.000001, 0.000000001, 0.000000001, 0.000000001, 0.00000001, 0.00000001] - diag_p_init: [1.0, 1.0, 0.5, 0.5, 0.5, 1.0, 0.1, 0.1, 0.1, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] + diag_Q_std: [0.01, 0.01, 0.01, 0.005, 0.005, 0.005, 0.00001, 0.00001, 0.00001, 0.00001, 0.00001, 0.00001] + diag_p_init: [1.0, 1.0, 1.0, 0.5, 0.5, 0.5, 0.1, 0.1, 0.1, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] imu_frame: [0.0, 0.0, -1.0, 0.0, -1.0, 0.0, -1.0, 0.0, 0.0] diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index 47dfe06e1..eacb32841 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -26,6 +26,8 @@ typedef Eigen::Matrix Matrix18x3d; typedef Eigen::Matrix Matrix36d; typedef Eigen::Matrix Matrix6d; typedef Eigen::Matrix Matrix9d; +typedef Eigen::Matrix Matrix15d; +typedef Eigen::Matrix Vector15d; } // namespace Eigen template @@ -36,7 +38,7 @@ Eigen::Matrix createDiagonalMatrix( } struct state_quat { - Eigen::Vector3d pos = Eigen::Vector3d::Zero(); + Eigen::Vector3d pos = Eigen::Vector3d(0,0,0.125); Eigen::Vector3d vel = Eigen::Vector3d::Zero(); Eigen::Quaterniond quat = Eigen::Quaterniond::Identity(); Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero(); @@ -58,7 +60,7 @@ struct state_quat { euler_diff = (quat * other.quat.inverse()) .toRotationMatrix() - .eulerAngles(0, 1, 2); + .eulerAngles(0, 1, 2) + Eigen::Vector3d(-M_PI, M_PI, -M_PI); vec << pos - other.pos, vel - other.vel, euler_diff, gyro_bias - other.gyro_bias, accel_bias - other.accel_bias, diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index e0e7c7a98..e39993abc 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -102,10 +102,9 @@ Eigen::Matrix3x18d ESKF::calculate_h_jacobian() { return H; } -Eigen::Matrix3x1d ESKF::calculate_h() { - Eigen::Matrix3x1d h; - Eigen::Matrix3d R_bn = - current_nom_state_.quat.normalized().toRotationMatrix().transpose(); +Eigen::Vector3d ESKF::calculate_h() { + Eigen::Vector3d h; + Eigen::Matrix3d R_bn = current_nom_state_.quat.normalized().toRotationMatrix().transpose(); h = R_bn * current_nom_state_.vel; @@ -114,18 +113,13 @@ Eigen::Matrix3x1d ESKF::calculate_h() { void ESKF::nominal_state_discrete(const imu_measurement& imu_meas, const double dt) { - Eigen::Vector3d acc = - current_nom_state_.quat.normalized().toRotationMatrix() * - (imu_meas.accel - current_nom_state_.accel_bias) + - current_nom_state_.gravity; + Eigen::Vector3d acc = current_nom_state_.quat.normalized().toRotationMatrix() * (imu_meas.accel - current_nom_state_.accel_bias) + current_nom_state_.gravity; Eigen::Vector3d gyro = (imu_meas.gyro - current_nom_state_.gyro_bias) * dt; - current_nom_state_.pos = current_nom_state_.pos + - current_nom_state_.vel * dt + 0.5 * sq(dt) * acc; + current_nom_state_.pos = current_nom_state_.pos + current_nom_state_.vel * dt + 0.5 * sq(dt) * acc; current_nom_state_.vel = current_nom_state_.vel + dt * acc; - current_nom_state_.quat = - (current_nom_state_.quat * vector3d_to_quaternion(gyro)); + current_nom_state_.quat = (current_nom_state_.quat * vector3d_to_quaternion(gyro)); current_nom_state_.quat.normalize(); current_nom_state_.gyro_bias = current_nom_state_.gyro_bias; @@ -159,8 +153,7 @@ void ESKF::error_state_prediction(const imu_measurement& imu_meas, std::tie(A_d, GQG_d) = van_loan_discretization(A_c, G_c, dt); state_euler next_error_state; - current_error_state_.covariance = - A_d * current_error_state_.covariance * A_d.transpose() + GQG_d; + current_error_state_.covariance = A_d * current_error_state_.covariance * A_d.transpose() + GQG_d; } void ESKF::NIS(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S) { @@ -170,27 +163,17 @@ void ESKF::NIS(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S) { void ESKF::NEEDS() { Eigen::Vector18d error_state = current_nom_state_.nees_error(ground_truth_); - - // Use SVD-based pseudo-inverse for better numerical stability - Eigen::JacobiSVD svd( - current_error_state_.covariance, - Eigen::ComputeThinU | Eigen::ComputeThinV); - const double epsilon = 1e-10; // Threshold for singular values - Eigen::VectorXd singular_values = svd.singularValues(); - Eigen::VectorXd singular_values_inv(singular_values.size()); - - for (int i = 0; i < singular_values.size(); ++i) { - if (singular_values(i) > epsilon) { - singular_values_inv(i) = 1.0 / singular_values(i); - } else { - singular_values_inv(i) = 0.0; - } + Eigen::Vector15d error_state_trim = error_state.head<15>(); + // Set the last 6 elements of error_state_trim to zero + for (int i = 9; i < 15; i++) { + error_state_trim(i) = 0; } - - Eigen::MatrixXd cov_inv = svd.matrixV() * singular_values_inv.asDiagonal() * - svd.matrixU().transpose(); - - NEES_ = error_state.transpose() * cov_inv * error_state; + error_state_trim(6) = 0.001; + error_state_trim(7) = 0.001; + error_state_trim(8) = 0.001; + Eigen::Matrix15d P = current_error_state_.covariance.block<15, 15>(0, 0); + Eigen::Matrix15d P_inv = P.inverse(); + NEES_ = error_state_trim.transpose() * P_inv * error_state_trim; } void ESKF::measurement_update(const dvl_measurement& dvl_meas) { @@ -201,6 +184,7 @@ void ESKF::measurement_update(const dvl_measurement& dvl_meas) { Eigen::Matrix3d S = H * P * H.transpose() + R; Eigen::Matrix18x3d K = P * H.transpose() * S.inverse(); Eigen::Vector3d innovation = dvl_meas.vel - calculate_h(); + NIS(innovation, S); current_error_state_.set_from_vector(K * innovation); @@ -215,9 +199,7 @@ void ESKF::measurement_update(const dvl_measurement& dvl_meas) { void ESKF::injection_and_reset() { current_nom_state_.pos = current_nom_state_.pos + current_error_state_.pos; current_nom_state_.vel = current_nom_state_.vel + current_error_state_.vel; - current_nom_state_.quat = - current_nom_state_.quat * - vector3d_to_quaternion(current_error_state_.euler); + current_nom_state_.quat = current_nom_state_.quat * vector3d_to_quaternion(current_error_state_.euler); current_nom_state_.quat.normalize(); current_nom_state_.gyro_bias = current_nom_state_.gyro_bias + current_error_state_.gyro_bias; diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index 54daadb4c..b7cdced09 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -48,7 +48,7 @@ void ESKFNode::set_subscribers_and_publisher() { odom_topic, qos_sensor_data); nis_pub_ = create_publisher("dvl/nis", 10); - nees_pub_ = create_publisher("dvl/needs", 10); + nees_pub_ = create_publisher("dvl/nees", 10); } void ESKFNode::set_parameters() { @@ -123,8 +123,10 @@ void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { } void ESKFNode::dvl_callback(const stonefish_ros2::msg::DVL::SharedPtr msg) { + // Log that we received a DVL message + // spdlog::info("DVL message received"); dvl_meas_.vel << msg->velocity.x, msg->velocity.y, msg->velocity.z; - dvl_meas_.cov << 0.001, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.001; + dvl_meas_.cov << 0.004*0.004, 0.0, 0.0, 0.0, 0.004*0.004, 0.0, 0.0, 0.0, 0.004*0.004; // msg->velocity_covariance[0], msg->velocity_covariance[1], // msg->velocity_covariance[2], @@ -144,7 +146,7 @@ void ESKFNode::dvl_callback(const stonefish_ros2::msg::DVL::SharedPtr msg) { float gravity_x = 0.0; float gravity_y = 0.0; - float gravity_z = -9.81; + float gravity_z = 9.81; g_truth_.gyro_bias << gyro_bias_x, gyro_bias_y, gyro_bias_z; g_truth_.accel_bias << accel_bias_x, accel_bias_y, accel_bias_z; diff --git a/navigation/tukf/simulation.py b/navigation/tukf/simulation.py new file mode 100644 index 000000000..56fb2a6a1 --- /dev/null +++ b/navigation/tukf/simulation.py @@ -0,0 +1,155 @@ +from rosbags.highlevel import AnyReader +from rosbags.typesys import get_types_from_msg, register_types +import numpy as np, pandas as pd, pathlib +from tukf import TUKF +import tukf_class as ukf + +bag_folder = pathlib.Path(r"/home/talha/vortex_auv_ws/bags/sim_data_no_dvl") + +# Initialize UKF with StateQuat +initial_position = np.array([0.0, 0.0, 0.0]) # x, y, z +initial_velocity = np.array([0.0, 0.0, 0.0]) # vx, vy, vz +initial_quaternion = np.array([0.0, 0.0, 0.0]) # w, x, y, z (identity quaternion) +initial_angular_velocity = np.array([0.0, 0.0, 0.0]) # wx, wy, wz +initial_g_eta = np.array([0.01, 0.01, 0.01, 0.01]) # g_eta parameters +initial_intertia = np.array([0.2, 0.2, 0.1, + 0.2, 0.2, 0.2, + 0.1, 0.2, 0.2]) +initial_damping = np.array([0.01, 0.01, 0.01, + 0.01, 0.01, 0.01]) +initla_added_mass = np.array([0.02, 0.02, 0.02, + 0.02, 0.02, 0.02]) + +p_diag = np.concatenate([ + 2*np.ones(3), # x position + 2*np.ones(3), # orientation + 2*np.ones(3), # velocity + 2*np.ones(3), # angular velocity + 2*np.ones(9), # inertia + 2*np.ones(6), # added mass + 2*np.ones(6), # damping + 2*np.ones(4) # g_eta +]) + +initial_covariance = np.diag(p_diag) + +state = ukf.AUVState(initial_position.copy(), initial_quaternion.copy(), initial_velocity.copy(), initial_angular_velocity.copy(), + initial_intertia.copy(), initla_added_mass.copy(), initial_damping.copy(), initial_g_eta.copy()) + +state.covariance = initial_covariance.copy() + +Q_diag = np.concatenate([ + 0.1*np.ones(3), # position + 0.1*np.ones(9), # kinematic (η & ν) + 0.001*np.ones(9), # inertia + 0.001*np.ones(6), # added mass + 0.001*np.ones(6), # damping + 0.001*np.ones(4), # g_eta +]) + +UKF_model = TUKF(state, np.diag(Q_diag)) # Process noise covariance + +def dvl_h(state: ukf.AUVState) -> 'ukf.MeasModel': + H_matrix = np.zeros((3, 12)) + H_matrix[:, 6:9] = np.eye(3) + z_i = ukf.MeasModel() + z_i.measurement = np.dot(H_matrix, state.dynamic_part()) + return z_i + +dvl_measurement = ukf.MeasModel(H=dvl_h) + +def ang_h(state: ukf.AUVState) -> 'ukf.MeasModel': + H_matrix = np.zeros((3, 12)) + H_matrix[:, 9:12] = np.eye(3) + z_i = ukf.MeasModel() + z_i.measurement = np.dot(H_matrix, state.dynamic_part()) + return z_i + +ang_measurement = ukf.MeasModel(H=ang_h) + +R_corr = np.array([[0.0, 0.0, -1.0], + [0.0, -1.0, 0.0], + [-1.0, 0.0, 0.0]]) + +# Storage for trajectory +positions = [] +velocities = [] +quaternions = [] +angular_velocities = [] +okid_params = [] + +# Storage for trajectory estimates +positions_est = [] +velocities_est = [] +quaternions_est = [] +angular_velocities_est = [] +okid_params_est = [] + +with AnyReader([bag_folder]) as reader: + # Filter topics once + conns = [c for c in reader.connections + if c.topic in ("/imu/data_raw", "/dvl_twist", "/orca/wrench_input")] + + last_time = None + log = [] + coutner = 0 + + for conn, ts_raw, raw in reader.messages(conns): + t_ns = ts_raw # already nanoseconds integer + coutner += 1 + + if conn.topic == "/orca/wrench_input": + + # Get the wrench input message + msg = reader.deserialize(raw, conn.msgtype) + wrench = msg.wrench # Extract the wrench field from the message + forces = np.array([wrench.force.x, wrench.force.y, wrench.force.z]) + torques = np.array([wrench.torque.x, wrench.torque.y, wrench.torque.z]) + + control_input = np.concatenate([forces, torques]) + + if last_time is not None: + UKF_model.dt = (t_ns - last_time) / 1e9 # Convert nanoseconds to seconds + + # 1. prediction step + state = UKF_model.unscented_transform(state, control_input) + + # 2. measurement update + msg = reader.deserialize(raw, conn.msgtype) + if conn.topic == "/imu/data_raw": + print("IMU data received") + + # Get the IMU data + measurement_imu = np.array([msg.angular_velocity.x, msg.angular_velocity.y, msg.angular_velocity.z]) + + ang_measurement.measurement = np.dot(R_corr,measurement_imu) + + ang_measurement.covariance = np.eye(3) * (0.03**2) + + UKF_model.measurement_update(state, ang_measurement) + state = UKF_model.posteriori_estimate(state, ang_measurement) + + if conn.topic == "/dvl_twist": + print("DVL data received") + + msg = reader.deserialize(raw, conn.msgtype) + dvl_measurement.measurement = np.array([msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z]) + dvl_measurement.measurement = np.dot(R_corr, dvl_measurement.measurement) + + dvl_measurement.covariance = np.eye(3) * (0.01**2) + + # Update UKF with measurement + UKF_model.measurement_update(state, dvl_measurement) + state = UKF_model.posteriori_estimate(state, dvl_measurement) + + + # Store the state estimates + positions_est.append(state.position.copy()) + velocities_est.append(state.velocity.copy()) + quaternions_est.append(state.quaternion.copy()) + angular_velocities_est.append(state.angular_velocity.copy()) + okid_params_est.append(state.okid_part().copy()) + + last_time = t_ns + + \ No newline at end of file diff --git a/navigation/tukf/simulation_re.ipynb b/navigation/tukf/simulation_re.ipynb new file mode 100644 index 000000000..e508825bf --- /dev/null +++ b/navigation/tukf/simulation_re.ipynb @@ -0,0 +1,265 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Simulation results for the TUKF ###\n", + "\n", + "try to simulate the path and parameters using the tukf algorithm" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "from rosbags.highlevel import AnyReader\n", + "from rosbags.typesys import get_types_from_msg, register_types\n", + "import numpy as np, pandas as pd, pathlib\n", + "from tukf import TUKF\n", + "import tukf_class as ukf" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "bag_folder = pathlib.Path(r\"/home/talha/vortex_auv_ws/bags/sim_data_no_dvl\")" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "# Initialize UKF with StateQuat\n", + "initial_position = np.array([0.0, 0.0, 0.0]) # x, y, z\n", + "initial_velocity = np.array([0.0, 0.0, 0.0]) # vx, vy, vz\n", + "initial_quaternion = np.array([0.0, 0.0, 0.0]) # w, x, y, z (identity quaternion)\n", + "initial_angular_velocity = np.array([0.0, 0.0, 0.0]) # wx, wy, wz\n", + "initial_g_eta = np.array([0.01, 0.01, 0.01, 0.01]) # g_eta parameters\n", + "initial_intertia = np.array([0.2, 0.2, 0.1, \n", + " 0.2, 0.2, 0.2, \n", + " 0.1, 0.2, 0.2])\n", + "initial_damping = np.array([0.01, 0.01, 0.01,\n", + " 0.01, 0.01, 0.01])\n", + "initla_added_mass = np.array([0.02, 0.02, 0.02,\n", + " 0.02, 0.02, 0.02])\n", + "\n", + "p_diag = np.concatenate([\n", + " 2*np.ones(3), # x position\n", + " 2*np.ones(3), # orientation\n", + " 2*np.ones(3), # velocity\n", + " 2*np.ones(3), # angular velocity\n", + " 2*np.ones(9), # inertia\n", + " 2*np.ones(6), # added mass\n", + " 2*np.ones(6), # damping\n", + " 2*np.ones(4) # g_eta\n", + "])\n", + "\n", + "initial_covariance = np.diag(p_diag) \n", + "\n", + "state = ukf.AUVState(initial_position.copy(), initial_quaternion.copy(), initial_velocity.copy(), initial_angular_velocity.copy(), \n", + " initial_intertia.copy(), initla_added_mass.copy(), initial_damping.copy(), initial_g_eta.copy())\n", + "\n", + "state.covariance = initial_covariance.copy()\n", + "\n", + "Q_diag = np.concatenate([\n", + " 0.1*np.ones(3), # position\n", + " 0.1*np.ones(9), # kinematic (η & ν)\n", + " 0.001*np.ones(9), # inertia\n", + " 0.001*np.ones(6), # added mass\n", + " 0.001*np.ones(6), # damping\n", + " 0.001*np.ones(4), # g_eta\n", + "])\n", + "\n", + "UKF_model = TUKF(state, np.diag(Q_diag)) # Process noise covariance\n", + "\n", + "def dvl_h(state: ukf.AUVState) -> 'ukf.MeasModel':\n", + " H_matrix = np.zeros((3, 12))\n", + " H_matrix[:, 6:9] = np.eye(3)\n", + " z_i = ukf.MeasModel()\n", + " z_i.measurement = np.dot(H_matrix, state.dynamic_part())\n", + " return z_i\n", + "\n", + "dvl_measurement = ukf.MeasModel(H=dvl_h)\n", + "\n", + "def ang_h(state: ukf.AUVState) -> 'ukf.MeasModel':\n", + " H_matrix = np.zeros((3, 12))\n", + " H_matrix[:, 9:12] = np.eye(3)\n", + " z_i = ukf.MeasModel()\n", + " z_i.measurement = np.dot(H_matrix, state.dynamic_part())\n", + " return z_i\n", + "\n", + "ang_measurement = ukf.MeasModel(H=ang_h) \n", + "\n", + "R_corr = np.array([[0.0, 0.0, -1.0],\n", + " [0.0, -1.0, 0.0],\n", + " [-1.0, 0.0, 0.0]])\n", + "\n", + "# Storage for trajectory\n", + "positions = []\n", + "velocities = []\n", + "quaternions = []\n", + "angular_velocities = []\n", + "okid_params = []\n", + "\n", + "# Storage for trajectory estimates\n", + "positions_est = []\n", + "velocities_est = []\n", + "quaternions_est = []\n", + "angular_velocities_est = []\n", + "okid_params_est = []" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [], + "source": [ + "with AnyReader([bag_folder]) as reader:\n", + " # Filter topics once\n", + " conns = [c for c in reader.connections\n", + " if c.topic in (\"/imu/data_raw\", \"/dvl_twist\", \"/orca/wrench_input\")]\n", + "\n", + " last_time = None\n", + " log = []\n", + " coutner = 0\n", + "\n", + " for conn, ts_raw, raw in reader.messages(conns):\n", + " t_ns = ts_raw # already nanoseconds integer\n", + " coutner += 1\n", + "\n", + " if conn.topic == \"/orca/wrench_input\":\n", + " \n", + " # Get the wrench input message\n", + " msg = reader.deserialize(raw, conn.msgtype)\n", + " wrench = msg.wrench # Extract the wrench field from the message\n", + " forces = np.array([wrench.force.x, wrench.force.y, wrench.force.z])\n", + " torques = np.array([wrench.torque.x, wrench.torque.y, wrench.torque.z])\n", + "\n", + " control_input = np.concatenate([forces, torques])\n", + "\n", + " if last_time is not None:\n", + " UKF_model.dt = (t_ns - last_time) / 1e9 # Convert nanoseconds to seconds\n", + "\n", + " # 1. prediction step\n", + " state = UKF_model.unscented_transform(state, control_input)\n", + "\n", + " # 2. measurement update\n", + " msg = reader.deserialize(raw, conn.msgtype)\n", + " if conn.topic == \"/imu/data_raw\":\n", + " # print(\"IMU data received\")\n", + "\n", + " # Get the IMU data\n", + " measurement_imu = np.array([msg.angular_velocity.x, msg.angular_velocity.y, msg.angular_velocity.z])\n", + "\n", + " ang_measurement.measurement = np.dot(R_corr,measurement_imu)\n", + "\n", + " ang_measurement.covariance = np.eye(3) * (0.03**2) \n", + "\n", + " UKF_model.measurement_update(state, ang_measurement)\n", + " state = UKF_model.posteriori_estimate(state, ang_measurement)\n", + "\n", + " if conn.topic == \"/dvl_twist\":\n", + " # print(\"DVL data received\")\n", + "\n", + " msg = reader.deserialize(raw, conn.msgtype)\n", + " dvl_measurement.measurement = np.array([msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z])\n", + " \n", + " dvl_measurement.covariance = np.eye(3) * (0.01**2) \n", + " \n", + " # Update UKF with measurement\n", + " UKF_model.measurement_update(state, dvl_measurement)\n", + " state = UKF_model.posteriori_estimate(state, dvl_measurement)\n", + "\n", + "\n", + " # Store the state estimates\n", + " positions_est.append(state.position.copy())\n", + " velocities_est.append(state.velocity.copy())\n", + " quaternions_est.append(state.orientation.copy())\n", + " angular_velocities_est.append(state.angular_velocity.copy())\n", + " okid_params_est.append(state.okid_part().copy())\n", + "\n", + " last_time = t_ns" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "import numpy as np\n", + "\n", + "import matplotlib.pyplot as plt\n", + "\n", + "# Extract x, y, z positions from positions_est\n", + "x_positions = np.array([pos[0] for pos in positions_est])\n", + "y_positions = np.array([pos[1] for pos in positions_est])\n", + "z_positions = np.array([pos[2] for pos in positions_est])\n", + "\n", + "# Create figure with three subplots\n", + "fig, axs = plt.subplots(3, 1, figsize=(12, 10), sharex=True)\n", + "fig.suptitle('AUV Position Estimates Over Time', fontsize=16)\n", + "\n", + "# Plot x position\n", + "axs[0].plot(x_positions, 'b-', linewidth=2)\n", + "axs[0].set_ylabel('X Position [m]')\n", + "axs[0].grid(True)\n", + "\n", + "# Plot y position\n", + "axs[1].plot(y_positions, 'g-', linewidth=2)\n", + "axs[1].set_ylabel('Y Position [m]')\n", + "axs[1].grid(True)\n", + "\n", + "# Plot z position\n", + "axs[2].plot(z_positions, 'r-', linewidth=2)\n", + "axs[2].set_ylabel('Z Position [m]')\n", + "axs[2].set_xlabel('Time steps')\n", + "axs[2].grid(True)\n", + "\n", + "plt.tight_layout(rect=[0, 0.03, 1, 0.95])\n", + "plt.show()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.10.12" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} From 025410a8ad499ebfd126e2ff35653e000731cc46 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Tue, 20 May 2025 13:23:59 +0200 Subject: [PATCH 22/30] fix:added in some minor fixes --- navigation/eskf/config/eskf_params.yaml | 2 +- navigation/eskf/include/eskf/eskf.hpp | 8 -- navigation/eskf/include/eskf/eskf_ros.hpp | 19 +-- navigation/eskf/src/eskf.cpp | 18 --- navigation/eskf/src/eskf_ros.cpp | 65 +-------- navigation/tukf/simulation_re.ipynb | 154 ++++++++++++++++++---- navigation/tukf/tukf_class.py | 4 +- 7 files changed, 138 insertions(+), 132 deletions(-) diff --git a/navigation/eskf/config/eskf_params.yaml b/navigation/eskf/config/eskf_params.yaml index 3b9fcdc0b..c08c21d3c 100644 --- a/navigation/eskf/config/eskf_params.yaml +++ b/navigation/eskf/config/eskf_params.yaml @@ -1,7 +1,7 @@ eskf_node: ros__parameters: imu_topic: /imu/data_raw - dvl_topic: /dvl/sim + dvl_topic: /orca/twist odom_topic: odom diag_Q_std: [0.01, 0.01, 0.01, 0.005, 0.005, 0.005, 0.00001, 0.00001, 0.00001, 0.00001, 0.00001, 0.00001] diag_p_init: [1.0, 1.0, 1.0, 0.5, 0.5, 0.5, 0.1, 0.1, 0.1, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp index d9b7d4fa0..214f462c4 100644 --- a/navigation/eskf/include/eskf/eskf.hpp +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -27,12 +27,6 @@ class ESKF { // NIS double NIS_; - // NEEDS - double NEES_; - - // ground truth - state_quat ground_truth_; - private: // @brief Predict the nominal state // @param imu_meas: IMU measurement @@ -53,8 +47,6 @@ class ESKF { // @param S: Innovation covariance matrix void NIS(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S); - void NEEDS(); - // @brief Update the error state // @param dvl_meas: DVL measurement void measurement_update(const dvl_measurement& dvl_meas); diff --git a/navigation/eskf/include/eskf/eskf_ros.hpp b/navigation/eskf/include/eskf/eskf_ros.hpp index c3d09e820..b10995f04 100644 --- a/navigation/eskf/include/eskf/eskf_ros.hpp +++ b/navigation/eskf/include/eskf/eskf_ros.hpp @@ -21,11 +21,6 @@ class ESKFNode : public rclcpp::Node { explicit ESKFNode(); private: - void pose_callback( - const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); - - void twist_callback( - const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); // @brief Callback function for the imu topic // @param msg: Imu message containing the imu data @@ -33,7 +28,7 @@ class ESKFNode : public rclcpp::Node { // @brief Callback function for the dvl topic // @param msg: TwistWithCovarianceStamped message containing the dvl data - void dvl_callback(const stonefish_ros2::msg::DVL::SharedPtr msg); + void dvl_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); // @brief Publish the odometry message void publish_odom(); @@ -46,28 +41,18 @@ class ESKFNode : public rclcpp::Node { rclcpp::Subscription::SharedPtr imu_sub_; - rclcpp::Subscription::SharedPtr dvl_sub_; - - rclcpp::Subscription< - geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr pose_sub_; - - rclcpp::Subscription< - geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr twist_sub_; + rclcpp::Subscription::SharedPtr dvl_sub_; rclcpp::Publisher::SharedPtr odom_pub_; rclcpp::Publisher::SharedPtr nis_pub_; - rclcpp::Publisher::SharedPtr nees_pub_; - std::chrono::milliseconds time_step; rclcpp::TimerBase::SharedPtr odom_pub_timer_; state_quat nom_state_; - state_quat g_truth_; - state_euler error_state_; imu_measurement imu_meas_; diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index e39993abc..8d1fdb6b4 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -160,22 +160,6 @@ void ESKF::NIS(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S) { Eigen::Matrix3d S_inv = S.inverse(); NIS_ = innovation.transpose() * S_inv * innovation; } - -void ESKF::NEEDS() { - Eigen::Vector18d error_state = current_nom_state_.nees_error(ground_truth_); - Eigen::Vector15d error_state_trim = error_state.head<15>(); - // Set the last 6 elements of error_state_trim to zero - for (int i = 9; i < 15; i++) { - error_state_trim(i) = 0; - } - error_state_trim(6) = 0.001; - error_state_trim(7) = 0.001; - error_state_trim(8) = 0.001; - Eigen::Matrix15d P = current_error_state_.covariance.block<15, 15>(0, 0); - Eigen::Matrix15d P_inv = P.inverse(); - NEES_ = error_state_trim.transpose() * P_inv * error_state_trim; -} - void ESKF::measurement_update(const dvl_measurement& dvl_meas) { Eigen::Matrix3x18d H = calculate_h_jacobian(); Eigen::Matrix18d P = current_error_state_.covariance; @@ -192,8 +176,6 @@ void ESKF::measurement_update(const dvl_measurement& dvl_meas) { current_error_state_.covariance = I_KH * P * I_KH.transpose() + K * R * K.transpose(); // Used joseph form for more stable calculations - - NEEDS(); } void ESKF::injection_and_reset() { diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index b7cdced09..cc4256c18 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -20,16 +20,6 @@ void ESKFNode::set_subscribers_and_publisher() { auto qos_sensor_data = rclcpp::QoS( rclcpp::QoSInitialization(qos_profile.history, 1), qos_profile); - pose_sub_ = this->create_subscription< - geometry_msgs::msg::PoseWithCovarianceStamped>( - "/orca/pose", qos_sensor_data, - std::bind(&ESKFNode::pose_callback, this, std::placeholders::_1)); - - twist_sub_ = this->create_subscription< - geometry_msgs::msg::TwistWithCovarianceStamped>( - "/orca/twist", qos_sensor_data, - std::bind(&ESKFNode::twist_callback, this, std::placeholders::_1)); - this->declare_parameter("imu_topic"); std::string imu_topic = this->get_parameter("imu_topic").as_string(); imu_sub_ = this->create_subscription( @@ -38,7 +28,7 @@ void ESKFNode::set_subscribers_and_publisher() { this->declare_parameter("dvl_topic"); std::string dvl_topic = this->get_parameter("dvl_topic").as_string(); - dvl_sub_ = this->create_subscription( + dvl_sub_ = this->create_subscription( dvl_topic, qos_sensor_data, std::bind(&ESKFNode::dvl_callback, this, std::placeholders::_1)); @@ -48,7 +38,6 @@ void ESKFNode::set_subscribers_and_publisher() { odom_topic, qos_sensor_data); nis_pub_ = create_publisher("dvl/nis", 10); - nees_pub_ = create_publisher("dvl/nees", 10); } void ESKFNode::set_parameters() { @@ -80,22 +69,6 @@ void ESKFNode::set_parameters() { error_state_.covariance = P; } -void ESKFNode::pose_callback( - const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg) { - g_truth_.pos << msg->pose.pose.position.x, msg->pose.pose.position.y, - msg->pose.pose.position.z; - g_truth_.quat.w() = msg->pose.pose.orientation.w; - g_truth_.quat.x() = msg->pose.pose.orientation.x; - g_truth_.quat.y() = msg->pose.pose.orientation.y; - g_truth_.quat.z() = msg->pose.pose.orientation.z; -} - -void ESKFNode::twist_callback( - const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { - g_truth_.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, - msg->twist.twist.linear.z; -} - void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { rclcpp::Time current_time = msg->header.stamp; @@ -122,37 +95,14 @@ void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { std::tie(nom_state_, error_state_) = eskf_->imu_update(imu_meas_, dt); } -void ESKFNode::dvl_callback(const stonefish_ros2::msg::DVL::SharedPtr msg) { +void ESKFNode::dvl_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { // Log that we received a DVL message // spdlog::info("DVL message received"); - dvl_meas_.vel << msg->velocity.x, msg->velocity.y, msg->velocity.z; - dvl_meas_.cov << 0.004*0.004, 0.0, 0.0, 0.0, 0.004*0.004, 0.0, 0.0, 0.0, 0.004*0.004; - - // msg->velocity_covariance[0], msg->velocity_covariance[1], - // msg->velocity_covariance[2], - // msg->velocity_covariance[3], msg->velocity_covariance[4], - // msg->velocity_covariance[5], - // msg->velocity_covariance[6], msg->velocity_covariance[7], - // msg->velocity_covariance[8]; - - // Set biases and gravity as float values - float gyro_bias_x = 0.00001; - float gyro_bias_y = 0.00001; - float gyro_bias_z = 0.00001; - - float accel_bias_x = 0.00001; - float accel_bias_y = 0.00001; - float accel_bias_z = 0.00001; - - float gravity_x = 0.0; - float gravity_y = 0.0; - float gravity_z = 9.81; - - g_truth_.gyro_bias << gyro_bias_x, gyro_bias_y, gyro_bias_z; - g_truth_.accel_bias << accel_bias_x, accel_bias_y, accel_bias_z; - g_truth_.gravity << gravity_x, gravity_y, gravity_z; + dvl_meas_.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, msg->twist.twist.linear.z; - eskf_->ground_truth_ = g_truth_; + dvl_meas_.cov << msg->twist.covariance[0], msg->twist.covariance[1], msg->twist.covariance[2], + msg->twist.covariance[6], msg->twist.covariance[7], msg->twist.covariance[8], + msg->twist.covariance[12], msg->twist.covariance[13], msg->twist.covariance[14]; std::tie(nom_state_, error_state_) = eskf_->dvl_update(dvl_meas_); @@ -160,9 +110,6 @@ void ESKFNode::dvl_callback(const stonefish_ros2::msg::DVL::SharedPtr msg) { nis_msg.data = eskf_->NIS_; nis_pub_->publish(nis_msg); - std_msgs::msg::Float64 nees_msg; - nees_msg.data = eskf_->NEES_; - nees_pub_->publish(nees_msg); } void ESKFNode::publish_odom() { diff --git a/navigation/tukf/simulation_re.ipynb b/navigation/tukf/simulation_re.ipynb index e508825bf..06f7369a6 100644 --- a/navigation/tukf/simulation_re.ipynb +++ b/navigation/tukf/simulation_re.ipynb @@ -11,7 +11,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 1, "metadata": {}, "outputs": [], "source": [ @@ -24,7 +24,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 2, "metadata": {}, "outputs": [], "source": [ @@ -33,33 +33,33 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 3, "metadata": {}, "outputs": [], "source": [ "# Initialize UKF with StateQuat\n", - "initial_position = np.array([0.0, 0.0, 0.0]) # x, y, z\n", + "initial_position = np.array([0.0, 0.0, 0.13]) # x, y, z\n", "initial_velocity = np.array([0.0, 0.0, 0.0]) # vx, vy, vz\n", "initial_quaternion = np.array([0.0, 0.0, 0.0]) # w, x, y, z (identity quaternion)\n", "initial_angular_velocity = np.array([0.0, 0.0, 0.0]) # wx, wy, wz\n", "initial_g_eta = np.array([0.01, 0.01, 0.01, 0.01]) # g_eta parameters\n", - "initial_intertia = np.array([0.2, 0.2, 0.1, \n", - " 0.2, 0.2, 0.2, \n", - " 0.1, 0.2, 0.2])\n", + "initial_intertia = np.array([0.2, 0.05, 0.01, \n", + " 0.05, 0.2, 0.05, \n", + " 0.01, 0.05, 0.2])\n", "initial_damping = np.array([0.01, 0.01, 0.01,\n", " 0.01, 0.01, 0.01])\n", "initla_added_mass = np.array([0.02, 0.02, 0.02,\n", " 0.02, 0.02, 0.02])\n", "\n", "p_diag = np.concatenate([\n", - " 2*np.ones(3), # x position\n", - " 2*np.ones(3), # orientation\n", - " 2*np.ones(3), # velocity\n", - " 2*np.ones(3), # angular velocity\n", - " 2*np.ones(9), # inertia\n", - " 2*np.ones(6), # added mass\n", - " 2*np.ones(6), # damping\n", - " 2*np.ones(4) # g_eta\n", + " (0.8**2)*np.ones(3), # x position\n", + " (0.4**2)*np.ones(3), # orientation\n", + " (0.4**2)*np.ones(3), # velocity\n", + " (0.5**2)*np.ones(3), # angular velocity\n", + " 30*np.ones(9), # inertia\n", + " 30*np.ones(6), # added mass\n", + " 30*np.ones(6), # damping\n", + " 30*np.ones(4) # g_eta\n", "])\n", "\n", "initial_covariance = np.diag(p_diag) \n", @@ -70,12 +70,14 @@ "state.covariance = initial_covariance.copy()\n", "\n", "Q_diag = np.concatenate([\n", - " 0.1*np.ones(3), # position\n", - " 0.1*np.ones(9), # kinematic (η & ν)\n", - " 0.001*np.ones(9), # inertia\n", - " 0.001*np.ones(6), # added mass\n", - " 0.001*np.ones(6), # damping\n", - " 0.001*np.ones(4), # g_eta\n", + " (0.09**2)*np.ones(3), # position\n", + " (0.06**2)*np.ones(3), # kinematic (η & ν)\n", + " (0.06**2)*np.ones(3),\n", + " (0.06**2)*np.ones(3),\n", + " 0.000001*np.ones(9), # inertia\n", + " 0.000001*np.ones(6), # added mass\n", + " 0.000001*np.ones(6), # damping\n", + " 0.000001*np.ones(4), # g_eta\n", "])\n", "\n", "UKF_model = TUKF(state, np.diag(Q_diag)) # Process noise covariance\n", @@ -119,7 +121,7 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 4, "metadata": {}, "outputs": [], "source": [ @@ -162,7 +164,7 @@ "\n", " ang_measurement.measurement = np.dot(R_corr,measurement_imu)\n", "\n", - " ang_measurement.covariance = np.eye(3) * (0.03**2) \n", + " ang_measurement.covariance = np.eye(3) * (0.005**2) \n", "\n", " UKF_model.measurement_update(state, ang_measurement)\n", " state = UKF_model.posteriori_estimate(state, ang_measurement)\n", @@ -173,7 +175,7 @@ " msg = reader.deserialize(raw, conn.msgtype)\n", " dvl_measurement.measurement = np.array([msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z])\n", " \n", - " dvl_measurement.covariance = np.eye(3) * (0.01**2) \n", + " dvl_measurement.covariance = np.eye(3) * (0.005**2) \n", " \n", " # Update UKF with measurement\n", " UKF_model.measurement_update(state, dvl_measurement)\n", @@ -192,12 +194,12 @@ }, { "cell_type": "code", - "execution_count": 9, + "execution_count": 5, "metadata": {}, "outputs": [ { "data": { - "image/png": "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", + "image/png": "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", "text/plain": [ "
" ] @@ -231,7 +233,7 @@ "axs[1].grid(True)\n", "\n", "# Plot z position\n", - "axs[2].plot(z_positions, 'r-', linewidth=2)\n", + "axs[2].plot(z_positions, 'r-', linewidth=2) \n", "axs[2].set_ylabel('Z Position [m]')\n", "axs[2].set_xlabel('Time steps')\n", "axs[2].grid(True)\n", @@ -239,6 +241,104 @@ "plt.tight_layout(rect=[0, 0.03, 1, 0.95])\n", "plt.show()" ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Convert okid_params_est from list of arrays to a numpy array for easier handling\n", + "okid_params_array = np.array(okid_params_est)\n", + "\n", + "# Create labels for the different parameter groups\n", + "inertia_labels = ['Ixx', 'Ixy', 'Ixz', 'Iyx', 'Iyy', 'Iyz', 'Izx', 'Izy', 'Izz']\n", + "added_mass_labels = ['Xu', 'Yv', 'Zw', 'Kp', 'Mq', 'Nr']\n", + "damping_labels = ['Xu', 'Yv', 'Zw', 'Kp', 'Mq', 'Nr']\n", + "g_eta_labels = ['g_eta1', 'g_eta2', 'g_eta3', 'g_eta4']\n", + "\n", + "# Create figures for each parameter group\n", + "plt.figure(figsize=(14, 10))\n", + "plt.suptitle('Inertia Matrix Parameters', fontsize=16)\n", + "for i in range(9):\n", + " plt.subplot(3, 3, i+1)\n", + " plt.plot(okid_params_array[:, i], 'b-')\n", + " plt.title(inertia_labels[i])\n", + " plt.grid(True)\n", + "plt.tight_layout(rect=[0, 0.03, 1, 0.95])\n", + "plt.show()\n", + "\n", + "plt.figure(figsize=(14, 8))\n", + "plt.suptitle('Added Mass Parameters', fontsize=16)\n", + "for i in range(6):\n", + " plt.subplot(2, 3, i+1)\n", + " plt.plot(okid_params_array[:, 9+i], 'g-')\n", + " plt.title(f'Added Mass: {added_mass_labels[i]}')\n", + " plt.grid(True)\n", + "plt.tight_layout(rect=[0, 0.03, 1, 0.95])\n", + "plt.show()\n", + "\n", + "plt.figure(figsize=(14, 8))\n", + "plt.suptitle('Damping Parameters', fontsize=16)\n", + "for i in range(6):\n", + " plt.subplot(2, 3, i+1)\n", + " plt.plot(okid_params_array[:, 15+i], 'r-')\n", + " plt.title(f'Damping: {damping_labels[i]}')\n", + " plt.grid(True)\n", + "plt.tight_layout(rect=[0, 0.03, 1, 0.95])\n", + "plt.show()\n", + "\n", + "plt.figure(figsize=(14, 6))\n", + "plt.suptitle('G-Eta Parameters', fontsize=16)\n", + "for i in range(4):\n", + " plt.subplot(2, 2, i+1)\n", + " plt.plot(okid_params_array[:, 21+i], 'm-')\n", + " plt.title(g_eta_labels[i])\n", + " plt.grid(True)\n", + "plt.tight_layout(rect=[0, 0.03, 1, 0.95])\n", + "plt.show()" + ] } ], "metadata": { diff --git a/navigation/tukf/tukf_class.py b/navigation/tukf/tukf_class.py index e3ec138fb..ff274680e 100644 --- a/navigation/tukf/tukf_class.py +++ b/navigation/tukf/tukf_class.py @@ -311,7 +311,7 @@ def angular_velocity_transformation(euler_angles: np.ndarray) -> np.ndarray: return T def M_rb(inertia: np.ndarray) -> np.ndarray: - m = 30.0 + m = 25.5 inertia = inertia.reshape((3, 3)) r_b_bg = np.array([0.01, 0.0, 0.02]) M_rb = np.zeros((6, 6)) @@ -330,7 +330,7 @@ def M_a(added_mass: np.ndarray) -> np.ndarray: def C_rb(inertia: np.ndarray, angular_velocity: np.ndarray) -> np.ndarray: """Calculates the Coriolis matrix.""" - m = 30.0 + m = 25.5 r_b_bg = np.array([0.01, 0.0, 0.02]) inertia = inertia.reshape((3, 3)) C_rb = np.zeros((6, 6)) From 04751549ffe411162c67c28d4354e6269e8a312f Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Fri, 30 May 2025 19:18:16 +0200 Subject: [PATCH 23/30] added the cpp code --- navigation/eskf/config/eskf_params.yaml | 2 +- navigation/eskf/include/eskf/eskf_ros.hpp | 2 +- navigation/eskf/include/eskf/typedefs.hpp | 4 +- navigation/eskf/src/eskf.cpp | 43 +- navigation/eskf/src/eskf_ros.cpp | 8 + navigation/tukf/simulation.py | 155 --- navigation/tukf/simulation_re.ipynb | 365 -------- navigation/tukf/test_tukf.py | 347 ------- navigation/tukf/tukf.py | 126 --- navigation/tukf/tukf_class.py | 437 --------- navigation/tukf_rsi/CMakeLists.txt | 61 ++ .../tukf_rsi/config/tusk_rsi_params.yaml | 12 + .../tukf_rsi/include/tukf_rsi/tukf_rsi.hpp | 63 ++ .../include/tukf_rsi/tukf_rsi_model.hpp | 50 + .../include/tukf_rsi/tukf_rsi_ros.hpp | 64 ++ .../include/tukf_rsi/tukf_rsi_utils.hpp | 65 ++ .../tukf_rsi/include/tukf_rsi/typedefs.hpp | 145 +++ navigation/tukf_rsi/launch/tukf_rsi.launch.py | 22 + navigation/{ukf_okid => tukf_rsi}/package.xml | 14 +- navigation/tukf_rsi/src/tukf_rsi.cpp | 84 ++ navigation/tukf_rsi/src/tukf_rsi_model.cpp | 125 +++ navigation/tukf_rsi/src/tukf_rsi_node.cpp | 9 + navigation/tukf_rsi/src/tukf_rsi_ros.cpp | 150 +++ navigation/tukf_rsi/src/tukf_rsi_utils.cpp | 199 ++++ navigation/ukf_okid/CMakeLists.txt | 23 - navigation/ukf_okid/launch/ukf.launch.py | 12 - navigation/ukf_okid/ukf_python/__init__.py | 0 navigation/ukf_okid/ukf_python/ukf_okid.py | 130 --- .../ukf_okid/ukf_python/ukf_okid_class.py | 880 ------------------ navigation/ukf_okid/ukf_python/ukf_ros.py | 159 ---- navigation/ukf_okid/ukf_python/ukf_test.py | 27 - navigation/ukf_okid/ukf_python/ukf_test_2.py | 229 ----- navigation/ukf_okid/ukf_python/ukf_utils.py | 35 - 33 files changed, 1079 insertions(+), 2968 deletions(-) delete mode 100644 navigation/tukf/simulation.py delete mode 100644 navigation/tukf/simulation_re.ipynb delete mode 100644 navigation/tukf/test_tukf.py delete mode 100644 navigation/tukf/tukf.py delete mode 100644 navigation/tukf/tukf_class.py create mode 100644 navigation/tukf_rsi/CMakeLists.txt create mode 100644 navigation/tukf_rsi/config/tusk_rsi_params.yaml create mode 100644 navigation/tukf_rsi/include/tukf_rsi/tukf_rsi.hpp create mode 100644 navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_model.hpp create mode 100644 navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_ros.hpp create mode 100644 navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_utils.hpp create mode 100644 navigation/tukf_rsi/include/tukf_rsi/typedefs.hpp create mode 100644 navigation/tukf_rsi/launch/tukf_rsi.launch.py rename navigation/{ukf_okid => tukf_rsi}/package.xml (56%) create mode 100644 navigation/tukf_rsi/src/tukf_rsi.cpp create mode 100644 navigation/tukf_rsi/src/tukf_rsi_model.cpp create mode 100644 navigation/tukf_rsi/src/tukf_rsi_node.cpp create mode 100644 navigation/tukf_rsi/src/tukf_rsi_ros.cpp create mode 100644 navigation/tukf_rsi/src/tukf_rsi_utils.cpp delete mode 100644 navigation/ukf_okid/CMakeLists.txt delete mode 100644 navigation/ukf_okid/launch/ukf.launch.py delete mode 100644 navigation/ukf_okid/ukf_python/__init__.py delete mode 100644 navigation/ukf_okid/ukf_python/ukf_okid.py delete mode 100644 navigation/ukf_okid/ukf_python/ukf_okid_class.py delete mode 100755 navigation/ukf_okid/ukf_python/ukf_ros.py delete mode 100644 navigation/ukf_okid/ukf_python/ukf_test.py delete mode 100644 navigation/ukf_okid/ukf_python/ukf_test_2.py delete mode 100644 navigation/ukf_okid/ukf_python/ukf_utils.py diff --git a/navigation/eskf/config/eskf_params.yaml b/navigation/eskf/config/eskf_params.yaml index c08c21d3c..f17dcd3df 100644 --- a/navigation/eskf/config/eskf_params.yaml +++ b/navigation/eskf/config/eskf_params.yaml @@ -3,6 +3,6 @@ eskf_node: imu_topic: /imu/data_raw dvl_topic: /orca/twist odom_topic: odom - diag_Q_std: [0.01, 0.01, 0.01, 0.005, 0.005, 0.005, 0.00001, 0.00001, 0.00001, 0.00001, 0.00001, 0.00001] + diag_Q_std: [0.0124, 0.0124, 0.0124, 0.0026, 0.0026, 0.0026, 0.000392, 0.000392, 0.000392, 0.00001145, 0.0000145, 0.0000145] diag_p_init: [1.0, 1.0, 1.0, 0.5, 0.5, 0.5, 0.1, 0.1, 0.1, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] imu_frame: [0.0, 0.0, -1.0, 0.0, -1.0, 0.0, -1.0, 0.0, 0.0] diff --git a/navigation/eskf/include/eskf/eskf_ros.hpp b/navigation/eskf/include/eskf/eskf_ros.hpp index b10995f04..d4a770864 100644 --- a/navigation/eskf/include/eskf/eskf_ros.hpp +++ b/navigation/eskf/include/eskf/eskf_ros.hpp @@ -21,7 +21,7 @@ class ESKFNode : public rclcpp::Node { explicit ESKFNode(); private: - + // @brief Callback function for the imu topic // @param msg: Imu message containing the imu data void imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg); diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index eacb32841..4dbdb6da3 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -38,9 +38,9 @@ Eigen::Matrix createDiagonalMatrix( } struct state_quat { - Eigen::Vector3d pos = Eigen::Vector3d(0,0,0.125); + Eigen::Vector3d pos = Eigen::Vector3d(5.58, 0.66, 0.12); Eigen::Vector3d vel = Eigen::Vector3d::Zero(); - Eigen::Quaterniond quat = Eigen::Quaterniond::Identity(); + Eigen::Quaterniond quat = Eigen::Quaterniond(0.98, -0.047, 0.028, -0.18); Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero(); Eigen::Vector3d accel_bias = Eigen::Vector3d::Zero(); Eigen::Vector3d gravity = Eigen::Vector3d::Zero(); diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index 8d1fdb6b4..3838e2f1a 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -43,6 +43,7 @@ Eigen::Matrix4x3d ESKF::calculate_q_delta() { q_delta_theta *= 0.5; return q_delta_theta; } + Eigen::Matrix3x19d ESKF::calculate_hx() { Eigen::Matrix3x19d Hx = Eigen::Matrix3x19d::Zero(); @@ -51,43 +52,21 @@ Eigen::Matrix3x19d ESKF::calculate_hx() { Eigen::Vector3d v_n = current_nom_state_.vel; + // Correct derivative w.r.t velocity (nominal state: v_n) Hx.block<3, 3>(0, 3) = R_bn.transpose(); + // Derivative w.r.t quaternion (nominal state: q) + // Compute partial derivative w.r.t quaternion directly: double qw = q.w(); - double qx = q.x(); - double qy = q.y(); - double qz = q.z(); - + Eigen::Vector3d q_vec(q.x(), q.y(), q.z()); Eigen::Matrix3d I3 = Eigen::Matrix3d::Identity(); - Eigen::Vector3d eps(qx, qy, qz); - - Eigen::Matrix3d dR_deta = 2 * qw * I3 - 2 * skew(eps); - - Eigen::Vector3d e1_vec(1, 0, 0), e2_vec(0, 1, 0), e3_vec(0, 0, 1); - - Eigen::Matrix3d dR_dqx = - -2 * qx * I3 + - 2 * (e1_vec * eps.transpose() + eps * e1_vec.transpose()) - - 2 * qw * skew(e1_vec); + Eigen::Matrix dhdq; + dhdq.col(0) = 2*( qw*v_n + q_vec.cross(v_n) ); + dhdq.block<3,3>(0,1) = 2*( q_vec.dot(v_n)*I3 + q_vec*v_n.transpose() - v_n*q_vec.transpose() - qw*skew(v_n) ); - Eigen::Matrix3d dR_dqy = - -2 * qy * I3 + - 2 * (e2_vec * eps.transpose() + eps * e2_vec.transpose()) - - 2 * qw * skew(e2_vec); - - Eigen::Matrix3d dR_dqz = - -2 * qz * I3 + - 2 * (e3_vec * eps.transpose() + eps * e3_vec.transpose()) - - 2 * qw * skew(e3_vec); - - Eigen::Matrix dR_dq; - dR_dq.col(0) = dR_deta * v_n; - dR_dq.col(1) = dR_dqx * v_n; - dR_dq.col(2) = dR_dqy * v_n; - dR_dq.col(3) = dR_dqz * v_n; - - Hx.block<3, 4>(0, 6) = dR_dq; + // Assign quaternion derivative (3x4 block at columns 6:9) + Hx.block<3,4>(0,6) = dhdq; return Hx; } @@ -107,7 +86,7 @@ Eigen::Vector3d ESKF::calculate_h() { Eigen::Matrix3d R_bn = current_nom_state_.quat.normalized().toRotationMatrix().transpose(); h = R_bn * current_nom_state_.vel; - + //0.027293, 0.028089, 0.028089, 0.00255253, 0.00270035, 0.00280294, return h; } diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index cc4256c18..cfa85172e 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -128,6 +128,14 @@ void ESKFNode::publish_odom() { odom_msg.twist.twist.linear.y = nom_state_.vel.y(); odom_msg.twist.twist.linear.z = nom_state_.vel.z(); + // Add bias values to the angular velocity field of twist + odom_msg.twist.twist.angular.x = nom_state_.accel_bias.x(); + odom_msg.twist.twist.angular.y = nom_state_.accel_bias.y(); + odom_msg.twist.twist.angular.z = nom_state_.accel_bias.z(); + + // If you also want to include gyro bias, you could add it to the covariance + // matrix or publish a separate topic for biases + odom_msg.header.stamp = this->now(); odom_pub_->publish(odom_msg); } diff --git a/navigation/tukf/simulation.py b/navigation/tukf/simulation.py deleted file mode 100644 index 56fb2a6a1..000000000 --- a/navigation/tukf/simulation.py +++ /dev/null @@ -1,155 +0,0 @@ -from rosbags.highlevel import AnyReader -from rosbags.typesys import get_types_from_msg, register_types -import numpy as np, pandas as pd, pathlib -from tukf import TUKF -import tukf_class as ukf - -bag_folder = pathlib.Path(r"/home/talha/vortex_auv_ws/bags/sim_data_no_dvl") - -# Initialize UKF with StateQuat -initial_position = np.array([0.0, 0.0, 0.0]) # x, y, z -initial_velocity = np.array([0.0, 0.0, 0.0]) # vx, vy, vz -initial_quaternion = np.array([0.0, 0.0, 0.0]) # w, x, y, z (identity quaternion) -initial_angular_velocity = np.array([0.0, 0.0, 0.0]) # wx, wy, wz -initial_g_eta = np.array([0.01, 0.01, 0.01, 0.01]) # g_eta parameters -initial_intertia = np.array([0.2, 0.2, 0.1, - 0.2, 0.2, 0.2, - 0.1, 0.2, 0.2]) -initial_damping = np.array([0.01, 0.01, 0.01, - 0.01, 0.01, 0.01]) -initla_added_mass = np.array([0.02, 0.02, 0.02, - 0.02, 0.02, 0.02]) - -p_diag = np.concatenate([ - 2*np.ones(3), # x position - 2*np.ones(3), # orientation - 2*np.ones(3), # velocity - 2*np.ones(3), # angular velocity - 2*np.ones(9), # inertia - 2*np.ones(6), # added mass - 2*np.ones(6), # damping - 2*np.ones(4) # g_eta -]) - -initial_covariance = np.diag(p_diag) - -state = ukf.AUVState(initial_position.copy(), initial_quaternion.copy(), initial_velocity.copy(), initial_angular_velocity.copy(), - initial_intertia.copy(), initla_added_mass.copy(), initial_damping.copy(), initial_g_eta.copy()) - -state.covariance = initial_covariance.copy() - -Q_diag = np.concatenate([ - 0.1*np.ones(3), # position - 0.1*np.ones(9), # kinematic (η & ν) - 0.001*np.ones(9), # inertia - 0.001*np.ones(6), # added mass - 0.001*np.ones(6), # damping - 0.001*np.ones(4), # g_eta -]) - -UKF_model = TUKF(state, np.diag(Q_diag)) # Process noise covariance - -def dvl_h(state: ukf.AUVState) -> 'ukf.MeasModel': - H_matrix = np.zeros((3, 12)) - H_matrix[:, 6:9] = np.eye(3) - z_i = ukf.MeasModel() - z_i.measurement = np.dot(H_matrix, state.dynamic_part()) - return z_i - -dvl_measurement = ukf.MeasModel(H=dvl_h) - -def ang_h(state: ukf.AUVState) -> 'ukf.MeasModel': - H_matrix = np.zeros((3, 12)) - H_matrix[:, 9:12] = np.eye(3) - z_i = ukf.MeasModel() - z_i.measurement = np.dot(H_matrix, state.dynamic_part()) - return z_i - -ang_measurement = ukf.MeasModel(H=ang_h) - -R_corr = np.array([[0.0, 0.0, -1.0], - [0.0, -1.0, 0.0], - [-1.0, 0.0, 0.0]]) - -# Storage for trajectory -positions = [] -velocities = [] -quaternions = [] -angular_velocities = [] -okid_params = [] - -# Storage for trajectory estimates -positions_est = [] -velocities_est = [] -quaternions_est = [] -angular_velocities_est = [] -okid_params_est = [] - -with AnyReader([bag_folder]) as reader: - # Filter topics once - conns = [c for c in reader.connections - if c.topic in ("/imu/data_raw", "/dvl_twist", "/orca/wrench_input")] - - last_time = None - log = [] - coutner = 0 - - for conn, ts_raw, raw in reader.messages(conns): - t_ns = ts_raw # already nanoseconds integer - coutner += 1 - - if conn.topic == "/orca/wrench_input": - - # Get the wrench input message - msg = reader.deserialize(raw, conn.msgtype) - wrench = msg.wrench # Extract the wrench field from the message - forces = np.array([wrench.force.x, wrench.force.y, wrench.force.z]) - torques = np.array([wrench.torque.x, wrench.torque.y, wrench.torque.z]) - - control_input = np.concatenate([forces, torques]) - - if last_time is not None: - UKF_model.dt = (t_ns - last_time) / 1e9 # Convert nanoseconds to seconds - - # 1. prediction step - state = UKF_model.unscented_transform(state, control_input) - - # 2. measurement update - msg = reader.deserialize(raw, conn.msgtype) - if conn.topic == "/imu/data_raw": - print("IMU data received") - - # Get the IMU data - measurement_imu = np.array([msg.angular_velocity.x, msg.angular_velocity.y, msg.angular_velocity.z]) - - ang_measurement.measurement = np.dot(R_corr,measurement_imu) - - ang_measurement.covariance = np.eye(3) * (0.03**2) - - UKF_model.measurement_update(state, ang_measurement) - state = UKF_model.posteriori_estimate(state, ang_measurement) - - if conn.topic == "/dvl_twist": - print("DVL data received") - - msg = reader.deserialize(raw, conn.msgtype) - dvl_measurement.measurement = np.array([msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z]) - dvl_measurement.measurement = np.dot(R_corr, dvl_measurement.measurement) - - dvl_measurement.covariance = np.eye(3) * (0.01**2) - - # Update UKF with measurement - UKF_model.measurement_update(state, dvl_measurement) - state = UKF_model.posteriori_estimate(state, dvl_measurement) - - - # Store the state estimates - positions_est.append(state.position.copy()) - velocities_est.append(state.velocity.copy()) - quaternions_est.append(state.quaternion.copy()) - angular_velocities_est.append(state.angular_velocity.copy()) - okid_params_est.append(state.okid_part().copy()) - - last_time = t_ns - - \ No newline at end of file diff --git a/navigation/tukf/simulation_re.ipynb b/navigation/tukf/simulation_re.ipynb deleted file mode 100644 index 06f7369a6..000000000 --- a/navigation/tukf/simulation_re.ipynb +++ /dev/null @@ -1,365 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Simulation results for the TUKF ###\n", - "\n", - "try to simulate the path and parameters using the tukf algorithm" - ] - }, - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [], - "source": [ - "from rosbags.highlevel import AnyReader\n", - "from rosbags.typesys import get_types_from_msg, register_types\n", - "import numpy as np, pandas as pd, pathlib\n", - "from tukf import TUKF\n", - "import tukf_class as ukf" - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [], - "source": [ - "bag_folder = pathlib.Path(r\"/home/talha/vortex_auv_ws/bags/sim_data_no_dvl\")" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [], - "source": [ - "# Initialize UKF with StateQuat\n", - "initial_position = np.array([0.0, 0.0, 0.13]) # x, y, z\n", - "initial_velocity = np.array([0.0, 0.0, 0.0]) # vx, vy, vz\n", - "initial_quaternion = np.array([0.0, 0.0, 0.0]) # w, x, y, z (identity quaternion)\n", - "initial_angular_velocity = np.array([0.0, 0.0, 0.0]) # wx, wy, wz\n", - "initial_g_eta = np.array([0.01, 0.01, 0.01, 0.01]) # g_eta parameters\n", - "initial_intertia = np.array([0.2, 0.05, 0.01, \n", - " 0.05, 0.2, 0.05, \n", - " 0.01, 0.05, 0.2])\n", - "initial_damping = np.array([0.01, 0.01, 0.01,\n", - " 0.01, 0.01, 0.01])\n", - "initla_added_mass = np.array([0.02, 0.02, 0.02,\n", - " 0.02, 0.02, 0.02])\n", - "\n", - "p_diag = np.concatenate([\n", - " (0.8**2)*np.ones(3), # x position\n", - " (0.4**2)*np.ones(3), # orientation\n", - " (0.4**2)*np.ones(3), # velocity\n", - " (0.5**2)*np.ones(3), # angular velocity\n", - " 30*np.ones(9), # inertia\n", - " 30*np.ones(6), # added mass\n", - " 30*np.ones(6), # damping\n", - " 30*np.ones(4) # g_eta\n", - "])\n", - "\n", - "initial_covariance = np.diag(p_diag) \n", - "\n", - "state = ukf.AUVState(initial_position.copy(), initial_quaternion.copy(), initial_velocity.copy(), initial_angular_velocity.copy(), \n", - " initial_intertia.copy(), initla_added_mass.copy(), initial_damping.copy(), initial_g_eta.copy())\n", - "\n", - "state.covariance = initial_covariance.copy()\n", - "\n", - "Q_diag = np.concatenate([\n", - " (0.09**2)*np.ones(3), # position\n", - " (0.06**2)*np.ones(3), # kinematic (η & ν)\n", - " (0.06**2)*np.ones(3),\n", - " (0.06**2)*np.ones(3),\n", - " 0.000001*np.ones(9), # inertia\n", - " 0.000001*np.ones(6), # added mass\n", - " 0.000001*np.ones(6), # damping\n", - " 0.000001*np.ones(4), # g_eta\n", - "])\n", - "\n", - "UKF_model = TUKF(state, np.diag(Q_diag)) # Process noise covariance\n", - "\n", - "def dvl_h(state: ukf.AUVState) -> 'ukf.MeasModel':\n", - " H_matrix = np.zeros((3, 12))\n", - " H_matrix[:, 6:9] = np.eye(3)\n", - " z_i = ukf.MeasModel()\n", - " z_i.measurement = np.dot(H_matrix, state.dynamic_part())\n", - " return z_i\n", - "\n", - "dvl_measurement = ukf.MeasModel(H=dvl_h)\n", - "\n", - "def ang_h(state: ukf.AUVState) -> 'ukf.MeasModel':\n", - " H_matrix = np.zeros((3, 12))\n", - " H_matrix[:, 9:12] = np.eye(3)\n", - " z_i = ukf.MeasModel()\n", - " z_i.measurement = np.dot(H_matrix, state.dynamic_part())\n", - " return z_i\n", - "\n", - "ang_measurement = ukf.MeasModel(H=ang_h) \n", - "\n", - "R_corr = np.array([[0.0, 0.0, -1.0],\n", - " [0.0, -1.0, 0.0],\n", - " [-1.0, 0.0, 0.0]])\n", - "\n", - "# Storage for trajectory\n", - "positions = []\n", - "velocities = []\n", - "quaternions = []\n", - "angular_velocities = []\n", - "okid_params = []\n", - "\n", - "# Storage for trajectory estimates\n", - "positions_est = []\n", - "velocities_est = []\n", - "quaternions_est = []\n", - "angular_velocities_est = []\n", - "okid_params_est = []" - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [], - "source": [ - "with AnyReader([bag_folder]) as reader:\n", - " # Filter topics once\n", - " conns = [c for c in reader.connections\n", - " if c.topic in (\"/imu/data_raw\", \"/dvl_twist\", \"/orca/wrench_input\")]\n", - "\n", - " last_time = None\n", - " log = []\n", - " coutner = 0\n", - "\n", - " for conn, ts_raw, raw in reader.messages(conns):\n", - " t_ns = ts_raw # already nanoseconds integer\n", - " coutner += 1\n", - "\n", - " if conn.topic == \"/orca/wrench_input\":\n", - " \n", - " # Get the wrench input message\n", - " msg = reader.deserialize(raw, conn.msgtype)\n", - " wrench = msg.wrench # Extract the wrench field from the message\n", - " forces = np.array([wrench.force.x, wrench.force.y, wrench.force.z])\n", - " torques = np.array([wrench.torque.x, wrench.torque.y, wrench.torque.z])\n", - "\n", - " control_input = np.concatenate([forces, torques])\n", - "\n", - " if last_time is not None:\n", - " UKF_model.dt = (t_ns - last_time) / 1e9 # Convert nanoseconds to seconds\n", - "\n", - " # 1. prediction step\n", - " state = UKF_model.unscented_transform(state, control_input)\n", - "\n", - " # 2. measurement update\n", - " msg = reader.deserialize(raw, conn.msgtype)\n", - " if conn.topic == \"/imu/data_raw\":\n", - " # print(\"IMU data received\")\n", - "\n", - " # Get the IMU data\n", - " measurement_imu = np.array([msg.angular_velocity.x, msg.angular_velocity.y, msg.angular_velocity.z])\n", - "\n", - " ang_measurement.measurement = np.dot(R_corr,measurement_imu)\n", - "\n", - " ang_measurement.covariance = np.eye(3) * (0.005**2) \n", - "\n", - " UKF_model.measurement_update(state, ang_measurement)\n", - " state = UKF_model.posteriori_estimate(state, ang_measurement)\n", - "\n", - " if conn.topic == \"/dvl_twist\":\n", - " # print(\"DVL data received\")\n", - "\n", - " msg = reader.deserialize(raw, conn.msgtype)\n", - " dvl_measurement.measurement = np.array([msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z])\n", - " \n", - " dvl_measurement.covariance = np.eye(3) * (0.005**2) \n", - " \n", - " # Update UKF with measurement\n", - " UKF_model.measurement_update(state, dvl_measurement)\n", - " state = UKF_model.posteriori_estimate(state, dvl_measurement)\n", - "\n", - "\n", - " # Store the state estimates\n", - " positions_est.append(state.position.copy())\n", - " velocities_est.append(state.velocity.copy())\n", - " quaternions_est.append(state.orientation.copy())\n", - " angular_velocities_est.append(state.angular_velocity.copy())\n", - " okid_params_est.append(state.okid_part().copy())\n", - "\n", - " last_time = t_ns" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "import numpy as np\n", - "\n", - "import matplotlib.pyplot as plt\n", - "\n", - "# Extract x, y, z positions from positions_est\n", - "x_positions = np.array([pos[0] for pos in positions_est])\n", - "y_positions = np.array([pos[1] for pos in positions_est])\n", - "z_positions = np.array([pos[2] for pos in positions_est])\n", - "\n", - "# Create figure with three subplots\n", - "fig, axs = plt.subplots(3, 1, figsize=(12, 10), sharex=True)\n", - "fig.suptitle('AUV Position Estimates Over Time', fontsize=16)\n", - "\n", - "# Plot x position\n", - "axs[0].plot(x_positions, 'b-', linewidth=2)\n", - "axs[0].set_ylabel('X Position [m]')\n", - "axs[0].grid(True)\n", - "\n", - "# Plot y position\n", - "axs[1].plot(y_positions, 'g-', linewidth=2)\n", - "axs[1].set_ylabel('Y Position [m]')\n", - "axs[1].grid(True)\n", - "\n", - "# Plot z position\n", - "axs[2].plot(z_positions, 'r-', linewidth=2) \n", - "axs[2].set_ylabel('Z Position [m]')\n", - "axs[2].set_xlabel('Time steps')\n", - "axs[2].grid(True)\n", - "\n", - "plt.tight_layout(rect=[0, 0.03, 1, 0.95])\n", - "plt.show()" - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - }, - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - }, - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - }, - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Convert okid_params_est from list of arrays to a numpy array for easier handling\n", - "okid_params_array = np.array(okid_params_est)\n", - "\n", - "# Create labels for the different parameter groups\n", - "inertia_labels = ['Ixx', 'Ixy', 'Ixz', 'Iyx', 'Iyy', 'Iyz', 'Izx', 'Izy', 'Izz']\n", - "added_mass_labels = ['Xu', 'Yv', 'Zw', 'Kp', 'Mq', 'Nr']\n", - "damping_labels = ['Xu', 'Yv', 'Zw', 'Kp', 'Mq', 'Nr']\n", - "g_eta_labels = ['g_eta1', 'g_eta2', 'g_eta3', 'g_eta4']\n", - "\n", - "# Create figures for each parameter group\n", - "plt.figure(figsize=(14, 10))\n", - "plt.suptitle('Inertia Matrix Parameters', fontsize=16)\n", - "for i in range(9):\n", - " plt.subplot(3, 3, i+1)\n", - " plt.plot(okid_params_array[:, i], 'b-')\n", - " plt.title(inertia_labels[i])\n", - " plt.grid(True)\n", - "plt.tight_layout(rect=[0, 0.03, 1, 0.95])\n", - "plt.show()\n", - "\n", - "plt.figure(figsize=(14, 8))\n", - "plt.suptitle('Added Mass Parameters', fontsize=16)\n", - "for i in range(6):\n", - " plt.subplot(2, 3, i+1)\n", - " plt.plot(okid_params_array[:, 9+i], 'g-')\n", - " plt.title(f'Added Mass: {added_mass_labels[i]}')\n", - " plt.grid(True)\n", - "plt.tight_layout(rect=[0, 0.03, 1, 0.95])\n", - "plt.show()\n", - "\n", - "plt.figure(figsize=(14, 8))\n", - "plt.suptitle('Damping Parameters', fontsize=16)\n", - "for i in range(6):\n", - " plt.subplot(2, 3, i+1)\n", - " plt.plot(okid_params_array[:, 15+i], 'r-')\n", - " plt.title(f'Damping: {damping_labels[i]}')\n", - " plt.grid(True)\n", - "plt.tight_layout(rect=[0, 0.03, 1, 0.95])\n", - "plt.show()\n", - "\n", - "plt.figure(figsize=(14, 6))\n", - "plt.suptitle('G-Eta Parameters', fontsize=16)\n", - "for i in range(4):\n", - " plt.subplot(2, 2, i+1)\n", - " plt.plot(okid_params_array[:, 21+i], 'm-')\n", - " plt.title(g_eta_labels[i])\n", - " plt.grid(True)\n", - "plt.tight_layout(rect=[0, 0.03, 1, 0.95])\n", - "plt.show()" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.10.12" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/navigation/tukf/test_tukf.py b/navigation/tukf/test_tukf.py deleted file mode 100644 index 2998855ea..000000000 --- a/navigation/tukf/test_tukf.py +++ /dev/null @@ -1,347 +0,0 @@ -import numpy as np -from tukf import TUKF -import tukf_class as ukf -from mpl_toolkits.mplot3d import Axes3D -import time -import math - -import matplotlib.pyplot as plt - -# Initialize UKF with StateQuat -initial_position = np.array([0.0, 0.0, 0.0]) # x, y, z -initial_velocity = np.array([0.0, 0.0, 0.0]) # vx, vy, vz -initial_quaternion = np.array([0.0, 0.0, 0.0]) # w, x, y, z (identity quaternion) -initial_angular_velocity = np.array([0.0, 0.0, 0.0]) # wx, wy, wz -initial_g_eta = np.array([1.2, 0.3, 0.3, 0.3]) # g_eta parameters -initial_intertia = np.array([0.68, 0.2, 0.1, - 0.2, 3.32, 0.2, - 0.1, 0.2, 3.34]) -initial_damping = np.array([0.01, 0.01, 0.01, - 0.01, 0.01, 0.01]) -initla_added_mass = np.array([0.02, 0.02, 0.02, - 0.02, 0.02, 0.02]) - -p_diag = np.concatenate([ - 2*np.ones(3), # x position - 2*np.ones(3), # orientation - 2*np.ones(3), # velocity - 2*np.ones(3), # angular velocity - 2*np.ones(9), # inertia - 2*np.ones(6), # added mass - 2*np.ones(6), # damping - 2*np.ones(4) # g_eta -]) - -initial_covariance = np.diag(p_diag) - -state = ukf.AUVState(initial_position.copy(), initial_quaternion.copy(), initial_velocity.copy(), initial_angular_velocity.copy()) -state.covariance = initial_covariance.copy() -state.inertia = np.array([0.58, 0.1, 0.05, - 0.1, 2.32, 0.1, - 0.01, 0.1, 2.34]) -state.g_eta = np.array([1.1, 0.1, 0.1, 0.1]) -state.damping = np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0]) -state.added_mass = np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0]) - -real_state = ukf.AUVState(initial_position.copy(), initial_quaternion.copy(), initial_velocity.copy(), initial_angular_velocity.copy()) -real_state.inertia = initial_intertia.copy() -real_state.g_eta = initial_g_eta.copy() -real_state.damping = initial_damping.copy() -real_state.added_mass = initla_added_mass.copy() - -Q_diag = np.concatenate([ - 0.01*np.ones(3), # position - 0.2*np.ones(9), # kinematic (η & ν) - 0.8*np.ones(9), # inertia - 0.8*np.ones(6), # added mass - 0.8*np.ones(6), # damping - 0.8*np.ones(4), # g_eta -]) - -UKF_model = TUKF(state, np.diag(Q_diag)) # Process noise covariance - -def dvl_h(state: ukf.AUVState) -> 'ukf.MeasModel': - H_matrix = np.zeros((3, 12)) - H_matrix[:, 6:9] = np.eye(3) - z_i = ukf.MeasModel() - z_i.measurement = np.dot(H_matrix, state.dynamic_part()) - return z_i - -dvl_measurement = ukf.MeasModel(H=dvl_h) - -def ang_h(state: ukf.AUVState) -> 'ukf.MeasModel': - H_matrix = np.zeros((3, 12)) - H_matrix[:, 9:12] = np.eye(3) - z_i = ukf.MeasModel() - z_i.measurement = np.dot(H_matrix, state.dynamic_part()) - return z_i - -ang_measurement = ukf.MeasModel(H=ang_h) - -# UKF parameters -dt = 0.01 # time step -sim_time = 50.0 # total simulation time -steps = int(sim_time / dt) - -# Storage for trajectory -positions = np.zeros((steps, 3)) -velocities = np.zeros((steps, 3)) -quaternions = np.zeros((steps, 3)) -angular_velocities = np.zeros((steps, 3)) -okid_params = np.zeros((steps, 25)) - -# Storage for trajectory -positions_est = np.zeros((steps, 3)) -velocities_est = np.zeros((steps, 3)) -quaternions_est = np.zeros((steps, 3)) -angular_velocities_est = np.zeros((steps, 3)) -okid_params_est = np.zeros((steps, 25)) - -# ---------- user‑tunable manoeuvre parameters ----------------------------- -SEG_DUR = 10.0 # [s] duration of each phase -A_F_TRANSL = 2.0 # [N] translational force amplitude -A_T_ROT = 1.0 # [N·m] rotational torque amplitude -# -------------------------------------------------------------------------- - -# Helper: build the scripted sequence as (kind, axis_idx, sign) -# kind = 'F' for force, 'T' for torque -# axes: 0‑x (surge/roll), 1‑y (sway/pitch), 2‑z (heave/yaw) -sequence = [ - ('F', 2, +1), # +z (up) - ('F', 2, -1), # –z (down) - ('F', 1, +1), # +y (right) - ('F', 1, -1), # –y (left / “back” sideways) - ('F', 0, +1), # +x (forward) - ('F', 0, -1), # –x (backward) - ('T', 2, +1), # +yaw (turn right) - ('T', 2, -1), # –yaw (turn left) - ('T', 1, +1), # +pitch (nose up) - ('T', 1, -1), # –pitch (nose down) - ('T', 0, +1), # +roll (starboard roll) - ('T', 0, -1) # –roll (port roll) -] - -TOTAL_TIME = len(sequence) * SEG_DUR # handy if you need it - -def _half_sine(local_t: float, duration: float) -> float: - """Smooth window: 0 → 1 → 0 over `duration` (half‑sine).""" - return np.sin(np.pi * local_t / duration) - -def control_inputs(t: float) -> tuple[np.ndarray, np.ndarray]: - """ - Piecewise scripted test signal: - – translations along z, y, x - – rotations about z (yaw), y (pitch), x (roll) - """ - # Default: no actuation - F = np.zeros(3) - T = np.zeros(3) - - # Past the last segment? keep everything zero - idx = int(t // SEG_DUR) - if idx >= len(sequence): - return F, T - - # Time inside current segment - tau = t - idx * SEG_DUR - window = _half_sine(tau, SEG_DUR) # 0‑to‑1‑to‑0 shape - - kind, axis, sgn = sequence[idx] - - if kind == 'F': - F[axis] = sgn * A_F_TRANSL * window - else: # 'T' - T[axis] = sgn * A_T_ROT * window - - return F, T - -# Simulation loop -for i in range(steps): - t = i * dt - - control_force, control_torque = control_inputs(t) - - control_input = np.concatenate((control_force, control_torque)) - - # Propagate state using UKF prediction - real_state = ukf.F_dynamics(real_state, dt, control_input) - state = UKF_model.unscented_transform(state, control_input) - - if UKF_model.filter_failed: - print("Filter failed, stopping simulation.") - break - - if i % 5 == 0: - # Simulate measurement update every 5 steps - ang_measurement.measurement = np.array([ - real_state.angular_velocity[0], - real_state.angular_velocity[1], - real_state.angular_velocity[2] - ]) + np.random.normal(0, 0.04, 3) - - ang_measurement.covariance = np.eye(3) * (0.03**2) # Measurement noise covariance - - UKF_model.measurement_update(state, ang_measurement) - state = UKF_model.posteriori_estimate(state, ang_measurement) - - if i % 10 == 0: - # Simulate measurement update every 10 steps - dvl_measurement.measurement = np.array([ - real_state.velocity[0], - real_state.velocity[1], - real_state.velocity[2] - ]) + np.random.normal(0, 0.04, 3) # Simulated measurement with noise - - # Simulate measurement covariance - dvl_measurement.covariance = np.eye(3) * (0.03**2) # Measurement noise covariance - - # Update UKF with measurement - UKF_model.measurement_update(state, dvl_measurement) - state = UKF_model.posteriori_estimate(state, dvl_measurement) - - # Store state for plotting - positions[i] = real_state.position - velocities[i] = real_state.velocity - quaternions[i] = real_state.orientation - angular_velocities[i] = real_state.angular_velocity - okid_params[i] = real_state.okid_part() - - # Store estimated state for plotting - positions_est[i] = state.position - velocities_est[i] = state.velocity - quaternions_est[i] = state.orientation - angular_velocities_est[i] = state.angular_velocity - okid_params_est[i] = state.okid_part() - - # Add small delay to simulate real-time execution - time.sleep(0.001) -print(state.as_vector()) -# Plotting -time_points = np.arange(0, sim_time, dt) - -# 3D trajectory plot -fig = plt.figure(figsize=(12, 10)) -ax = fig.add_subplot(111, projection='3d') -ax.plot(positions[:, 0], positions[:, 1], positions[:, 2], 'b-', label='True Trajectory') -ax.plot(positions_est[:, 0], positions_est[:, 1], positions_est[:, 2], 'r--', label='Estimated Trajectory') -ax.scatter(positions[0, 0], positions[0, 1], positions[0, 2], c='g', marker='o', s=100, label='Start') -ax.scatter(positions[-1, 0], positions[-1, 1], positions[-1, 2], c='r', marker='o', s=100, label='End') -ax.set_xlabel('X Position') -ax.set_ylabel('Y Position') -ax.set_zlabel('Z Position') -ax.set_title('3D Trajectory') -ax.legend() - -# Position plot -plt.figure(figsize=(12, 6)) -plt.subplot(311) -plt.plot(time_points, positions[:, 0], 'b-', label='True') -plt.plot(time_points, positions_est[:, 0], 'r--', label='Estimated') -plt.ylabel('X Position') -plt.legend() -plt.subplot(312) -plt.plot(time_points, positions[:, 1], 'b-', label='True') -plt.plot(time_points, positions_est[:, 1], 'r--', label='Estimated') -plt.ylabel('Y Position') -plt.legend() -plt.subplot(313) -plt.plot(time_points, positions[:, 2], 'b-', label='True') -plt.plot(time_points, positions_est[:, 2], 'r--', label='Estimated') -plt.ylabel('Z Position') -plt.xlabel('Time (s)') -plt.legend() -plt.tight_layout() - -# Velocity plot -plt.figure(figsize=(12, 6)) -plt.subplot(311) -plt.plot(time_points, velocities[:, 0], 'b-', label='True') -plt.plot(time_points, velocities_est[:, 0], 'r--', label='Estimated') -plt.ylabel('X Velocity') -plt.legend() -plt.subplot(312) -plt.plot(time_points, velocities[:, 1], 'b-', label='True') -plt.plot(time_points, velocities_est[:, 1], 'r--', label='Estimated') -plt.ylabel('Y Velocity') -plt.legend() -plt.subplot(313) -plt.plot(time_points, velocities[:, 2], 'b-', label='True') -plt.plot(time_points, velocities_est[:, 2], 'r--', label='Estimated') -plt.ylabel('Z Velocity') -plt.xlabel('Time (s)') -plt.legend() -plt.tight_layout() - -# Angular velocity plot -plt.figure(figsize=(12, 6)) -plt.subplot(311) -plt.plot(time_points, angular_velocities[:, 0], 'b-', label='True') -plt.plot(time_points, angular_velocities_est[:, 0], 'r--', label='Estimated') -plt.ylabel('Roll Rate') -plt.legend() -plt.subplot(312) -plt.plot(time_points, angular_velocities[:, 1], 'b-', label='True') -plt.plot(time_points, angular_velocities_est[:, 1], 'r--', label='Estimated') -plt.ylabel('Pitch Rate') -plt.legend() -plt.subplot(313) -plt.plot(time_points, angular_velocities[:, 2], 'b-', label='True') -plt.plot(time_points, angular_velocities_est[:, 2], 'r--', label='Estimated') -plt.ylabel('Yaw Rate') -plt.xlabel('Time (s)') -plt.legend() -plt.tight_layout() - -# OKID Inertia parameters plot (9 parameters) -plt.figure(figsize=(15, 10)) -plt.suptitle('Inertia Parameters', fontsize=16) -for i in range(9): - plt.subplot(3, 3, i+1) - plt.plot(time_points, okid_params[:, i], 'b-', label='True') - plt.plot(time_points, okid_params_est[:, i], 'r--', label='Estimated') - plt.ylabel(f'Inertia[{i}]') - if i >= 6: # Add x-label only to bottom row - plt.xlabel('Time (s)') - plt.legend() -plt.tight_layout(rect=[0, 0, 1, 0.96]) # Adjust for suptitle - -# OKID Added Mass parameters plot (6 parameters) -plt.figure(figsize=(15, 8)) -plt.suptitle('Added Mass Parameters', fontsize=16) -for i in range(6): - plt.subplot(2, 3, i+1) - plt.plot(time_points, okid_params[:, i+9], 'b-', label='True') - plt.plot(time_points, okid_params_est[:, i+9], 'r--', label='Estimated') - plt.ylabel(f'Added Mass[{i}]') - if i >= 3: # Add x-label only to bottom row - plt.xlabel('Time (s)') - plt.legend() -plt.tight_layout(rect=[0, 0, 1, 0.96]) # Adjust for suptitle - -# OKID Damping parameters plot (6 parameters) -plt.figure(figsize=(15, 8)) -plt.suptitle('Damping Parameters', fontsize=16) -for i in range(6): - plt.subplot(2, 3, i+1) - plt.plot(time_points, okid_params[:, i+15], 'b-', label='True') - plt.plot(time_points, okid_params_est[:, i+15], 'r--', label='Estimated') - plt.ylabel(f'Damping[{i}]') - if i >= 3: # Add x-label only to bottom row - plt.xlabel('Time (s)') - plt.legend() -plt.tight_layout(rect=[0, 0, 1, 0.96]) # Adjust for suptitle - -# OKID g_eta parameters plot (4 parameters) -plt.figure(figsize=(12, 8)) -plt.suptitle('g_eta Parameters', fontsize=16) -for i in range(4): - plt.subplot(2, 2, i+1) - plt.plot(time_points, okid_params[:, i+21], 'b-', label='True') - plt.plot(time_points, okid_params_est[:, i+21], 'r--', label='Estimated') - plt.ylabel(f'g_eta[{i}]') - plt.xlabel('Time (s)') - plt.legend() -plt.tight_layout(rect=[0, 0, 1, 0.96]) # Adjust for suptitle - -plt.show() - diff --git a/navigation/tukf/tukf.py b/navigation/tukf/tukf.py deleted file mode 100644 index a4badd887..000000000 --- a/navigation/tukf/tukf.py +++ /dev/null @@ -1,126 +0,0 @@ -import numpy as np -from tukf_class import ( - MeasModel, - AUVState, - covariance_measurement, - covariance_set, - cross_covariance, - mean_measurement, - mean_set, - F_dynamics, - generate_delta_matrix, -) - -def print_matrix(matrix, name="Matrix"): - """Custom print function to print matrices in a formatted form.""" - print(f"{name}: {matrix.shape}") - if isinstance(matrix, np.ndarray): - for row in matrix: - print(" ".join(f"{val:.2f}" for val in row)) - else: - print(matrix) - -class TUKF: - def __init__(self, x_0: AUVState, Q): - self.x = x_0 - self.Q = Q - self.delta = generate_delta_matrix(len(x_0.as_vector())) / np.sqrt(len(x_0.as_vector())) - self.sigma_points_list = None - self.measurement_updated = MeasModel() - self.dt = 0.01 # Time step for dynamics - self.flagg = 0 - self.filter_failed = False - - def sigma_points(self, current_state: AUVState) -> list[AUVState]: - """Functions that generate the sigma points for the UKF.""" - n = len(current_state.covariance) - self.flagg += 1 - try: - S = np.linalg.cholesky(current_state.covariance) - except np.linalg.LinAlgError: - print("Cholesky decomposition failed!") - print("flagg", self.flagg) - print_matrix(current_state.covariance, "Current State Covariance") - print_matrix(self.Q, "Process Noise Covariance (Q)") - - # Set flag to indicate filter has failed - self.filter_failed = True - - # Create a valid but minimal S matrix to avoid crashing - # This allows the simulation to continue to the next step where it can be checked - S = np.eye(n) * 1e-6 - - self.sigma_points_list = [AUVState() for _ in range(2 * n)] - - for index, state in enumerate(self.sigma_points_list): - state.fill_states(current_state.as_vector() + S @ self.delta[:, index]) - - return self.sigma_points_list - - def unscented_transform(self, current_state: AUVState, control_force: np.ndarray) -> AUVState: - """The unscented transform function generates the priori state estimate.""" - self.sigma_points(current_state) - n = len(current_state.covariance) - - self.y_i = [AUVState() for _ in range(2 * n)] - - for i, sp in enumerate(self.sigma_points_list): - self.y_i[i] = F_dynamics(sp, self.dt, control_force) - - state_estimate = AUVState() - x = mean_set(self.y_i) - - state_estimate.fill_states(x) - state_estimate.covariance = covariance_set(self.y_i, x) + + self.Q - return state_estimate - - def measurement_update( - self, current_state: AUVState, measurement: MeasModel - ) -> None: - """Function that updates the state estimate with a measurement. - - Hopefully this is the DVL or GNSS - """ - n = len(current_state.covariance) - z_i = [MeasModel() for _ in range(2 * n)] - - for i, state in enumerate(self.y_i): - z_i[i] = measurement.H(state) - - self.measurement_updated.measurement = mean_measurement(z_i) - - self.measurement_updated.covariance = covariance_measurement( - z_i, self.measurement_updated.measurement - ) - - self.cross_correlation = cross_covariance( - self.y_i, - current_state.as_vector(), - z_i, - self.measurement_updated.measurement, - ) - - def posteriori_estimate( - self, - current_state: AUVState, - measurement: MeasModel, - ) -> AUVState: - """Calculates the posteriori estimate using measurement and the prior estimate.""" - nu_k = MeasModel() - nu_k.measurement = ( - measurement.measurement - self.measurement_updated.measurement - ) - nu_k.covariance = self.measurement_updated.covariance + measurement.covariance - - K_k = np.dot(self.cross_correlation, np.linalg.inv(nu_k.covariance)) - - posteriori_estimate = AUVState() - - posteriori_estimate.fill_states( - current_state.as_vector() + np.dot(K_k, nu_k.measurement) - ) - posteriori_estimate.covariance = current_state.covariance - np.dot( - K_k, np.dot(nu_k.covariance, np.transpose(K_k)) - ) - - return posteriori_estimate diff --git a/navigation/tukf/tukf_class.py b/navigation/tukf/tukf_class.py deleted file mode 100644 index ff274680e..000000000 --- a/navigation/tukf/tukf_class.py +++ /dev/null @@ -1,437 +0,0 @@ -import numpy as np -from dataclasses import dataclass, field -from typing import Callable - -@dataclass -class AUVState: - position: np.ndarray = field(default_factory=lambda: np.zeros(3)) - orientation: np.ndarray = field(default_factory=lambda: np.array(3)) - velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) - angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) - inertia: np.ndarray = field(default_factory=lambda: np.zeros((9))) - added_mass: np.ndarray = field(default_factory=lambda: np.zeros((6))) - damping: np.ndarray = field(default_factory=lambda: np.zeros((6))) - g_eta: np.ndarray = field(default_factory=lambda: np.zeros((4))) - covariance: np.ndarray = field(default_factory=lambda: np.zeros((37, 37))) - - def dynamic_part(self) -> np.ndarray: - """Get the dynamic part of the AUV state.""" - return np.concatenate([ - self.position, - self.orientation, - self.velocity, - self.angular_velocity - ]) - def okid_part(self) -> np.ndarray: - """Get the OKID part of the AUV state.""" - return np.concatenate([ - self.inertia, - self.added_mass, - self.damping, - self.g_eta - ]) - def as_vector(self) -> np.ndarray: - """Convert the AUV state to a vector representation.""" - return np.concatenate([ - self.position, - self.orientation, - self.velocity, - self.angular_velocity, - self.inertia.flatten(), - self.added_mass.flatten(), - self.damping.flatten(), - self.g_eta - ]) - - def __add__(self, other: 'AUVState') -> 'AUVState': - """Add two AUV states together.""" - return AUVState( - position=self.position + other.position, - orientation=self.orientation + other.orientation, - velocity=self.velocity + other.velocity, - angular_velocity=self.angular_velocity + other.angular_velocity, - inertia=self.inertia + other.inertia, - added_mass=self.added_mass + other.added_mass, - damping=self.damping + other.damping, - g_eta=self.g_eta + other.g_eta - ) - def __sub__(self, other: 'AUVState') -> 'AUVState': - """Subtract two AUV states.""" - return AUVState( - position=self.position - other.position, - orientation=self.orientation - other.orientation, - velocity=self.velocity - other.velocity, - angular_velocity=self.angular_velocity - other.angular_velocity, - inertia=self.inertia - other.inertia, - added_mass=self.added_mass - other.added_mass, - damping=self.damping - other.damping, - g_eta=self.g_eta - other.g_eta - ) - def fill_states(self, x: np.ndarray) -> None: - """Fill the AUV state with a vector representation.""" - self.position = x[0:3] - self.orientation = x[3:6] - self.velocity = x[6:9] - self.angular_velocity = x[9:12] - self.inertia = x[12:21] - self.added_mass = x[21:27] - self.damping = x[27:33] - self.g_eta = x[33:37] - - -@dataclass -class MeasModel: - """A class defined for a general measurement model.""" - measurement: np.ndarray = field(default_factory=lambda: np.zeros(3)) - covariance: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) - H: Callable[["AUVState"], "MeasModel"] | None = None - - def __post_init__(self): - """Initialize H with a default measurement function if none provided.""" - if self.H is None: - self.H = self._default_H - - def _default_H(self, state: AUVState) -> 'MeasModel': - """Default measurement function that returns velocity.""" - H_matrix = np.zeros((3, 12)) - H_matrix[:, 6:9] = np.eye(3) - z_i = MeasModel() - z_i.measurement = np.dot(H_matrix, state.dynamic_part()) - return z_i - - def __add__(self, other: 'MeasModel') -> 'MeasModel': - """Defines the addition operation between two MeasModel objects.""" - result = MeasModel() - result.measurement = self.measurement + other.measurement - return result - - def __rmul__(self, scalar: float) -> 'MeasModel': - """Defines multiplication between scalar value and MeasModel object.""" - result = MeasModel() - result.measurement = scalar * self.measurement - return result - - def __sub__(self, other: 'MeasModel') -> 'MeasModel': - """Defines the subtraction between two MeasModel objects.""" - result = MeasModel() - result.measurement = self.measurement - other.measurement - return result - -def generate_delta_matrix_2(n: float) -> np.ndarray: - """Generates the weight matrix used in the TUKF sigma point generation. - - Parameters: - n (int): The state dimension. - - Returns: - delta (np.ndarray): An n x 2n orthonormal transformation matrix used to generate TUKF sigma points. - """ - delta = np.zeros((n, 2 * n)) - k = 0.001 # Tuning parameter to ensure pos def - - for i in range(2 * n): - for j in range(n // 2): - delta[2 * j + 1, i] = ( - np.sqrt(2) * np.sin(2 * j - 1) * ((k * np.pi) / n) - ) - delta[2 * j, i] = np.sqrt(2) * np.cos(2 * j - 1) * ((k * np.pi) / n) - - if (n % 2) == 1: - delta[n - 1, i] = np.sqrt(2) * np.cos(2 * j - 1) * ((k * np.pi) / n) - - return delta - -def generate_delta_matrix(n: int) -> np.ndarray: - if n < 1: - raise ValueError("n must be a positive integer") - - delta = np.zeros((n, 2 * n)) - r_max = n // 2 # floor(n/2) - sq2 = np.sqrt(2.0) - - for k in range(1, 2 * n + 1): # k = 1 … 2n - for r in range(1, r_max + 1): - row_cos = 2 * r - 2 # 0‑based index for γ_{k,2r‑1} - row_sin = 2 * r - 1 # 0‑based index for γ_{k,2r} - angle = (2 * r - 1) * k * np.pi / n - delta[row_cos, k - 1] = sq2 * np.cos(angle) - delta[row_sin, k - 1] = sq2 * np.sin(angle) - - if n % 2 == 1: # extra entry when n is odd - delta[n - 1, k - 1] = (-1) ** k - - return delta - -def skew_symmetric(vector: np.ndarray) -> np.ndarray: - """Calculates the skew symmetric matrix of a vector. - - Args: - vector (np.ndarray): The vector. - - Returns: - np.ndarray: The skew symmetric matrix. - """ - return np.array( - [ - [0, -vector[2], vector[1]], - [vector[2], 0, -vector[0]], - [-vector[1], vector[0], 0], - ] - ) - -def mean_set(set_points: list[AUVState]) -> np.ndarray: - """Function calculates the mean vector of a set of points. - - Args: - set_points (list[AUVState]): List of AUVState objects - - Returns: - np.ndarray: The mean vector - """ - n = len(set_points) - mean_value = np.zeros(set_points[0].as_vector().shape) - - for state in set_points: - mean_value = mean_value + state.as_vector() - - mean_value = (1 / n) * mean_value - - return mean_value - - -def mean_measurement(set_points: list[MeasModel]) -> np.ndarray: - """Function that calculates the mean of a set of points.""" - n = len(set_points) - mean_value = MeasModel() - - for state in set_points: - mean_value = mean_value + state - - mean_value = (1 / n) * mean_value - - return mean_value.measurement - - -def covariance_set(set_points: list[AUVState], mean: np.ndarray) -> np.ndarray: - """Function that calculates the covariance of a set of points.""" - n = len(set_points) - covariance = np.zeros(set_points[0].covariance.shape) - - for state in set_points: - W_i = state.as_vector() - mean - - covariance += np.outer(W_i, W_i) - - covariance = (1 / n) * covariance - - return covariance - - -def covariance_measurement(set_points: list[MeasModel], mean: np.ndarray) -> np.ndarray: - """Function that calculates the covariance of a set of points.""" - n = len(set_points) - co_size = len(set_points[0].measurement) - covariance = np.zeros((co_size, co_size)) - - mean_meas = MeasModel() - mean_meas.measurement = mean - - for state in set_points: - temp_state = state - mean_meas - covariance += np.outer(temp_state.measurement, temp_state.measurement) - - covariance = (1 / n) * covariance - - return covariance - - -def cross_covariance( - set_y: list[AUVState], - mean_y: np.ndarray, - set_z: list[MeasModel], - mean_z: np.ndarray, -) -> np.ndarray: - """Calculates the cross covariance between the measurement and state prediction.""" - n = len(set_y) - - cross_covariance = np.zeros((len(mean_y), len(mean_z))) - - for i in range(n): - state_diff = set_y[i].as_vector() - mean_y - meas_diff = set_z[i].measurement - mean_z - - cross_covariance += np.outer(state_diff, meas_diff) - - cross_covariance = (1 / n) * cross_covariance - - return cross_covariance - - -# ----------------------------------------------------------- - -def rotation_matrix(euler_angles: np.ndarray) -> np.ndarray: - """Calculates the rotation matrix from Euler angles (roll, pitch, yaw).""" - roll, pitch, yaw = euler_angles - - # Roll rotation - Rx = np.array([ - [1, 0, 0], - [0, np.cos(roll), -np.sin(roll)], - [0, np.sin(roll), np.cos(roll)] - ]) - - # Pitch rotation - Ry = np.array([ - [np.cos(pitch), 0, np.sin(pitch)], - [0, 1, 0], - [-np.sin(pitch), 0, np.cos(pitch)] - ]) - - # Yaw rotation - Rz = np.array([ - [np.cos(yaw), -np.sin(yaw), 0], - [np.sin(yaw), np.cos(yaw), 0], - [0, 0, 1] - ]) - - # Complete rotation matrix - R = Rz @ Ry @ Rx - return R - -def angular_velocity_transformation(euler_angles: np.ndarray) -> np.ndarray: - """Transformation matrix relating Euler rates to angular velocities.""" - roll, pitch, yaw = euler_angles - - T = np.array([ - [1, 0, -np.sin(pitch)], - [0, np.cos(roll), np.cos(pitch) * np.sin(roll)], - [0, -np.sin(roll), np.cos(pitch) * np.cos(roll)] - ]) - - return T - -def M_rb(inertia: np.ndarray) -> np.ndarray: - m = 25.5 - inertia = inertia.reshape((3, 3)) - r_b_bg = np.array([0.01, 0.0, 0.02]) - M_rb = np.zeros((6, 6)) - M_rb[0:3, 0:3] = m * np.eye(3) - M_rb[3:6, 3:6] = inertia - M_rb[0:3, 3:6] = -m * skew_symmetric(r_b_bg) - M_rb[3:6, 0:3] = m * skew_symmetric(r_b_bg) - return M_rb - -def M_a(added_mass: np.ndarray) -> np.ndarray: - """Calculates the added mass matrix.""" - M_a = np.zeros((6, 6)) - M_a[0:3, 0:3] = np.diag(added_mass[0:3]) - M_a[3:6, 3:6] = np.diag(added_mass[3:6]) - return M_a - -def C_rb(inertia: np.ndarray, angular_velocity: np.ndarray) -> np.ndarray: - """Calculates the Coriolis matrix.""" - m = 25.5 - r_b_bg = np.array([0.01, 0.0, 0.02]) - inertia = inertia.reshape((3, 3)) - C_rb = np.zeros((6, 6)) - - C_rb[0:3, 0:3] = m * skew_symmetric(angular_velocity) - C_rb[3:6, 3:6] = -skew_symmetric(np.dot(inertia, angular_velocity)) - C_rb[0:3, 3:6] = -m * skew_symmetric(angular_velocity) @ skew_symmetric(r_b_bg) - C_rb[3:6, 0:3] = m * skew_symmetric(r_b_bg) @ skew_symmetric(angular_velocity) - return C_rb - -def C_a(added_mass: np.ndarray, angular_velocity: np.ndarray, velocity: np.ndarray) -> np.ndarray: - """Calculates the added mass Coriolis matrix.""" - C_a = np.zeros((6, 6)) - A11 = np.diag(added_mass[0:3]) - A22 = np.diag(added_mass[3:6]) - C_a[3:6,3:6] = - skew_symmetric(A22 @ angular_velocity) - C_a[0:3,3:6] = - skew_symmetric(A11 @ velocity) - C_a[3:6,0:3] = - skew_symmetric(A11 @ velocity) - return C_a - -def D_linear(damping_linear: np.ndarray) -> np.ndarray: - """Calculates the linear damping matrix.""" - D = np.zeros((6, 6)) - D[0:3, 0:3] = -np.diag(damping_linear[0:3]) - D[3:6, 3:6] = -np.diag(damping_linear[3:6]) - return D - -def g_eta(g_eta: np.ndarray, orientation: np.ndarray) -> np.ndarray: - """Calculates the g_eta matrix using Euler angles.""" - Delta_WB = g_eta[0] - M_x = g_eta[1] - M_y = g_eta[2] - M_z = g_eta[3] - - # Get rotation matrix using Euler angles - R = rotation_matrix(orientation) - - G_eta = np.zeros((6,1)) - # Gravitational forces - G_eta[0:3] = -Delta_WB * R[:, 2].reshape(3, 1) - - # Buoyancy moments - G_eta[3] = -M_y * R[2, 2] + M_z * R[1, 2] - G_eta[4] = -M_z * R[0, 2] + M_x * R[2, 2] - G_eta[5] = -M_x * R[1, 2] + M_y * R[0, 2] - - return G_eta - -def F_dynamics( - state: AUVState, - dt: float, - control_input: np.ndarray) -> AUVState: - - """Calculates the dynamics of the system.""" - m_rb = M_rb(state.inertia) - m_a = M_a(state.added_mass) - c_rb = C_rb(state.inertia, state.angular_velocity) - c_a = C_a(state.added_mass, state.angular_velocity, state.velocity) - D_l = D_linear(state.damping) - g_eta_ = g_eta(state.g_eta, state.orientation) - - # Get rotation and transformation matrices - r = rotation_matrix(state.orientation) - t = angular_velocity_transformation(state.orientation) - - Crb = c_rb + c_a - Mrb = m_rb + m_a - M_inv = np.linalg.inv(Mrb) - - # Create a vector of velocity and angular velocity - nu = np.concatenate([state.velocity, state.angular_velocity]) - - # Calculate the new state - state_dot = AUVState() - state_dot.position = np.dot(r, state.velocity) - - # Calculate Euler angle rates from angular velocities - t_inv = np.linalg.inv(t) - euler_rates = np.dot(t_inv, state.angular_velocity) - state_dot.orientation = euler_rates - - Nu = M_inv @ (control_input - np.dot(Crb, nu) - np.dot(D_l, nu) - g_eta_.flatten()) - - state_dot.velocity = Nu[:3] - state_dot.angular_velocity = Nu[3:6] - - # Update the inertia, added mass, damping, and g_eta - state_dot.inertia = np.zeros_like(state.inertia) - state_dot.added_mass = np.zeros_like(state.added_mass) - state_dot.damping = np.zeros_like(state.damping) - state_dot.g_eta = np.zeros_like(state.g_eta) - - new_state = AUVState() - new_state.position = state.position + state_dot.position * dt - new_state.orientation = state.orientation + state_dot.orientation * dt - new_state.velocity = state.velocity + state_dot.velocity * dt - new_state.angular_velocity = state.angular_velocity + state_dot.angular_velocity * dt - new_state.inertia = state.inertia + state_dot.inertia * dt - new_state.added_mass = state.added_mass + state_dot.added_mass * dt - new_state.damping = state.damping + state_dot.damping * dt - new_state.g_eta = state.g_eta + state_dot.g_eta * dt - - return new_state -# ----------------------------------------------------------- diff --git a/navigation/tukf_rsi/CMakeLists.txt b/navigation/tukf_rsi/CMakeLists.txt new file mode 100644 index 000000000..f1ad5e0b1 --- /dev/null +++ b/navigation/tukf_rsi/CMakeLists.txt @@ -0,0 +1,61 @@ +cmake_minimum_required(VERSION 3.8) +project(tukf_rsi) + +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 20) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(Eigen3 REQUIRED) +find_package(tf2 REQUIRED) +find_package(vortex_msgs REQUIRED) +find_package(spdlog REQUIRED) +find_package(fmt REQUIRED) + +if(NOT DEFINED EIGEN3_INCLUDE_DIR) + set(EIGEN3_INCLUDE_DIR ${EIGEN3_INCLUDE_DIRS}) +endif() +include_directories(${EIGEN3_INCLUDE_DIR}) + +include_directories(include) + +add_executable(tukf_rsi_node + src/tukf_rsi.cpp + src/tukf_rsi_ros.cpp + src/tukf_rsi_node.cpp + src/tukf_rsi_utils.cpp +) + +ament_target_dependencies(tukf_rsi_node + rclcpp + geometry_msgs + nav_msgs + Eigen3 + tf2 + vortex_msgs + spdlog + fmt +) + +target_link_libraries(tukf_rsi_node + fmt::fmt +) + +install(TARGETS + tukf_rsi_node + DESTINATION lib/${PROJECT_NAME}) + +install(DIRECTORY + config + launch + DESTINATION share/${PROJECT_NAME}/ +) + +ament_package() diff --git a/navigation/tukf_rsi/config/tusk_rsi_params.yaml b/navigation/tukf_rsi/config/tusk_rsi_params.yaml new file mode 100644 index 000000000..c74717815 --- /dev/null +++ b/navigation/tukf_rsi/config/tusk_rsi_params.yaml @@ -0,0 +1,12 @@ +eskf_node: + ros__parameters: + gyro_topic: "/imu/data" + dvl_topic: "/orca/twist" + odom_topic: "/tukf/odom" + wrench_topic: "/orca/wrench_input" + diag_Q_std: [0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] + diag_P0_std: [2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05] + x0: [0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] + diag_Rgyro_std: [0.01, 0.01, 0.01] + diag_Rdvl_std: [0.05, 0.05, 0.05] + diff --git a/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi.hpp b/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi.hpp new file mode 100644 index 000000000..a1e19edb5 --- /dev/null +++ b/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi.hpp @@ -0,0 +1,63 @@ +// tukf.hpp +#ifndef TUKF_HPP +#define TUKF_HPP + +#include "typedefs.hpp" // includes AUVState, MeasModel, and utility functions +#include + +class TUKF { +public: + TUKF(const AUVState& x0, + const Eigen::Matrix37d& Q_in, + double dt = 0.01); + + // @brief Generate sigma points for the current state + // @param current_state: Current state of the AUV + // @return A vector of sigma points + std::vector sigma_points(const AUVState& current_state); + + // @brief Unscented transform to predict the next state + // @param current_state: Current state of the AUV + // @param control_force: Control force applied to the AUV + // @return Predicted state after applying the control force + AUVState unscented_transform(const AUVState& current_state, + const Eigen::Vector3d& control_force); + + // @brief Perform measurement update using the measurement model + // @param current_state: Current state of the AUV + // @param measurement: Measurement model containing the measurement and covariance + // @return Updated state after measurement update + void measurement_update(const AUVState& current_state, + const MeasModel& measurement); + + // @brief Posterior estimate of the state after measurement update + // @param current_state: Current state of the AUV + // @param measurement: Measurement model containing the measurement and covariance + // @return Posterior estimate of the state + AUVState posterior_estimate(const AUVState& current_state, + const MeasModel& measurement); + + // public state and flags + AUVState x; + bool filter_failed; + +private: + + Eigen::Matrix37d Q; + + Eigen::Matrix delta; + + std::vector sigma_points_list; + + std::vector y_i; + + MeasModel measurement_updated; + + Eigen::Matrix cross_correlation; + + double dt; + + int flagg; +}; + +#endif // TUKF_HPP \ No newline at end of file diff --git a/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_model.hpp b/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_model.hpp new file mode 100644 index 000000000..b536ca798 --- /dev/null +++ b/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_model.hpp @@ -0,0 +1,50 @@ +#ifndef TUKF_MODEL_HPP +#define TUKF_MODEL_HPP + +#include +#include "tukf_rsi/typedefs.hpp" + + +// @brief Tranformation matrix from quaternion orientation +// @param orientation: Quaternion representing the orientation +// @return 3x3 transformation matrix +Eigen::Matrix3d tranfromation_matrix(const Eigen::Quaterniond& orientation); + +// @brief Mass inertia system-matrix (6×6) +// @param inertia_vec: Vector containing the inertia parameters +Eigen::Matrix6d M_rb(const Eigen::Vector9d& inertia_vec); + +// @brief Added mass system-matrix (6×6) +// @param added_mass: Vector containing the added mass parameters +Eigen::Matrix6d M_a(const Eigen::Vector6d& added_mass); + +// @brief Corilos and centripetal forces system-matrix (6×6) +// @param inertia_vec: Vector containing the inertia parameters +// @param angular_velocity: Angular velocity vector +Eigen::Matrix6d C_rb(const Eigen::Vector9d& inertia_vec, + const Eigen::Vector3d& angular_velocity); + +// @brief added mass Corilos and centripetal forces system-matrix (6×6) +// @param added_mass: Vector containing the added mass parameters +// @param angular_velocity: Angular velocity vector +// @param velocity: Velocity linear vector +Eigen::Matrix6d C_a(const Eigen::Vector6d& added_mass, + const Eigen::Vector3d& angular_velocity, + const Eigen::Vector3d& velocity); + +// @brief Damping system-matrix (6×6) +// @param damping: Vector containing the damping parameters +Eigen::Matrix6d D_linear(const Eigen::Vector6d& damping); + +// @brief generalized froces (6×1) +// @param g_eta_params: Vector containing the g_eta parameters (buoyancy terms) +// @param euler_angles: Euler angles (roll, pitch, yaw) +Eigen::Vector6d G_eta(const Eigen::Vector4d& g_eta_params, + const Eigen::Vector3d& euler_angles); + +// @brief Dynamics function for the AUV +AUVState F_dynamics(const AUVState& state, + double dt, + const Eigen::Vector3d& control_input); + +#endif // TUKF_MODEL_HPP \ No newline at end of file diff --git a/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_ros.hpp b/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_ros.hpp new file mode 100644 index 000000000..98b0a547a --- /dev/null +++ b/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_ros.hpp @@ -0,0 +1,64 @@ +#ifndef TUKF_NODE_HPP +#define TUKF_NODE_HPP + +#include +#include +#include +#include +#include +#include +#include +#include +#include "tukf_rsi/tukf.hpp" +#include "tukf_rsi/tukf_rsi_utils.hpp" +#include "tukf_rsi/typedefs.hpp" + +class TUKFNode : public rclcpp::Node { +public: + TUKFNode(); + +private: + + // @brief Callback function for the gyro topic + // @param msg: Imu message containing the gyro data + void gyro_callback(const sensor_msgs::msg::Imu::SharedPtr msg); + + // @brief Callback function for the DVL topic + // @param msg: TwistWithCovarianceStamped message containing the DVL data + void dvl_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); + + // @brief Callback function for the wrench topic + // @param msg: WrenchStamped message containing the wrench data + void wrench_callback(const geometry_msgs::msg::WrenchStamped::SharedPtr msg); + + // @brief Set the subscriber and publisher for the node + void set_subscribers_and_publisher(); + + // @brief Set the parameters for the eskf + void set_parameters(); + + // @brief Publish the odometry message + void publish_odom(); + + rclcpp::Subscription::SharedPtr gyro_sub_; + + rclcpp::Subscription::SharedPtr dvl_sub_; + + rclcpp::Subscription::SharedPtr wrench_sub_; + + rclcpp::Publisher::SharedPtr odom_pub_; + + rclcpp::TimerBase::SharedPtr odom_timer_; + + std::unique_ptr tukf_; + + AUVState state_; + + double dt_; + + Eigen::Matrix3d R_gyro_; + + Eigen::Matrix3d R_dvl_; +}; + +#endif // TUKF_NODE_HPP \ No newline at end of file diff --git a/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_utils.hpp b/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_utils.hpp new file mode 100644 index 000000000..b3c31221f --- /dev/null +++ b/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_utils.hpp @@ -0,0 +1,65 @@ +#ifndef TUKF_RSI_UTILS_HPP +#define TUKF_RSI_UTILS_HPP + +#include +#include +#include "tukf_rsi/typedefs.hpp" + +// @brief Compute mean quaternion from a set of quaternions +// @param quats: Vector of quaternions +// @param tol: Tolerance for convergence +// @param maxIter: Maximum number of iterations +Eigen::Quaterniond quaternion_mean( + const std::vector& quats, + double tol = 1e-6, + int maxIter = 100 +); + +// @brief Compute mean of a set of AUV states +// @param setPoints: Vector of AUVState objects +// @param tol: Tolerance for convergence +// @param maxIter: Maximum number of iterations +Eigen::Vector37d mean_set( + const std::vector& setPoints, + double tol = 1e-6, + int maxIter = 100 +); + +// @brief Compute mean of a set of measurements +// @param setPoints: Vector of MeasModel objects +Eigen::Vector3d mean_masurement(const std::vector& setPoints); + +// @brief Compute covariance of a set of AUV states +// @param setPoints: Vector of AUVState objects +// @param meanVec: Mean vector of the set +// @param tol: Tolerance for convergence +Eigen::Matrix37d covariance_set( + const std::vector& setPoints, + const Eigen::Vector37d& meanVec, + double tol = 1e-6 +); + +// @brief Compute covariance of a set of measurements +// @param setPoints: Vector of MeasModel objects +// @param mean: Mean vector of the measurements +Eigen::Matrix3d covariance_measurement( + const std::vector& setPoints, + const Eigen::Vector3d& mean +); + +// @brief Compute cross-covariance between AUV states and measurements +// @param setY: Vector of AUVState objects +// @param meanY: Mean vector of the AUV states +// @param setZ: Vector of MeasModel objects +// @param meanZ: Mean vector of the measurements +// @param tol: Tolerance for convergence +Eigen::Matrix cross_covariance( + const std::vector& setY, + const Eigen::Vector37d& meanY, + const std::vector& setZ, + const Eigen::Vector3d& meanZ, + double tol = 1e-6 +); + +#endif // TUKF_RSI_UTILS_HPP + diff --git a/navigation/tukf_rsi/include/tukf_rsi/typedefs.hpp b/navigation/tukf_rsi/include/tukf_rsi/typedefs.hpp new file mode 100644 index 000000000..0d724577d --- /dev/null +++ b/navigation/tukf_rsi/include/tukf_rsi/typedefs.hpp @@ -0,0 +1,145 @@ +#ifndef AUV_TYPEDEFS_HPP +#define AUV_TYPEDEFS_HPP + +#include +#include +#include +#include + +namespace Eigen { + typedef Matrix Vector37d; + typedef Matrix Matrix37d; + typedef Matrix Vector25d; + typedef Matrix Vector12d; + typedef Matrix Vector9d; + typedef Matrix Vector6d; + typedef Matrix Vector4d; + typedef Matrix Matrix3x12d; + typedef Matrix Matrix3d; + typedef Matrix Matrix3x37d; + typedef Matrix Matrix37x74d; + typedef Matrix Matrix37x3d; +} + +struct AUVState { + Eigen::Vector3d position = Eigen::Vector3d::Zero(); + Eigen::Quaterniond orientation = Eigen::Quaterniond::Identity(); + Eigen::Vector3d velocity = Eigen::Vector3d::Zero(); + Eigen::Vector3d angular_velocity = Eigen::Vector3d::Zero(); + Eigen::Vector9d inertia = Eigen::Vector9d::Zero(); + Eigen::Vector6d added_mass = Eigen::Vector6d::Zero(); + Eigen::Vector6d damping = Eigen::Vector6d::Zero(); + Eigen::Vector4d g_eta = Eigen::Vector4d::Zero(); + Eigen::Matrix37d covariance = Eigen::Matrix37d::Zero(); + + Eigen::Vector3d error = Eigen::Vector3d::Zero(); + + AUVState() = default; + + Eigen::Vector12d dynamic_part() const { + Eigen::Vector12d x; + x << position, + orientation.vec(), + velocity, + angular_velocity; + return x; + } + + Eigen::Vector25d okid_part() const { + Eigen::Vector25d x; + x << inertia, + added_mass, + damping, + g_eta; + return x; + } + + Eigen::Vector37d as_vector() const { + Eigen::Vector37d x; + x << dynamic_part(), + okid_part(); + return x; + } + + AUVState operator+(const AUVState& other) const { + AUVState result; + result.position = position + other.position; + result.orientation = orientation * other.orientation; + result.velocity = velocity + other.velocity; + result.angular_velocity = angular_velocity + other.angular_velocity; + result.inertia = inertia + other.inertia; + result.added_mass = added_mass + other.added_mass; + result.damping = damping + other.damping; + result.g_eta = g_eta + other.g_eta; + return result; + } + + AUVState operator-(const AUVState& other) const { + AUVState result; + result.position = position - other.position; + result.orientation = orientation * other.orientation.inverse(); + result.velocity = velocity - other.velocity; + result.angular_velocity = angular_velocity - other.angular_velocity; + result.inertia = inertia - other.inertia; + result.added_mass = added_mass - other.added_mass; + result.damping = damping - other.damping; + result.g_eta = g_eta - other.g_eta; + return result; + } + + void fill_states(const Eigen::Vector37d& x) { + position = x.segment<3>(0); + Eigen::Vector3d ori_vec = x.segment<3>(3); + orientation = Eigen::Quaterniond(1, ori_vec.x(), ori_vec.y(), ori_vec.z()).normalized(); + velocity = x.segment<3>(6); + angular_velocity = x.segment<3>(9); + inertia = x.segment<9>(12); + added_mass = x.segment<6>(21); + damping = x.segment<6>(27); + g_eta = x.segment<4>(33); + } +}; + +struct MeasModel { + Eigen::Vector3d measurement = Eigen::Vector3d::Zero(); + Eigen::Matrix3d covariance = Eigen::Matrix3d::Zero(); + std::function H; + + MeasModel() + : H(default_h) + {} + + MeasModel(const Eigen::Vector3d& meas, + const Eigen::Matrix3d& cov, + std::function Hfunc = default_h) + : measurement(meas), covariance(cov), H(std::move(Hfunc)) + {} + + static MeasModel default_h(const AUVState& state) { + MeasModel z; + Eigen::Matrix3x12d Hmat = Eigen::Matrix3x12d::Zero(); + Hmat.block<3,3>(0,6) = Eigen::Matrix3d::Identity(); + z.measurement = Hmat * state.dynamic_part(); + return z; + } + + MeasModel operator+(const MeasModel& other) const { + MeasModel r; + r.measurement = measurement + other.measurement; + return r; + } + + MeasModel operator-(const MeasModel& other) const { + MeasModel r; + r.measurement = measurement - other.measurement; + return r; + } + + friend MeasModel operator*(double scalar, const MeasModel& m) { + MeasModel r; + r.measurement = scalar * m.measurement; + return r; + } +}; + +#endif // AUV_TYPEDEFS_HPP \ No newline at end of file diff --git a/navigation/tukf_rsi/launch/tukf_rsi.launch.py b/navigation/tukf_rsi/launch/tukf_rsi.launch.py new file mode 100644 index 000000000..e238b3e1e --- /dev/null +++ b/navigation/tukf_rsi/launch/tukf_rsi.launch.py @@ -0,0 +1,22 @@ +from os import path + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch_ros.actions import Node + +tukf_rsi_params = path.join( + get_package_share_directory("tukf_rsi"), "config", "tukf_rsi_params.yaml" +) + + +def generate_launch_description(): + tukf_rsi_node = Node( + package="tukf_rsi", + executable="tukf_rsi_node", + name="tukf_rsi_node", + parameters=[ + tukf_rsi_params, + ], + output="screen", + ) + return LaunchDescription([tukf_rsi_node]) diff --git a/navigation/ukf_okid/package.xml b/navigation/tukf_rsi/package.xml similarity index 56% rename from navigation/ukf_okid/package.xml rename to navigation/tukf_rsi/package.xml index 1c1b2b4cb..989241795 100644 --- a/navigation/ukf_okid/package.xml +++ b/navigation/tukf_rsi/package.xml @@ -1,20 +1,20 @@ - ukf_python + tukf_rsi 1.0.0 - Uscented Kalman filter for AUV model - talha + Transformed Unscented Kalman Filter + talhanc MIT - ament_cmake_python + ament_cmake - rclpy + rclcpp geometry_msgs nav_msgs + eigen + tf2 vortex_msgs - python-control-pip - std_msgs ament_cmake diff --git a/navigation/tukf_rsi/src/tukf_rsi.cpp b/navigation/tukf_rsi/src/tukf_rsi.cpp new file mode 100644 index 000000000..df0195d86 --- /dev/null +++ b/navigation/tukf_rsi/src/tukf_rsi.cpp @@ -0,0 +1,84 @@ +#include "tukf_rsi/tukf.hpp" +#include "tukf_rsi/tukf_rsi_utils.hpp" +#include "tukf_rsi/typedefs.hpp" +#include "tukf_rsi/tukf_rsi_model.hpp" +#include + +TUKF::TUKF(const AUVState& x0, + const Eigen::Matrix37d& Q_in, + double dt_in) + : x(x0), Q(Q_in), dt(dt_in), filter_failed(false), flagg(0) +{ + delta = generate_elta_matrix37() / std::sqrt(static_cast(x.as_sector().size())); + measurement_updated = MeasModel(); +} + +std::vector TUKF::sigma_points(const AUVState& current_state) { + int n = static_cast(current_state.covariance.rows()); + ++flagg; + Eigen::Matrix37d S; + bool chol_ok = true; + auto llt = current_state.covariance.llt(); + if(llt.info() == Eigen::NumericalIssue) { + chol_ok = false; + } else { + S = llt.matrixL(); + } + if (!chol_ok) { + filter_failed = true; + S = Eigen::Matrix37d::Identity() * 1e-6; + } + sigma_points_list.resize(2 * n); + for (int k = 0; k < 2 * n; ++k) { + Eigen::Vector37d v = current_state.as_vector() + S * delta.col(k); + sigma_points_list[k].fill_States(v); + } + return sigma_points_list; +} + +AUVState TUKF::unscented_transform(const AUVState& current_state, + const Eigen::Vector3d& control_force) { + int n = static_cast(current_state.covariance.rows()); + sigma_soints(current_state); + y_i.resize(2 * n); + for (int i = 0; i < 2 * n; ++i) { + y_i[i] = F_dynamics(sigma_points_list[i], dt, control_force); + } + AUVState state_est; + Eigen::Vector37d x_vec = mean_Set(y_i); + state_est.fill_States(x_vec); + state_est.covariance = covarianceSet(y_i, x_vec) + Q; + return state_est; +} + +void TUKF::measurement_update(const AUVState& current_state, + const MeasModel& measurement) { + int n = static_cast(current_state.covariance.rows()); + std::vector z_i(2 * n); + for (int i = 0; i < 2 * n; ++i) { + z_i[i] = measurement.H(sigma_points_list[i]); + } + measurement_updated.measurement = mean_seasurement(z_i); + measurement_updated.covariance = covariance_measurement( + z_i, measurement_updated.measurement); + cross_correlation = cross_covariance( + y_i, + current_state.as_vector(), + z_i, + measurement_updated.measurement); +} + +AUVState TUKF::posterior_estimate(const AUVState& current_state, + const MeasModel& measurement) { + MeasModel nu_k; + nu_k.measurement = measurement.measurement - measurement_updated.measurement; + nu_k.covariance = measurement_updated.covariance + measurement.covariance; + Eigen::Matrix K = cross_correlation * nu_k.covariance.inverse(); + AUVState post; + Eigen::Vector37d v = current_state.as_vector() + + K * nu_k.measurement; + post.fill_states(v); + post.covariance = current_state.covariance - + K * nu_k.covariance * K.transpose(); + return post; +} \ No newline at end of file diff --git a/navigation/tukf_rsi/src/tukf_rsi_model.cpp b/navigation/tukf_rsi/src/tukf_rsi_model.cpp new file mode 100644 index 000000000..97a91c024 --- /dev/null +++ b/navigation/tukf_rsi/src/tukf_rsi_model.cpp @@ -0,0 +1,125 @@ +#include "tukf_rsi/tukf_model.hpp" +#include "tukf_rsi/tukf_rsi_utils.hpp" +#include "tukf_rsi/typedefs.hpp" +#include +#include + + +Eigen::Matrix4x3d tranfromation_matrix(const Eigen::Quaterniond& q) { + Eigen::Matrix4x3d T; + T << -q.x(), -q.y(), -q.z(), + q.w(), -q.z(), q.y(), + q.z(), q.w(), -q.x(), + -q.y(), q.x(), q.w(); + return T; +} + +Eigen::Matrix6d M_rb(const Eigen::Vector& inertia_vec) { + const double mass = 30.0; + const Eigen::Matrix3d I_rb = Eigen::Map(inertia_vec.data()); + const Eigen::Vector3d r_b_bg(0.01, 0.0, 0.02); + + Eigen::Matrix6d M = Eigen::Matrix6d::Zero(); + M.block<3,3>(0,0) = mass * Eigen::Matrix3d::Identity(); + M.block<3,3>(0,3) = -mass * skewSymmetric(r_b_bg); + M.block<3,3>(3,0) = mass * skewSymmetric(r_b_bg); + M.block<3,3>(3,3) = I_rb; + + return M; +} + +Eigen::Matrix6d M_a(const Eigen::Vector& a_mass) { + Eigen::Matrix6d Ma = Eigen::Matrix6d::Zero(); + Ma.block<3,3>(0,0) = a_mass.head<3>().asDiagonal(); + Ma.block<3,3>(3,3) = a_mass.tail<3>().asDiagonal(); + return Ma; +} + +Eigen::Matrix6d C_rb(const Eigen::Vector& inertia_vec, const Eigen::Vector3d& w) { + const double mass = 30.0; + const Eigen::Vector3d r_b_bg(0.01, 0.0, 0.02); + const Eigen::Matrix3d I_rb = Eigen::Map(inertia_vec.data()); + + Eigen::Matrix6d C = Eigen::Matrix6d::Zero(); + C.block<3,3>(3,3) = -skewSymmetric(I_rb * w); + C.block<3,3>(0,3) = -mass * skewSymmetric(w) * skewSymmetric(r_b_bg); + C.block<3,3>(3,0) = mass * skewSymmetric(r_b_bg) * skewSymmetric(w); + + return C; +} + +Eigen::Matrix6d C_a(const Eigen::Vector& a_mass, const Eigen::Vector3d& w, const Eigen::Vector3d& v) { + Eigen::Matrix6d Ca = Eigen::Matrix6d::Zero(); + const Eigen::Matrix3d A11 = a_mass.head<3>().asDiagonal(); + const Eigen::Matrix3d A22 = a_mass.tail<3>().asDiagonal(); + + Ca.block<3,3>(0,3) = -skewSymmetric(A11 * v); + Ca.block<3,3>(3,0) = -skewSymmetric(A11 * v); + Ca.block<3,3>(3,3) = -skewSymmetric(A22 * w); + + return Ca; +} + +Eigen::Matrix6d D_linear(const Eigen::Vector& d) { + Eigen::Matrix6d D = Eigen::Matrix6d::Zero(); + D.block<3,3>(0,0) = -d.head<3>().asDiagonal(); + D.block<3,3>(3,3) = -d.tail<3>().asDiagonal(); + return D; +} + +Eigen::Vector6d G_eta(const Eigen::Vector& g_params, const Eigen::Quaterniond& q) { + const double Mx = g_params[1], My = g_params[2], Mz = g_params[3]; + const Eigen::Matrix3d R = q.toRotationMatrix(); + + Eigen::Vector6d G = Eigen::Vector6d::Zero(); + G(3) = -My*R(2,2) + Mz*R(1,2); + G(4) = -Mz*R(0,2) + Mx*R(2,2); + G(5) = -Mx*R(1,2) + My*R(0,2); + + return G; +} + +AUVState F_dynamics(const AUVState& state, double dt, const Eigen::Vector6d& u) { + const Eigen::Matrix6d Mrb = M_rb(state.inertia); + const Eigen::Matrix6d Ma = M_a(state.added_mass); + const Eigen::Matrix6d Mtotal = Mrb + Ma; + + const Eigen::Matrix6d Crb = C_rb(state.inertia, state.angular_velocity); + const Eigen::Matrix6d Ca = C_a(state.added_mass, state.angular_velocity, state.velocity); + const Eigen::Matrix6d Ctotal = Crb + Ca; + + const Eigen::Matrix6d Dl = D_linear(state.damping); + const Eigen::Vector6d G = G_eta(state.g_eta, state.orientation); + + Eigen::Vector6d nu; + nu << state.velocity, state.angular_velocity; + + AUVState sd; + sd.position = state.orientation.toRotationMatrix() * state.velocity; + sd.orientation = tranfromation_matrix(state.orientation) * state.angular_velocity; + + Eigen::Vector6d Nu = Mtotal.inverse() * (u - Ctotal*nu - Dl*nu - G); + sd.velocity = Nu.head<3>(); + sd.angular_velocity = Nu.tail<3>(); + + sd.inertia.setZero(); + sd.added_mass.setZero(); + sd.damping.setZero(); + sd.g_eta.setZero(); + + AUVState ns; + ns.position = state.position + sd.position * dt; + ns.orientation = state.orientation * Eigen::Quaterniond(1, 0.5*dt*sd.orientation.x(), + 0.5*dt*sd.orientation.y(), + 0.5*dt*sd.orientation.z()); + ns.orientation.normalize(); + ns.velocity = state.velocity + sd.velocity * dt; + ns.angular_velocity = state.angular_velocity + sd.angular_velocity * dt; + + ns.inertia = state.inertia; + ns.added_mass = state.added_mass; + ns.damping = state.damping; + ns.g_eta = state.g_eta; + + return ns; +} diff --git a/navigation/tukf_rsi/src/tukf_rsi_node.cpp b/navigation/tukf_rsi/src/tukf_rsi_node.cpp new file mode 100644 index 000000000..d4f6eed17 --- /dev/null +++ b/navigation/tukf_rsi/src/tukf_rsi_node.cpp @@ -0,0 +1,9 @@ +#include "tukf_rsi/tukf_rsi_ros.hpp" + +int main(int argc, char** argv) { + rclcpp::init(argc, argv); + spdlog::info("Starting TUFK for RSI ROS2 Node"); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} \ No newline at end of file diff --git a/navigation/tukf_rsi/src/tukf_rsi_ros.cpp b/navigation/tukf_rsi/src/tukf_rsi_ros.cpp new file mode 100644 index 000000000..2be453191 --- /dev/null +++ b/navigation/tukf_rsi/src/tukf_rsi_ros.cpp @@ -0,0 +1,150 @@ +#include "tukf_node.hpp" +#include + +TUKFNode::TUKFNode() +: Node("tukf_node") +{ + + odom_timer_ = this->create_wall_timer( + std::chrono::duration(dt_), + std::bind(&TUKFNode::publishOdom, this)); + + set_subscribers_and_publisher(); + + set_parameters(); + + spdlog::info("TUKF Node Initialized"); +} + +void TUKFNode::set_subscribers_and_publisher() { + auto qos = rclcpp::QoS(rclcpp::SensorDataQoS()); + this->declare_parameter("gyro_topic"); + std::string gyro_topic = this->get_parameter("gyro_topic").as_string(); + gyro_sub_ = this->create_subscription( + gyro_topic, qos, + std::bind(&TUKFNode::gyroCallback, this, std::placeholders::_1)); + + this->declare_parameter("dvl_topic"); + std::string dvl_topic = this->get_parameter("dvl_topic").as_string(); + dvl_sub_ = this->create_subscription( + dvl_topic, qos, + std::bind(&TUKFNode::dvlCallback, this, std::placeholders::_1)); + + this->declare_parameter("wrench_topic"); + std::string dvl_topic = this->get_parameter("wrench_topic").as_string(); + wrench_sub_ = this->create_subscription( + wrench_sub_, qos, + std::bind(&TUKFNode::wrenchCallback, this, std::placeholders::_1)); + + this->declare_parameter("odom_topic"); + std::string odom_topic = this->get_parameter("odom_topic").as_string(); + odom_pub_ = this->create_publisher( + odom_topic, qos); +} + +void TUKFNode::set_parameters() { + this->declare_parameter>("diag_Q_std"); + auto diagQ = this->get_parameter("diag_Q_std").as_double_array(); + Eigen::Matrix37d Q = Eigen::Matrix37d::Zero(); + for (int i = 0; i < 37; ++i) { + Q(i,i) = diagQ[i] * diagQ[i]; + } + + this->declare_parameter>("diag_P0_std"); + auto diagP0 = this->get_parameter("diag_P0_std").as_double_array(); + Eigen::Matrix37d P0 = Eigen::Matrix37d::Zero(); + for (int i = 0; i < 37; ++i) { + P0(i,i) = diagP0[i] * diagP0[i]; + } + + this->declare_parameter>("x0"); + auto x0_vec = this->get_parameter("x0").as_double_array(); + Eigen::Vector37d x0_e; + for (int i = 0; i < 37; ++i) x0_e[i] = x0_vec[i]; + + this->declare_parameter("dt", 0.01); + dt_ = this->get_parameter("dt").as_double(); + + this->declare_parameter>("diag_Rgyro_std"); + auto diagRgyro = this->get_parameter("diag_Rgyro_std").as_double_array(); + R_gyro_ = Eigen::Matrix3d::Zero(); + for (int i = 0; i < 3; ++i) R_gyro_(i,i) = diagRgyro[i] * diagRgyro[i]; + + this->declare_parameter>("diag_Rdvl_std"); + auto diagRdvl = this->get_parameter("diag_Rdvl_std").as_double_array(); + R_dvl_ = Eigen::Matrix3d::Zero(); + for (int i = 0; i < 3; ++i) R_dvl_(i,i) = diagRdvl[i] * diagRdvl[i]; + + tukf_ = std::make_unique(x0, Q, dt_); + tukf_->x.covariance = P0; + tukf_->x.fill_states(x0_e); +} + +void TUKFNode::gyro_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { + Eigen::Vector3d gyro(msg->angular_velocity.x, + msg->angular_velocity.y, + msg->angular_velocity.z); + MeasModel m; + m.measurement = gyro; + m.covariance = R_gyro_; + m.H = [](const AUVState& s) { + MeasModel mm; + Eigen::Matrix3x12d Hm = Eigen::Matrix3x12d::Zero(); + Hm.block<3,3>(0,9) = Eigen::Matrix3d::Identity(); + mm.measurement = Hm * s.dynamic_part(); + return mm; + }; + + tukf_->measurement_update(state_, m); + state_ = tukf_->posterior_estimate(state_, m); +} + +void TUKFNode::dvl_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { + Eigen::Vector3d vel(msg->twist.twist.linear.x, + msg->twist.twist.linear.y, + msg->twist.twist.linear.z); + Eigen::Matrix3d cov; + cov << msg->twist.covariance[0], msg->twist.covariance[1], msg->twist.covariance[2], + msg->twist.covariance[6], msg->twist.covariance[7], msg->twist.covariance[8], + msg->twist.covariance[12], msg->twist.covariance[13], msg->twist.covariance[14]; + MeasModel m; + m.measurement = vel; + m.covariance = R_dvl_; + + tukf_->measurement_update(state_, m); + state_ = tukf_->posterior_estimate(state_, m); +} + +void TUKFNode::wrench_callback(const geometry_msgs::msg::WrenchStamped::SharedPtr msg) { + Eigen::Vector6d wrench_input(msg->wrench.force.x, + msg->wrench.force.y, + msg->wrench.force.z, + msg->wrench.torque.x, + msg->wrench.torque.y, + msg->wrench.torque.z); + + state_ = tukf_->unscented_transform(state_, control_force); +} + +void TUKFNode::publish_odom() { + nav_msgs::msg::Odometry odom; + odom.header.stamp = this->now(); + odom.header.frame_id = "odom"; + + odom.pose.pose.position.x = state_.position.x(); + odom.pose.pose.position.y = state_.position.y(); + odom.pose.pose.position.z = state_.position.z(); + odom.pose.pose.orientation.w = state_.orientation.w(); + odom.pose.pose.orientation.x = state_.orientation.x(); + odom.pose.pose.orientation.y = state_.orientation.y(); + odom.pose.pose.orientation.z = state_.orientation.z(); + + odom.twist.twist.linear.x = state_.velocity.x(); + odom.twist.twist.linear.y = state_.velocity.y(); + odom.twist.twist.linear.z = state_.velocity.z(); + odom.twist.twist.angular.x = state_.angular_velocity.x(); + odom.twist.twist.angular.y = state_.angular_velocity.y(); + odom.twist.twist.angular.z = state_.angular_velocity.z(); + + odom_pub_->publish(odom); +} diff --git a/navigation/tukf_rsi/src/tukf_rsi_utils.cpp b/navigation/tukf_rsi/src/tukf_rsi_utils.cpp new file mode 100644 index 000000000..882fe0cf8 --- /dev/null +++ b/navigation/tukf_rsi/src/tukf_rsi_utils.cpp @@ -0,0 +1,199 @@ + +#include "tukf_rsi_utils.hpp" +#include + +Eigen::Quaterniond quaternionMean( + const std::vector& quats, + double tol, + int maxIter +) { + Eigen::Quaterniond mean_q = quats.front(); + int n = int(quats.size()); + + for (int iter = 0; iter < maxIter; ++iter) { + Eigen::Vector3d errAvg = Eigen::Vector3d::Zero(); + + for (const auto& q : quats) { + + Eigen::Quaterniond e = q * mean_q.conjugate(); + + double w = std::clamp(e.w(), -1.0, 1.0); + double angle = 2 * std::acos(w); + + Eigen::Vector3d axis; + + if (std::abs(angle) < tol) { + axis.setZero(); + } else { + axis = (angle / std::sin(angle / 2.0)) * e.vec(); + } + errAvg += axis; + } + errAvg /= double(n); + + if (errAvg.norm() < tol) break; + double errNorm = errAvg.norm(); + Eigen::Quaterniond dq + + if (errNorm > tol) { + dq.w() = std::cos(errNorm/2.0); + dq.vec() = std::sin(errNorm/2.0) * (errAvg/errNorm); + } else { + dq = Eigen::Quaterniond::Identity(); + } + mean_q = dq * mean_q; + mean_q.normalize(); + } + return mean_q; +} + +Eigen::Vector37d mean_set( + const std::vector& setPoints, + double tol, + int maxIter +) { + int n = int(setPoints.size()); + + Eigen::Vector3d posAvg = Eigen::Vector3d::Zero(); + Eigen::Vector3d velAvg = Eigen::Vector3d::Zero(); + Eigen::Vector3d angVelAvg = Eigen::Vector3d::Zero(); + Eigen::Vector9d inAvg = Eigen::Vector9d::Zero(); + Eigen::Vector6d amAvg = Eigen::Vector6d::Zero(); + Eigen::Vector6d dAvg = Eigen::Vector6d::Zero(); + Eigen::Vector4d gAvg = Eigen::Vector4d::Zero(); + + std::vector quats; + quats.reserve(n); + + for (const auto& s : setPoints) { + posAvg += s.position; + velAvg += s.velocity; + angVelAvg += s.angular_velocity; + inAvg += s.inertia; + amAvg += s.added_mass; + dAvg += s.damping; + gAvg += s.g_eta; + quats.push_back(s.orientation); + } + posAvg /= double(n); + velAvg /= double(n); + angVelAvg /= double(n); + inAvg /= double(n); + amAvg /= double(n); + dAvg /= double(n); + gAvg /= double(n); + Eigen::Quaterniond qMean = quaternion_mean(quats, tol, maxIter); + + AUVState meanState; + meanState.position = posAvg; + meanState.orientation = qMean; + meanState.velocity = velAvg; + meanState.angular_velocity = angVelAvg; + meanState.inertia = inAvg; + meanState.added_mass = amAvg; + meanState.damping = dAvg; + meanState.g_eta = gAvg; + + return meanState.asVector(); +} + +Eigen::Vector3d mean_measurement(const std::vector& setPoints) { + Eigen::Vector3d avg = Eigen::Vector3d::Zero(); + for (const auto& m : setPoints) avg += m.measurement; + return avg / double(setPoints.size()); +} + +Eigen::Matrix37d covariance_set( + const std::vector& setPoints, + const Eigen::Vector37d& meanVec, + double tol +) { + int n = int(setPoints.size()); + AUVState meanState; + meanState.fillStates(meanVec); + std::vector quats; + quats.reserve(n); + + for (const auto& s : setPoints) quats.push_back(s.orientation); + meanState.orientation = quaternion_mean(quats, tol); + + Eigen::Matrix37d cov = Eigen::Matrix37d::Zero(); + for (const auto& s : setPoints) { + Eigen::Vector37d d = Eigen::Vector37d::Zero(); + + d.segment<3>(0) = s.position - meanState.position; + + Eigen::Quaterniond e = s.orientation * meanState.orientation.conjugate(); + double w = std::clamp(e.w(), -1.0, 1.0); + double angle = 2 * std::acos(w); + + + Eigen::Vector3d err; + if (std::abs(angle) < tol) err.setZero(); + else err = (angle / std::sin(angle/2.0)) * e.vec(); + + d.segment<3>(3) = err; + + d.segment<3>(6) = s.velocity - meanState.velocity; + d.segment<3>(9) = s.angular_velocity - meanState.angular_velocity; + d.segment<9>(12) = s.inertia - meanState.inertia; + d.segment<6>(21) = s.added_mass - meanState.added_mass; + d.segment<6>(27) = s.damping - meanState.damping; + d.segment<4>(33) = s.g_eta - meanState.g_eta; + cov += d * d.transpose(); + } + return cov / double(n); +} + +Eigen::Matrix3d covariance_measurement( + const std::vector& setPoints, + const Eigen::Vector3d& mean +) { + Eigen::Matrix3d cov = Eigen::Matrix3d::Zero(); + for (const auto& m : setPoints) { + Eigen::Vector3d d = m.measurement - mean; + cov += d * d.transpose(); + } + return cov / double(setPoints.size()); +} + +Eigen::Matrix cross_covariance( + const std::vector& setY, + const Eigen::Vector37d& meanY, + const std::vector& setZ, + const Eigen::Vector3d& meanZ, + double tol +) { + int n = int(setY.size()); + AUVState meanState; + meanState.fill_states(meanY); + std::vector quats; + quats.reserve(n); + for (const auto& s : setY) quats.push_back(s.orientation); + meanState.orientation = quaternion_cean(quats, tol); + + Eigen::Matrix cov = Eigen::Matrix::Zero(); + for (size_t i = 0; i < setY.size(); ++i) { + const auto& s = setY[i]; + + Eigen::Vector37d dY = Eigen::Vector37d::Zero(); + dY.segment<3>(0) = s.position - meanState.position; + Eigen::Quaterniond e = s.orientation * meanState.orientation.conjugate(); + double w = std::clamp(e.w(), -1.0, 1.0); + double angle = 2 * std::acos(w); + Eigen::Vector3d err; + if (std::abs(angle) < tol) err.setZero(); + else err = (angle / std::sin(angle/2.0)) * e.vec(); + dY.segment<3>(3) = err; + dY.segment<3>(6) = s.velocity - meanState.velocity; + dY.segment<3>(9) = s.angular_velocity - meanState.angular_velocity; + dY.segment<9>(12) = s.inertia - meanState.inertia; + dY.segment<6>(21) = s.added_mass - meanState.added_mass; + dY.segment<6>(27) = s.damping - meanState.damping; + dY.segment<4>(33) = s.g_eta - meanState.g_eta; + + Eigen::Vector3d dZ = setZ[i].measurement - meanZ; + cov += dY * dZ.transpose(); + } + return cov / double(n); +} \ No newline at end of file diff --git a/navigation/ukf_okid/CMakeLists.txt b/navigation/ukf_okid/CMakeLists.txt deleted file mode 100644 index 901ca044b..000000000 --- a/navigation/ukf_okid/CMakeLists.txt +++ /dev/null @@ -1,23 +0,0 @@ -cmake_minimum_required(VERSION 3.8) -project(ukf_python) - -find_package(ament_cmake_python REQUIRED) -find_package(rclpy REQUIRED) -find_package(nav_msgs REQUIRED) -find_package(geometry_msgs REQUIRED) -find_package(vortex_msgs REQUIRED) - -install(DIRECTORY - launch - config - DESTINATION share/${PROJECT_NAME} -) - -ament_python_install_package(${PROJECT_NAME}) - -install(PROGRAMS - ukf_python/ukf_ros.py - DESTINATION lib/${PROJECT_NAME} -) - -ament_package() diff --git a/navigation/ukf_okid/launch/ukf.launch.py b/navigation/ukf_okid/launch/ukf.launch.py deleted file mode 100644 index 5d075259f..000000000 --- a/navigation/ukf_okid/launch/ukf.launch.py +++ /dev/null @@ -1,12 +0,0 @@ -from launch import LaunchDescription -from launch_ros.actions import Node - - -def generate_launch_description() -> LaunchDescription: - ukf_node = Node( - package="ukf_python", - executable="ukf_ros.py", - name="ukf_node", - ) - - return LaunchDescription([ukf_node]) diff --git a/navigation/ukf_okid/ukf_python/__init__.py b/navigation/ukf_okid/ukf_python/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/navigation/ukf_okid/ukf_python/ukf_okid.py b/navigation/ukf_okid/ukf_python/ukf_okid.py deleted file mode 100644 index 240ca42bb..000000000 --- a/navigation/ukf_okid/ukf_python/ukf_okid.py +++ /dev/null @@ -1,130 +0,0 @@ -import numpy as np -from ukf_okid_class import ( - MeasModel, - StateQuat, - covariance_measurement, - covariance_set, - cross_covariance, - mean_measurement, - mean_set, - F_dynamics, -) - - -class UKF: - def __init__(self, x_0: StateQuat, Q): - self.x = x_0 - self.Q = Q - # self.G = G - self.sigma_points_list = None - self.measurement_updated = MeasModel() - self.y_i = None - self.weight = None - self.delta = self.generate_delta_matrix(len(x_0.as_vector()) - 1) - self.cross_correlation = None - self.dt = 0.01 # Time step for dynamics - - def generate_delta_matrix(self, n: float) -> np.ndarray: - """Generates the weight matrix used in the TUKF sigma point generation. - - Parameters: - n (int): The state dimension. - - Returns: - delta (np.ndarray): An n x 2n orthonormal transformation matrix used to generate TUKF sigma points. - """ - delta = np.zeros((n, 2 * n)) - k = 0.00000001 # Tuning parameter to ensure pos def - - for i in range(2 * n): - for j in range(n // 2): - delta[2 * j + 1, i] = ( - np.sqrt(2) * np.sin((2 * j - 1) * ((k * np.pi) / n)) - ) - delta[2 * j, i] = np.sqrt(2) * np.cos((2 * j - 1) * ((k * np.pi) / n)) - - if (n % 2) == 1: - delta[n - 1, i] = (-1) ** i - return delta - - def sigma_points(self, current_state: StateQuat) -> list[StateQuat]: - """Functions that generate the sigma points for the UKF.""" - n = len(current_state.covariance) - - S = np.linalg.cholesky(current_state.covariance + self.Q) - - self.sigma_points_list = [StateQuat() for _ in range(2 * n)] - - for index, state in enumerate(self.sigma_points_list): - delta_x = S @ self.delta[:, index] - state.fill_dynamic_states(current_state.as_vector(), delta_x) - - return self.sigma_points_list - - def unscented_transform(self, current_state: StateQuat, control_force: np.ndarray) -> StateQuat: - """The unscented transform function generates the priori state estimate.""" - self.sigma_points(current_state) - n = len(current_state.covariance) - - self.y_i = [StateQuat() for _ in range(2 * n)] - - for i, sp in enumerate(self.sigma_points_list): - self.y_i[i] = F_dynamics(sp, self.dt, control_force) - - state_estimate = StateQuat() - x = mean_set(self.y_i) - - state_estimate.fill_states(x) - state_estimate.covariance = covariance_set(self.y_i, x) - return state_estimate - - def measurement_update( - self, current_state: StateQuat, measurement: MeasModel - ) -> None: - """Function that updates the state estimate with a measurement. - - Hopefully this is the DVL or GNSS - """ - n = len(current_state.covariance) - z_i = [MeasModel() for _ in range(2 * n)] - - for i, state in enumerate(self.sigma_points_list): - z_i[i] = measurement.H(state) - - self.measurement_updated.measurement = mean_measurement(z_i) - - self.measurement_updated.covariance = covariance_measurement( - z_i, self.measurement_updated.measurement - ) - - self.cross_correlation = cross_covariance( - self.y_i, - current_state.as_vector(), - z_i, - self.measurement_updated.measurement, - ) - - def posteriori_estimate( - self, - current_state: StateQuat, - measurement: MeasModel, - ) -> StateQuat: - """Calculates the posteriori estimate using measurement and the prior estimate.""" - nu_k = MeasModel() - nu_k.measurement = ( - measurement.measurement - self.measurement_updated.measurement - ) - nu_k.covariance = self.measurement_updated.covariance + measurement.covariance - - K_k = np.dot(self.cross_correlation, np.linalg.inv(nu_k.covariance)) - - posteriori_estimate = StateQuat() - - posteriori_estimate.fill_states_different_dim( - current_state.as_vector(), np.dot(K_k, nu_k.measurement) - ) - posteriori_estimate.covariance = current_state.covariance - np.dot( - K_k, np.dot(nu_k.covariance, np.transpose(K_k)) - ) - - return posteriori_estimate diff --git a/navigation/ukf_okid/ukf_python/ukf_okid_class.py b/navigation/ukf_okid/ukf_python/ukf_okid_class.py deleted file mode 100644 index f494e3280..000000000 --- a/navigation/ukf_okid/ukf_python/ukf_okid_class.py +++ /dev/null @@ -1,880 +0,0 @@ -from dataclasses import dataclass, field -from typing import Callable -import numpy as np - - -@dataclass -class okid: - """A class to represent the parameters for the OKID algorithm.""" - - inertia: np.ndarray = field( - default_factory=lambda: np.array( - [0.68, 0.0, 0.0, 0.0, 3.32, 0.0, 0.0, 0.0, 3.34] - ) - ) - added_mass: np.ndarray = field( - default_factory=lambda: np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0]) - ) - damping_linear: np.ndarray = field( - default_factory=lambda: np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0]) - ) - g_eta: np.ndarray = field( - default_factory=lambda: np.array([0.0, 0.0, 0.0, 0.0]) - ) - - def fill(self, state: np.ndarray) -> None: - """Fills the okid_params object with values from a numpy array.""" - self.inertia = state[0:9] - self.added_mass = state[9:15] - self.damping_linear = state[15:21] - self.g_eta = state[21:25] - - def as_vector(self) -> np.ndarray: - """Returns the okid_params as a numpy array.""" - return np.concatenate([self.inertia, self.added_mass, self.damping_linear, self.g_eta]) - - def __add__(self, other: 'okid') -> 'okid': - """Defines the addition operation between two okid_params objects.""" - result = okid() - result.inertia = self.inertia + other.inertia - result.added_mass = self.added_mass + other.added_mass - result.damping_linear = self.damping_linear + other.damping_linear - result.g_eta = self.g_eta + other.g_eta - return result - - def __sub__(self, other: 'okid') -> 'okid': - """Defines the subtraction operation between two okid_params objects.""" - result = okid() - result.inertia = self.inertia - other.inertia - result.added_mass = self.added_mass - other.added_mass - result.damping_linear = self.damping_linear - other.damping_linear - result.g_eta = self.g_eta - other.g_eta - return result - - def __sub__(self, other: np.ndarray) -> 'okid': - """Defines sub between okid_params and np.ndarray.""" - result = okid() - result.inertia = self.inertia - other[0:9] - result.added_mass = self.added_mass - other[9:15] - result.damping_linear = self.damping_linear - other[15:21] - result.g_eta = self.g_eta - other[21:25] - return result - - def __rmul__(self, scalar: float) -> 'okid': - """Defines the multiplication operation between a scalar and okid_params object.""" - result = okid() - result.inertia = scalar * self.inertia - result.added_mass = scalar * self.added_mass - result.damping_linear = scalar * self.damping_linear - result.g_eta = scalar * self.g_eta - return result - - -@dataclass -class StateQuat: - """A class to represent the state to be estimated by the UKF.""" - - position: np.ndarray = field(default_factory=lambda: np.zeros(3)) - orientation: np.ndarray = field(default_factory=lambda: np.array([1, 0, 0, 0])) - velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) - angular_velocity: np.ndarray = field(default_factory=lambda: np.zeros(3)) - okid_params: okid = field(default_factory=okid) - covariance: np.ndarray = field(default_factory=lambda: np.zeros((37, 37))) - - def as_vector(self) -> np.ndarray: - """Returns the StateVector as a numpy array.""" - return np.concatenate( - [ - self.position, - self.orientation, - self.velocity, - self.angular_velocity, - self.okid_params.as_vector(), - ] - ) - - def dynamic_part(self) -> np.ndarray: - """Returns the dynamic part of the state vector.""" - return np.concatenate( - [self.position, self.orientation, self.velocity, self.angular_velocity] - ) - - def nu(self) -> np.ndarray: - """Calculates the nu vector.""" - return np.concatenate([self.velocity, self.angular_velocity]) - - def R_q(self) -> np.ndarray: - """Calculates the rotation matrix from the orientation quaternion.""" - q0, q1, q2, q3 = self.orientation - R = np.array( - [ - [ - 1 - 2 * q2**2 - 2 * q3**2, - 2 * (q1 * q2 - q0 * q3), - 2 * (q0 * q2 + q1 * q3), - ], - [ - 2 * (q1 * q2 + q0 * q3), - 1 - 2 * q1**2 - 2 * q3**2, - 2 * (q2 * q3 - q0 * q1), - ], - [ - 2 * (q1 * q3 - q0 * q2), - 2 * (q0 * q1 + q2 * q3), - 1 - 2 * q1**2 - 2 * q2**2, - ], - ] - ) - return R - - def fill_states(self, state: np.ndarray) -> None: - """Fills the state vector with the values from a numpy array.""" - self.position = state[0:3] - self.orientation = state[3:7] - self.velocity = state[7:10] - self.angular_velocity = state[10:13] - self.okid_params.fill(state[13:]) - - def fill_dynamic_states(self, state: np.ndarray, state_euler: np.ndarray) -> None: - """Fills only the dynamic part of the state vector with the values from a numpy array.""" - self.position = state[0:3] + state_euler[0:3] - self.orientation = quaternion_super_product( - state[3:7], euler_to_quat(state_euler[3:6]) - ) - self.velocity = state[7:10] + state_euler[6:9] - self.angular_velocity = state[10:13] + state_euler[9:12] - self.okid_params.fill(state[13:] + state_euler[12:]) - - def fill_states_different_dim( - self, state: np.ndarray, state_euler: np.ndarray - ) -> None: - """Fills states when the state vector has different dimensions than the default state vector.""" - self.position = state[0:3] + state_euler[0:3] - self.orientation = quaternion_super_product( - state[3:7], euler_to_quat(state_euler[3:6]) - ) - self.velocity = state[7:10] + state_euler[6:9] - self.angular_velocity = state[10:13] + state_euler[9:12] - self.okid_params.fill(state[13:] + state_euler[12:]) - - def subtract(self, other: 'StateQuat', error_ori: 'np.ndarray') -> np.ndarray: - """Subtracts two StateQuat objects, returning the difference with Euler angles.""" - new_array = np.zeros(len(self.as_vector()) - 1) - new_array[:3] = self.position - other.position - new_array[3:6] = error_ori - new_array[6:9] = self.velocity - other.velocity - new_array[9:12] = self.angular_velocity - other.angular_velocity - new_array[12:] = self.okid_params.as_vector() - other.okid_params.as_vector() - - return new_array - - def __add__(self, other: 'StateQuat') -> 'StateQuat': - """Adds two StateQuat objects.""" - new_state = StateQuat() - new_state.position = self.position + other.position - new_state.orientation = quaternion_super_product( - self.orientation, other.orientation - ) - new_state.velocity = self.velocity + other.velocity - new_state.angular_velocity = self.angular_velocity + other.angular_velocity - new_state.okid_params = self.okid_params + other.okid_params - - return new_state - - def __sub__(self, other: 'StateQuat') -> 'StateQuat': - """Subtracts two StateQuat objects.""" - new_state = StateQuat() - new_state.position = self.position - other.position - new_state.orientation = quaternion_error(self.orientation, other.orientation) - new_state.velocity = self.velocity - other.velocity - new_state.angular_velocity = self.angular_velocity - other.angular_velocity - new_state.okid_params = self.okid_params - other.okid_params - - return new_state.as_vector() - - def __rmul__(self, scalar: float) -> 'StateQuat': - """Multiplies the StateQuat object by a scalar.""" - new_state = StateQuat() - new_state.position = scalar * self.position - new_state.orientation = quat_norm(scalar * self.orientation) - new_state.velocity = scalar * self.velocity - new_state.angular_velocity = scalar * self.angular_velocity - new_state.okid_params = scalar * self.okid_params - - return new_state - - def insert_weights(self, weights: np.ndarray) -> np.ndarray: - """Inserts the weights into the covariance matrix.""" - new_state = StateQuat() - new_state.position = self.position - weights[:3] - new_state.orientation = quaternion_error( - self.orientation, euler_to_quat(weights[3:6]) - ) - new_state.velocity = self.velocity - weights[6:9] - new_state.angular_velocity = self.angular_velocity - weights[9:12] - new_state.okid_params = self.okid_params - weights[12:] - - return new_state.as_vector() - - def add_without_quaternions(self, other: 'StateQuat') -> None: - """Adds elements into the state vector without considering the quaternions.""" - self.position += other.position - self.velocity += other.velocity - self.angular_velocity += other.angular_velocity - self.okid_params += other.okid_params - - -@dataclass -class MeasModel: - """A class defined for a general measurement model.""" - measurement: np.ndarray = field(default_factory=lambda: np.zeros(3)) - covariance: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) - H: Callable[["StateQuat"], "MeasModel"] | None = None - - def __post_init__(self): - """Initialize H with a default measurement function if none provided.""" - if self.H is None: - self.H = self._default_H - - def _default_H(self, state: StateQuat) -> 'MeasModel': - """Default measurement function that returns velocity.""" - H_matrix = np.zeros((3, 13)) - H_matrix[:, 7:10] = np.eye(3) - z_i = MeasModel() - z_i.measurement = np.dot(H_matrix, state.dynamic_part()) - return z_i - - def __add__(self, other: 'MeasModel') -> 'MeasModel': - """Defines the addition operation between two MeasModel objects.""" - result = MeasModel() - result.measurement = self.measurement + other.measurement - return result - - def __rmul__(self, scalar: float) -> 'MeasModel': - """Defines multiplication between scalar value and MeasModel object.""" - result = MeasModel() - result.measurement = scalar * self.measurement - return result - - def __sub__(self, other: 'MeasModel') -> 'MeasModel': - """Defines the subtraction between two MeasModel objects.""" - result = MeasModel() - result.measurement = self.measurement - other.measurement - return result - - -@dataclass -class process_model: - """A class defined for a general process model.""" - - state_vector: StateQuat = field(default_factory=StateQuat) - state_vector_dot: StateQuat = field(default_factory=StateQuat) - state_vector_prev: StateQuat = field(default_factory=StateQuat) - Control_input: np.ndarray = field(default_factory=lambda: np.zeros(6)) - mass_interia_matrix: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) - added_mass: np.ndarray = field(default_factory=lambda: np.zeros(6)) - damping_linear: np.ndarray = field(default_factory=lambda: np.zeros(6)) - damping_nonlinear: np.ndarray = field(default_factory=lambda: np.zeros(6)) - m: float = 0.0 - inertia: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) - r_b_bg: np.ndarray = field(default_factory=lambda: np.zeros(3)) - dt: float = 0.0 - integral_error_position: np.ndarray = field(default_factory=lambda: np.zeros(3)) - integral_error_orientation: np.ndarray = field(default_factory=lambda: np.zeros(4)) - prev_position_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) - prev_orientation_error: np.ndarray = field(default_factory=lambda: np.zeros(3)) - - def R(self) -> np.ndarray: - """Calculates the rotation matrix.""" - nu, e_1, e_2, e_3 = self.state_vector.orientation - R = np.array( - [ - [ - 1 - 2 * e_2**2 - 2 * e_3**2, - 2 * e_1 * e_2 - 2 * nu * e_3, - 2 * e_1 * e_3 + 2 * nu * e_2, - ], - [ - 2 * e_1 * e_2 + 2 * nu * e_3, - 1 - 2 * e_1**2 - 2 * e_3**2, - 2 * e_2 * e_3 - 2 * nu * e_1, - ], - [ - 2 * e_1 * e_3 - 2 * nu * e_2, - 2 * e_2 * e_3 + 2 * nu * e_1, - 1 - 2 * e_1**2 - 2 * e_2**2, - ], - ] - ) - return R - - def T(self) -> np.ndarray: - """Calculates the transformation matrix.""" - nu, e_1, e_2, e_3 = self.state_vector.orientation - T = 0.5 * np.array( - [[-e_1, -e_2, -e_3], [nu, -e_3, e_2], [e_3, nu, -e_1], [-e_2, e_1, nu]] - ) - return T - - def Crb(self) -> np.ndarray: - """Calculates the Coriolis matrix.""" - ang_vel = self.state_vector.angular_velocity - ang_vel_skew = skew_symmetric(ang_vel) - lever_arm_skew = skew_symmetric(self.r_b_bg) - Crb = np.zeros((6, 6)) - Crb[0:3, 0:3] = self.m * ang_vel_skew - Crb[3:6, 3:6] = -skew_symmetric(np.dot(self.inertia, ang_vel)) - Crb[0:3, 3:6] = -self.m * np.dot(ang_vel_skew, lever_arm_skew) - Crb[3:6, 0:3] = self.m * np.dot(lever_arm_skew, ang_vel_skew) - return Crb - - def D(self) -> np.ndarray: - """Calculates the damping matrix.""" - D_l = -np.diag(self.damping_linear) - D_nl = -np.diag(self.damping_nonlinear) * np.abs(self.state_vector.nu()) - return D_l + D_nl - - def model_prediction(self, state: StateQuat) -> None: - """Calculates the model of the system.""" - self.state_vector = state - self.state_vector_dot.position = np.dot(self.R(), self.state_vector.velocity) - self.state_vector_dot.orientation = np.dot( - self.T(), self.state_vector.angular_velocity - ) - Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ ( - self.Control_input - - np.dot(self.Crb(), self.state_vector.nu()) - - np.dot(self.D(), self.state_vector.nu()) - ) - self.state_vector_dot.velocity = Nu[:3] - self.state_vector_dot.angular_velocity = Nu[3:] - - def euler_forward(self) -> StateQuat: - """Calculates the forward Euler integration.""" - self.state_vector.position = ( - self.state_vector_prev.position + self.state_vector_dot.position * self.dt - ) - self.state_vector.orientation = quat_norm( - self.state_vector_prev.orientation - + self.state_vector_dot.orientation * self.dt - ) - self.state_vector.velocity = ( - self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt - ) - self.state_vector.angular_velocity = ( - self.state_vector_prev.angular_velocity - + self.state_vector_dot.angular_velocity * self.dt - ) - return self.state_vector - - -@dataclass -class okid_process_model: - state_vector: StateQuat = field(default_factory=StateQuat) - state_vector_dot: StateQuat = field(default_factory=StateQuat) - state_vector_prev: StateQuat = field(default_factory=StateQuat) - Control_input: np.ndarray = field(default_factory=lambda: np.zeros(6)) - mass_interia_matrix: np.ndarray = field(default_factory=lambda: np.zeros((6, 6))) - added_mass: np.ndarray = field(default_factory=lambda: np.zeros(6)) - damping_linear: np.ndarray = field(default_factory=lambda: np.zeros(6)) - m: float = 30.0 - inertia: np.ndarray = field(default_factory=lambda: np.zeros((3, 3))) - r_b_bg: np.ndarray = field(default_factory=lambda: np.zeros(3)) - dt: float = 0.01 - - def R(self) -> np.ndarray: - """Calculates the rotation matrix.""" - nu, e_1, e_2, e_3 = self.state_vector.orientation - R = np.array( - [ - [ - 1 - 2 * e_2**2 - 2 * e_3**2, - 2 * e_1 * e_2 - 2 * nu * e_3, - 2 * e_1 * e_3 + 2 * nu * e_2, - ], - [ - 2 * e_1 * e_2 + 2 * nu * e_3, - 1 - 2 * e_1**2 - 2 * e_3**2, - 2 * e_2 * e_3 - 2 * nu * e_1, - ], - [ - 2 * e_1 * e_3 - 2 * nu * e_2, - 2 * e_2 * e_3 + 2 * nu * e_1, - 1 - 2 * e_1**2 - 2 * e_2**2, - ], - ] - ) - return R - - def T(self) -> np.ndarray: - """Calculates the transformation matrix.""" - nu, e_1, e_2, e_3 = self.state_vector.orientation - T = 0.5 * np.array( - [[-e_1, -e_2, -e_3], [nu, -e_3, e_2], [e_3, nu, -e_1], [-e_2, e_1, nu]] - ) - return T - - def Crb(self) -> np.ndarray: - """Calculates the Coriolis matrix.""" - ang_vel = self.state_vector.angular_velocity - ang_vel_skew = skew_symmetric(ang_vel) - lever_arm_skew = skew_symmetric(self.r_b_bg) - Crb = np.zeros((6, 6)) - Crb[0:3, 0:3] = self.m * ang_vel_skew - Crb[3:6, 3:6] = -skew_symmetric(np.dot(self.inertia, ang_vel)) - Crb[0:3, 3:6] = -self.m * np.dot(ang_vel_skew, lever_arm_skew) - Crb[3:6, 0:3] = self.m * np.dot(lever_arm_skew, ang_vel_skew) - return Crb - - def D(self) -> np.ndarray: - """Calculates the damping matrix.""" - D_l = -np.diag(self.damping_linear) - - return D_l - - def model_prediction(self, state: StateQuat) -> None: - """Calculates the model of the system.""" - self.state_vector = state - """ - separate out the different okid values - """ - self.inertia = state.okid_params.inertia.reshape((3, 3)) - self.added_mass = state.okid_params.added_mass - self.damping_linear = state.okid_params.damping_linear - - self.state_vector_dot.position = np.dot(self.R(), self.state_vector.velocity) - self.state_vector_dot.orientation = np.dot( - self.T(), self.state_vector.angular_velocity - ) - Nu = np.linalg.inv(self.mass_interia_matrix + np.diag(self.added_mass)) @ ( - self.Control_input - - np.dot(self.Crb(), self.state_vector.nu()) - - np.dot(self.D(), self.state_vector.nu()) - ) - self.state_vector_dot.velocity = Nu[:3] - self.state_vector_dot.angular_velocity = Nu[3:] - - def euler_forward(self) -> None: - """Calculates the forward Euler integration.""" - self.state_vector.position = ( - self.state_vector_prev.position + self.state_vector_dot.position * self.dt - ) - self.state_vector.orientation = quat_norm( - self.state_vector_prev.orientation - + self.state_vector_dot.orientation * self.dt - ) - self.state_vector.velocity = ( - self.state_vector_prev.velocity + self.state_vector_dot.velocity * self.dt - ) - self.state_vector.angular_velocity = ( - self.state_vector_prev.angular_velocity - + self.state_vector_dot.angular_velocity * self.dt - ) - return self.state_vector - - -# ----------------------------------------------------------- - -def R_q(orientation: np.ndarray) -> np.ndarray: - """Calculates the rotation matrix from the orientation quaternion.""" - q0, q1, q2, q3 = orientation - R = np.array( - [ - [1 - 2 * q2**2 - 2 * q3**2, 2 * (q1 * q2 - q0 * q3), 2 * (q0 * q2 + q1 * q3)], - [2 * (q1 * q2 + q0 * q3), 1 - 2 * q1**2 - 2 * q3**2, 2 * (q2 * q3 - q0 * q1)], - [2 * (q1 * q3 - q0 * q2), 2 * (q0 * q1 + q2 * q3), 1 - 2 * q1**2 - 2 * q2**2], - ] - ) - return R - -def T_q(orientation: np.ndarray) -> np.ndarray: - """Calculates the transformation matrix from the orientation quaternion.""" - q0, q1, q2, q3 = orientation - T = 0.5 * np.array( - [[-q1, -q2, -q3], [q0, -q3, q2], [q3, q0, -q1], [-q2, q1, q0]] - ) - return T - -def M_rb(inertia: np.ndarray) -> np.ndarray: - m = 30.0 - inertia = inertia.reshape((3, 3)) - r_b_bg = np.array([0.01, 0.0, 0.02]) - M_rb = np.zeros((6, 6)) - M_rb[0:3, 0:3] = m * np.eye(3) - M_rb[3:6, 3:6] = inertia - M_rb[0:3, 3:6] = -m * skew_symmetric(r_b_bg) - M_rb[3:6, 0:3] = m * skew_symmetric(r_b_bg) - return M_rb - -def M_a(added_mass: np.ndarray) -> np.ndarray: - """Calculates the added mass matrix.""" - M_a = np.zeros((6, 6)) - M_a[0:3, 0:3] = np.diag(added_mass[0:3]) - M_a[3:6, 3:6] = np.diag(added_mass[3:6]) - return M_a - -def C_rb(inertia: np.ndarray, angular_velocity: np.ndarray) -> np.ndarray: - """Calculates the Coriolis matrix.""" - m = 30.0 - r_b_bg = np.array([0.01, 0.0, 0.02]) - inertia = inertia.reshape((3, 3)) - C_rb = np.zeros((6, 6)) - - C_rb[0:3, 0:3] = m * skew_symmetric(angular_velocity) - C_rb[3:6, 3:6] = -skew_symmetric(np.dot(inertia, angular_velocity)) - C_rb[0:3, 3:6] = -m * skew_symmetric(angular_velocity) @ skew_symmetric(r_b_bg) - C_rb[3:6, 0:3] = m * skew_symmetric(r_b_bg) @ skew_symmetric(angular_velocity) - return C_rb - -def C_a(added_mass: np.ndarray, angular_velocity: np.ndarray, velocity: np.ndarray) -> np.ndarray: - """Calculates the added mass Coriolis matrix.""" - C_a = np.zeros((6, 6)) - A11 = np.diag(added_mass[0:3]) - A22 = np.diag(added_mass[3:6]) - C_a[3:6,3:6] = - skew_symmetric(A22 @ angular_velocity) - C_a[0:3,3:6] = - skew_symmetric(A11 @ velocity) - C_a[3:6,0:3] = - skew_symmetric(A11 @ velocity) - return C_a - -def D_linear(damping_linear: np.ndarray) -> np.ndarray: - """Calculates the linear damping matrix.""" - D = np.zeros((6, 6)) - D[0:3, 0:3] = -np.diag(damping_linear[0:3]) - D[3:6, 3:6] = -np.diag(damping_linear[3:6]) - return D - -def g_eta(g_eta: np.ndarray, orientation: np.ndarray) -> np.ndarray: - """Calculates the g_eta matrix.""" - Delta_WB = g_eta[0] - M_x = g_eta[1] - M_y = g_eta[2] - M_z = g_eta[3] - - q_0 = orientation[0] - q_1 = orientation[1] - q_2 = orientation[2] - q_3 = orientation[3] - - R1 = (2*(q_1*q_3 - q_0*q_2)) - R2 = (2*(q_2*q_3 + q_0*q_1)) - R3 = (1 - 2*(q_1**2 + q_2**2)) - G_eta = np.zeros((6,1)) - G_eta[0] = - Delta_WB * R1 - G_eta[1] = - Delta_WB * R2 - G_eta[2] = - Delta_WB * R3 - - G_eta[3] = -M_y * R3 + M_z * R2 - G_eta[4] = -M_z * R1 + M_x * R3 - G_eta[5] = -M_x * R2 + M_y * R1 - - return G_eta - -def F_dynamics( - state: StateQuat, - dt: float, - control_input: np.ndarray) -> np.ndarray: - - """Calculates the dynamics of the system.""" - m_rb = M_rb(state.okid_params.inertia) - m_a = M_a(state.okid_params.added_mass) - c_rb = C_rb(state.okid_params.inertia, state.angular_velocity) - c_a = C_a(state.okid_params.added_mass, state.angular_velocity, state.velocity) - D_l = D_linear(state.okid_params.damping_linear) - g_eta_ = g_eta(state.okid_params.g_eta, state.orientation) - r_q = R_q(state.orientation) - t_q = T_q(state.orientation) - Crb = c_rb + c_a - Mrb = m_rb + m_a - M_inv = np.linalg.inv(Mrb) - - - # Calculate the new state - state_dot = StateQuat() - state_dot.position = np.dot(r_q, state.velocity) - state_dot.orientation = np.dot(t_q, state.angular_velocity) - Nu = M_inv @ (control_input - np.dot(Crb, state.nu()) - np.dot(D_l, state.nu()) - g_eta_.flatten()) - - state_dot.velocity = Nu[:3] - state_dot.angular_velocity = Nu[3:6] - state_dot.okid_params.added_mass = state.okid_params.added_mass - state_dot.okid_params.damping_linear = state.okid_params.damping_linear - state_dot.okid_params.inertia = state.okid_params.inertia - state_dot.okid_params.g_eta = state.okid_params.g_eta - - # Update the state using Euler integration - state.position += state_dot.position * dt - state.orientation = quat_norm( - state.orientation + state_dot.orientation * dt - ) - state.velocity += state_dot.velocity * dt - state.angular_velocity += state_dot.angular_velocity * dt - state.okid_params.added_mass = state.okid_params.added_mass - state.okid_params.damping_linear = state.okid_params.damping_linear - state.okid_params.inertia = state.okid_params.inertia - state.okid_params.g_eta = state.okid_params.g_eta - return state -# ----------------------------------------------------------- - - -def euler_to_quat(euler_angles: np.ndarray) -> np.ndarray: - """Converts Euler angles to a quaternion.""" - psi, theta, phi = euler_angles - c_psi = np.cos(psi / 2) - s_psi = np.sin(psi / 2) - c_theta = np.cos(theta / 2) - s_theta = np.sin(theta / 2) - c_phi = np.cos(phi / 2) - s_phi = np.sin(phi / 2) - - quat = np.array( - [ - c_psi * c_theta * c_phi + s_psi * s_theta * s_phi, - c_psi * c_theta * s_phi - s_psi * s_theta * c_phi, - s_psi * c_theta * s_phi + c_psi * s_theta * c_phi, - s_psi * c_theta * c_phi - c_psi * s_theta * s_phi, - ] - ) - - return quat - - -def quat_to_euler(quat: np.ndarray) -> np.ndarray: - """Converts a quaternion to Euler angles.""" - nu, eta_1, eta_2, eta_3 = quat - - phi = np.arctan2(2 * (eta_2 * eta_3 + nu * eta_1), 1 - 2 * (eta_1**2 + eta_2**2)) - theta = -np.arcsin(2 * (eta_1 * eta_3 - nu * eta_2)) - psi = np.arctan2(2 * (nu * eta_3 + eta_1 * eta_2), 1 - 2 * (eta_2**2 + eta_3**2)) - - return np.array([phi, theta, psi]) - - -def quat_norm(quat: np.ndarray) -> np.ndarray: - """Function that normalizes a quaternion.""" - quat = quat / np.linalg.norm(quat) - - return quat - - -def skew_symmetric(vector: np.ndarray) -> np.ndarray: - """Calculates the skew symmetric matrix of a vector. - - Args: - vector (np.ndarray): The vector. - - Returns: - np.ndarray: The skew symmetric matrix. - """ - return np.array( - [ - [0, -vector[2], vector[1]], - [vector[2], 0, -vector[0]], - [-vector[1], vector[0], 0], - ] - ) - - -def quaternion_super_product(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: - """Calculates the quaternion super product of two quaternions. - - Args: - q1 (np.ndarray): The first quaternion. - q2 (np.ndarray): The second quaternion. - - Returns: - np.ndarray: The quaternion super product. - """ - eta_0, e_0_x, e_0_y, e_0_z = q1 - eta_1, e_1_x, e_1_y, e_1_z = q2 - - e_0 = np.array([e_0_x, e_0_y, e_0_z]) - e_1 = np.array([e_1_x, e_1_y, e_1_z]) - - eta_new = eta_0 * eta_1 - (e_0_x * e_1_x + e_0_y * e_1_y + e_0_z * e_1_z) - nu_new = e_1 * eta_0 + e_0 * eta_1 + np.dot(skew_symmetric(e_0), e_1) - - q_new = quat_norm(np.array([eta_new, nu_new[0], nu_new[1], nu_new[2]])) - - return q_new - - -def quaternion_error(quat_1: np.ndarray, quat_2: np.ndarray) -> np.ndarray: - """Calculates the error between two quaternions.""" - quat_2_inv = np.array([quat_2[0], -quat_2[1], -quat_2[2], -quat_2[3]]) - - error_quat = quaternion_super_product(quat_1, quat_2_inv) - - return error_quat - - -def iterative_quaternion_mean_statequat( - state_list: list[StateQuat], tol: float = 1e-6, max_iter: int = 100 -) -> np.ndarray: - """Computes the iterative mean of quaternion orientations from StateQuat objects. - - Args: - state_list: List of StateQuat objects - tol: Convergence tolerance - max_iter: Maximum iterations - - Returns: - Mean quaternion as numpy array - """ - sigma_quats = [state.orientation for state in state_list] - n = len(state_list) - - mean_q = sigma_quats[0].copy() - - for _ in range(max_iter): - weighted_error_vectors = [] - for i, q in enumerate(sigma_quats): - mean_q_conj = np.array([mean_q[0], -mean_q[1], -mean_q[2], -mean_q[3]]) - e = quaternion_super_product(q, mean_q_conj) - - e0_clipped = np.clip(e[0], -1.0, 1.0) - angle = 2 * np.arccos(e0_clipped) - if np.abs(angle) < 1e-8: - error_vec = np.zeros(3) - else: - error_vec = (angle / np.sin(angle / 2)) * e[1:4] - weighted_error_vectors.append(error_vec) - - error_avg = (1 / n) * np.sum(weighted_error_vectors, axis=0) - if np.linalg.norm(error_avg) < tol: - break - - error_norm = np.linalg.norm(error_avg) - if error_norm > 0: - delta_q = np.array( - [ - np.cos(error_norm / 2), - *(np.sin(error_norm / 2) * (error_avg / error_norm)), - ] - ) - else: - delta_q = np.array([1.0, 0.0, 0.0, 0.0]) - - mean_q = quaternion_super_product(delta_q, mean_q) - mean_q = quat_norm(mean_q) - - return mean_q - - -def mean_set(set_points: list[StateQuat]) -> np.ndarray: - """Function calculates the mean vector of a set of points. - - Args: - set_points (list[StateQuat]): List of StateQuat objects - - Returns: - np.ndarray: The mean vector - """ - n = len(set_points) - mean_value = StateQuat() - - for state in set_points: - mean_value.add_without_quaternions(state) - - mean_value.position = (1 / n) * mean_value.position - mean_value.velocity = (1 / n) * mean_value.velocity - mean_value.angular_velocity = (1 / n) * mean_value.angular_velocity - mean_value.okid_params = (1 / n) * mean_value.okid_params - - mean_value.orientation = iterative_quaternion_mean_statequat(set_points) - return mean_value.as_vector() - - -def mean_measurement(set_points: list[MeasModel]) -> np.ndarray: - """Function that calculates the mean of a set of points.""" - n = len(set_points) - mean_value = MeasModel() - - for state in set_points: - mean_value = mean_value + state - - mean_value = (1 / n) * mean_value - - return mean_value.measurement - - -def covariance_set(set_points: list[StateQuat], mean: np.ndarray) -> np.ndarray: - """Function that calculates the covariance of a set of points.""" - n = len(set_points) - covariance = np.zeros(set_points[0].covariance.shape) - - mean_quat = StateQuat() - mean_quat.fill_states(mean) - - mean_q = mean_quat.orientation - - for state in set_points: - q = state.orientation - diff_q = quaternion_error(q, mean_q) - - e0_clipped = np.clip(diff_q[0], -1.0, 1.0) - angle = 2.0 * np.arccos(e0_clipped) - if abs(angle) < 1e-8: - e_vec = np.zeros(3) - else: - e_vec = (angle / np.sin(angle / 2)) * diff_q[1:4] - - covariance += np.outer( - state.subtract(mean_quat, e_vec), state.subtract(mean_quat, e_vec) - ) - - covariance = (1 / (n)) * covariance - - return covariance - - -def covariance_measurement(set_points: list[MeasModel], mean: np.ndarray) -> np.ndarray: - """Function that calculates the covariance of a set of points.""" - n = len(set_points) - co_size = len(set_points[0].measurement) - covariance = np.zeros((co_size, co_size)) - - mean_meas = MeasModel() - mean_meas.measurement = mean - - for state in set_points: - temp_state = state - mean_meas - covariance += np.outer(temp_state.measurement, temp_state.measurement) - - covariance = (1 / n) * covariance - - return covariance - - -def cross_covariance( - set_y: list[StateQuat], - mean_y: np.ndarray, - set_z: list[MeasModel], - mean_z: np.ndarray, -) -> np.ndarray: - """Calculates the cross covariance between the measurement and state prediction.""" - n = len(set_y) - - cross_covariance = np.zeros((len(mean_y) - 1, len(mean_z))) - mean_quat = StateQuat() - mean_quat.fill_states(mean_y) - - mean_q = mean_quat.orientation - - for i in range(n): - q = set_y[i].orientation - diff_q = quaternion_error(q, mean_q) - - e0_clipped = np.clip(diff_q[0], -1.0, 1.0) - angle = 2.0 * np.arccos(e0_clipped) - if abs(angle) < 1e-8: - e_vec = np.zeros(3) - else: - e_vec = (angle / np.sin(angle / 2)) * diff_q[1:4] - - cross_covariance += np.outer( - set_y[i].subtract(mean_quat, e_vec), set_z[i].measurement - mean_z - ) - - cross_covariance = (1 / n) * cross_covariance - - return cross_covariance diff --git a/navigation/ukf_okid/ukf_python/ukf_ros.py b/navigation/ukf_okid/ukf_python/ukf_ros.py deleted file mode 100755 index a40c2f7c3..000000000 --- a/navigation/ukf_okid/ukf_python/ukf_ros.py +++ /dev/null @@ -1,159 +0,0 @@ -#!/usr/bin/env python3 -import numpy as np -import rclpy -from geometry_msgs.msg import TwistWithCovarianceStamped, WrenchStamped -from nav_msgs.msg import Odometry -from rclpy.node import Node -from rclpy.qos import HistoryPolicy, QoSProfile, ReliabilityPolicy -from ukf_okid import UKF -from ukf_okid_class import MeasModel, StateQuat, process_model - - -class UKFNode(Node): - def __init__(self): - super().__init__("UKFNode") - - best_effort_qos = QoSProfile( - reliability=ReliabilityPolicy.BEST_EFFORT, - history=HistoryPolicy.KEEP_LAST, - depth=1, - ) - - # subscribers - self.dvl_subscriber = self.create_subscription( - TwistWithCovarianceStamped, - "/orca/twist", - self.dvl_callback, - qos_profile=best_effort_qos, - ) - - self.control_input = self.create_subscription( - WrenchStamped, - "/orca/wrench_input", - self.control_callback, - qos_profile=best_effort_qos, - ) - - self.odom_publish = self.create_publisher( - Odometry, "/orca/odometry", qos_profile=best_effort_qos - ) - dt = self.declare_parameter("dt", 0.01).get_parameter_value().double_value - self.control_timer = self.create_timer(dt, self.odom_publisher) - - self.current_state = StateQuat() - x0 = np.zeros(13) - x0[3] = 1.0 # quaternion: [1, 0, 0, 0] - P0 = np.eye(12) * 0.5 - self.ukf_model = process_model() - self.ukf_model.dt = 0.01 - self.ukf_model.mass_interia_matrix = np.array( - [ - [30.0, 0.0, 0.0, 0.0, 0.0, 0.6], - [0.0, 30.0, 0.0, 0.0, -0.6, 0.3], - [0.0, 0.0, 30.0, 0.6, 0.3, 0.0], - [0.0, 0.0, 0.6, 0.68, 0.0, 0.0], - [0.0, -0.6, 0.3, 0.0, 3.32, 0.0], - [0.6, 0.3, 0.0, 0.0, 0.0, 3.34], - ] - ) - self.ukf_model.m = 30.0 - self.ukf_model.r_b_bg = np.array([0.01, 0.0, 0.02]) - self.ukf_model.inertia = np.diag([0.68, 3.32, 3.34]) - self.ukf_model.damping_linear = np.array([0.01] * 6) - # self.ukf_model.added_mass = np.diag([1.0, 1.0, 1.0, 2.0, 2.0, 2.0]) - - Q = np.diag([0.02, 0.02, 0.02, 0.02, 0.02, 0.02, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) - - self.ukf = UKF(self.ukf_model, x0, P0, Q) - self.ukf_flagg = False - - def dvl_callback(self, msg: TwistWithCovarianceStamped): - # unpack msg - dvl_measurement = MeasModel() - # Print received DVL data to console - # self.get_logger().info(f"DVL data received: x={msg.twist.twist.linear.x}, y={msg.twist.twist.linear.y}, z={msg.twist.twist.linear.z}") - dvl_measurement.measurement = np.array( - [ - msg.twist.twist.linear.x, - msg.twist.twist.linear.y, - msg.twist.twist.linear.z, - ] - ) - dvl_measurement.covariance = np.array( - [ - [ - msg.twist.covariance[0], - msg.twist.covariance[1], - msg.twist.covariance[3], - ], - [ - msg.twist.covariance[6], - msg.twist.covariance[7], - msg.twist.covariance[8], - ], - [ - msg.twist.covariance[12], - msg.twist.covariance[13], - msg.twist.covariance[14], - ], - ] - ) - - self.ukf.measurement_update(self.current_state, dvl_measurement) - self.current_state = self.ukf.posteriori_estimate( - self.current_state, dvl_measurement - ) - self.ukf_flagg = True - - def control_callback(self, msg: WrenchStamped): - # unpack message - control_array = np.array( - [ - msg.wrench.force.x, - msg.wrench.force.y, - msg.wrench.force.z, - msg.wrench.torque.x, - msg.wrench.torque.y, - msg.wrench.torque.z, - ] - ) - self.ukf_model.Control_input = control_array - - def odom_publisher(self): - msg = Odometry() - - if self.ukf_flagg == False: - self.current_state = self.ukf.unscented_transform(self.current_state) - else: - self.ukf_flagg = False - - msg.header.stamp = self.get_clock().now().to_msg() - msg.header.frame_id = "odom" - msg.child_frame_id = "base_link" - - msg.pose.pose.position.x = self.current_state.position[0] - msg.pose.pose.position.y = self.current_state.position[1] - msg.pose.pose.position.z = self.current_state.position[2] - msg.pose.pose.orientation.w = self.current_state.orientation[0] - msg.pose.pose.orientation.x = self.current_state.orientation[1] - msg.pose.pose.orientation.y = self.current_state.orientation[2] - msg.pose.pose.orientation.z = self.current_state.orientation[3] - msg.twist.twist.linear.x = self.current_state.velocity[0] - msg.twist.twist.linear.y = self.current_state.velocity[1] - msg.twist.twist.linear.z = self.current_state.velocity[2] - msg.twist.twist.angular.x = self.current_state.angular_velocity[0] - msg.twist.twist.angular.y = self.current_state.angular_velocity[1] - msg.twist.twist.angular.z = self.current_state.angular_velocity[2] - - self.odom_publish.publish(msg) - - -def main(args=None): - rclpy.init(args=args) - ukf_node = UKFNode() - rclpy.spin(ukf_node) - rclpy.shutdown() - - -if __name__ == "__main__": - main() diff --git a/navigation/ukf_okid/ukf_python/ukf_test.py b/navigation/ukf_okid/ukf_python/ukf_test.py deleted file mode 100644 index e664bd848..000000000 --- a/navigation/ukf_okid/ukf_python/ukf_test.py +++ /dev/null @@ -1,27 +0,0 @@ -import numpy as np -def generate_delta_matrix(n: int) -> np.ndarray: - if n < 1: - raise ValueError("n must be a positive integer") - - delta = np.zeros((n, 2 * n)) - r_max = n // 2 # floor(n/2) - sq2 = np.sqrt(2.0) - - for k in range(1, 2 * n + 1): # k = 1 … 2n - for r in range(1, r_max + 1): - row_cos = 2 * r - 2 # 0‑based index for γ_{k,2r‑1} - row_sin = 2 * r - 1 # 0‑based index for γ_{k,2r} - angle = (2 * r - 1) * k * np.pi / n - delta[row_cos, k - 1] = sq2 * np.cos(angle) - delta[row_sin, k - 1] = sq2 * np.sin(angle) - - if n % 2 == 1: # extra entry when n is odd - delta[n - 1, k - 1] = (-1) ** k - - return delta - -a1 = np.array([1, 0, 1]) -a2 = np.array([1, 1, 0]) - -a3 = np.outer(a1, a2) -print(a3) \ No newline at end of file diff --git a/navigation/ukf_okid/ukf_python/ukf_test_2.py b/navigation/ukf_okid/ukf_python/ukf_test_2.py deleted file mode 100644 index 0a2d5b2fe..000000000 --- a/navigation/ukf_okid/ukf_python/ukf_test_2.py +++ /dev/null @@ -1,229 +0,0 @@ -import numpy as np -import ukf_okid_class as ukf -from ukf_okid import UKF -from mpl_toolkits.mplot3d import Axes3D -import time -import math -from ukf_utils import print_StateQuat, print_matrix - -import matplotlib.pyplot as plt - -# Initialize UKF with StateQuat -initial_position = np.array([0.0, 0.0, 0.0]) # x, y, z -initial_velocity = np.array([0.0, 0.0, 0.0]) # vx, vy, vz -initial_quaternion = np.array([1.0, 0.0, 0.0, 0.0]) # w, x, y, z (identity quaternion) -initial_angular_velocity = np.array([0.0, 0.0, 0.0]) # wx, wy, wz -initial_g_eta = np.array([1.2, 0.3, 0.3, 0.3]) # g_eta parameters -initial_covariance = np.eye(37) * 20.0 # Initial covariance matrix - -# Create StateQuat object -state = ukf.StateQuat(initial_position, initial_quaternion, initial_velocity, initial_angular_velocity) -state.okid_params.g_eta = initial_g_eta -state.covariance = initial_covariance - -real_state = ukf.StateQuat(initial_position, initial_quaternion, initial_velocity, initial_angular_velocity) -real_state.okid_params.g_eta = np.array([1.2, 0.3, 0.3, 0.3]) - -UKF_model = UKF(state, Q=10.0 * np.eye(37)) # Process noise covariance -dvl_measurement = ukf.MeasModel() - -def ang_h(state: ukf.StateQuat) -> 'ukf.MeasModel': - H_matrix = np.zeros((3, 13)) - H_matrix[:, 10:13] = np.eye(3) - z_i = ukf.MeasModel() - z_i.measurement = np.dot(H_matrix, state.dynamic_part()) - return z_i - -ang_measurement = ukf.MeasModel(H=ang_h) - -# UKF parameters -dt = 0.01 # time step -sim_time = 1.0 # total simulation time -steps = int(sim_time / dt) - -# Storage for trajectory -positions = np.zeros((steps, 3)) -velocities = np.zeros((steps, 3)) -quaternions = np.zeros((steps, 4)) -angular_velocities = np.zeros((steps, 3)) -okid_params = np.zeros((steps, 4)) - -# Storage for trajectory -positions_est = np.zeros((steps, 3)) -velocities_est = np.zeros((steps, 3)) -quaternions_est = np.zeros((steps, 4)) -angular_velocities_est = np.zeros((steps, 3)) -okid_params_est = np.zeros((steps, 4)) - -# Simulation loop -for i in range(steps): - t = i * dt - - # Generate control input (slow sinusoidal signals) - control_force = np.array([ - 5 * np.sin(4.0 * t), - 10 * np.sin(3.0 * t), - 10 * np.sin(2.0 * t) - ]) - - control_torque = np.array([ - 10 * np.sin(4.0 * t), - 10 * np.sin(4.0 * t), - 10 * np.sin(4.0 * t) - ]) - - control_input = np.concatenate((control_force, control_torque)) - - # Propagate state using UKF prediction - real_state = ukf.F_dynamics(real_state, dt, control_input) - state = UKF_model.unscented_transform(state, control_input) - if i % 5 == 0: - # Simulate measurement update every 5 steps - ang_measurement.measurement = np.array([ - real_state.angular_velocity[0], - real_state.angular_velocity[1], - real_state.angular_velocity[2] - ]) + np.random.normal(0, 0.03, 3) - # Simulate measurement covariance - ang_measurement.covariance = np.eye(3) * 0.04 # Measurement noise covariance - # Update UKF with measurement - UKF_model.measurement_update(state, ang_measurement) - state = UKF_model.posteriori_estimate(state, ang_measurement) - - if i % 10 == 0: - # Simulate measurement update every 10 steps - dvl_measurement.measurement = np.array([ - real_state.velocity[0], - real_state.velocity[1], - real_state.velocity[2] - ]) + np.random.normal(0, 0.03, 3) # Simulated measurement with noise - - # Simulate measurement covariance - dvl_measurement.covariance = np.eye(3) * 0.04 # Measurement noise covariance - - # Update UKF with measurement - UKF_model.measurement_update(state, dvl_measurement) - state = UKF_model.posteriori_estimate(state, dvl_measurement) - print_matrix(state.covariance) - - print("Determinant of covariance matrix:", np.linalg.det(state.covariance)) - # Store state for plotting - positions[i] = real_state.position - velocities[i] = real_state.velocity - quaternions[i] = real_state.orientation - angular_velocities[i] = real_state.angular_velocity - okid_params[i] = real_state.okid_params.g_eta - - # Store estimated state for plotting - positions_est[i] = state.position - velocities_est[i] = state.velocity - quaternions_est[i] = state.orientation - angular_velocities_est[i] = state.angular_velocity - okid_params_est[i] = state.okid_params.g_eta - - # Add small delay to simulate real-time execution - time.sleep(0.001) -print(state.as_vector()) -# Plotting -time_points = np.arange(0, sim_time, dt) - -# 3D trajectory plot -fig = plt.figure(figsize=(12, 10)) -ax = fig.add_subplot(111, projection='3d') -ax.plot(positions[:, 0], positions[:, 1], positions[:, 2], 'b-', label='True Trajectory') -ax.plot(positions_est[:, 0], positions_est[:, 1], positions_est[:, 2], 'r--', label='Estimated Trajectory') -ax.scatter(positions[0, 0], positions[0, 1], positions[0, 2], c='g', marker='o', s=100, label='Start') -ax.scatter(positions[-1, 0], positions[-1, 1], positions[-1, 2], c='r', marker='o', s=100, label='End') -ax.set_xlabel('X Position') -ax.set_ylabel('Y Position') -ax.set_zlabel('Z Position') -ax.set_title('3D Trajectory') -ax.legend() - -# Position plot -plt.figure(figsize=(12, 6)) -plt.subplot(311) -plt.plot(time_points, positions[:, 0], 'b-', label='True') -plt.plot(time_points, positions_est[:, 0], 'r--', label='Estimated') -plt.ylabel('X Position') -plt.legend() -plt.subplot(312) -plt.plot(time_points, positions[:, 1], 'b-', label='True') -plt.plot(time_points, positions_est[:, 1], 'r--', label='Estimated') -plt.ylabel('Y Position') -plt.legend() -plt.subplot(313) -plt.plot(time_points, positions[:, 2], 'b-', label='True') -plt.plot(time_points, positions_est[:, 2], 'r--', label='Estimated') -plt.ylabel('Z Position') -plt.xlabel('Time (s)') -plt.legend() -plt.tight_layout() - -# Velocity plot -plt.figure(figsize=(12, 6)) -plt.subplot(311) -plt.plot(time_points, velocities[:, 0], 'b-', label='True') -plt.plot(time_points, velocities_est[:, 0], 'r--', label='Estimated') -plt.ylabel('X Velocity') -plt.legend() -plt.subplot(312) -plt.plot(time_points, velocities[:, 1], 'b-', label='True') -plt.plot(time_points, velocities_est[:, 1], 'r--', label='Estimated') -plt.ylabel('Y Velocity') -plt.legend() -plt.subplot(313) -plt.plot(time_points, velocities[:, 2], 'b-', label='True') -plt.plot(time_points, velocities_est[:, 2], 'r--', label='Estimated') -plt.ylabel('Z Velocity') -plt.xlabel('Time (s)') -plt.legend() -plt.tight_layout() - -# Angular velocity plot -plt.figure(figsize=(12, 6)) -plt.subplot(311) -plt.plot(time_points, angular_velocities[:, 0], 'b-', label='True') -plt.plot(time_points, angular_velocities_est[:, 0], 'r--', label='Estimated') -plt.ylabel('Roll Rate') -plt.legend() -plt.subplot(312) -plt.plot(time_points, angular_velocities[:, 1], 'b-', label='True') -plt.plot(time_points, angular_velocities_est[:, 1], 'r--', label='Estimated') -plt.ylabel('Pitch Rate') -plt.legend() -plt.subplot(313) -plt.plot(time_points, angular_velocities[:, 2], 'b-', label='True') -plt.plot(time_points, angular_velocities_est[:, 2], 'r--', label='Estimated') -plt.ylabel('Yaw Rate') -plt.xlabel('Time (s)') -plt.legend() -plt.tight_layout() - -# OKID g_eta plot -plt.figure(figsize=(12, 6)) -plt.subplot(411) -plt.plot(time_points, okid_params[:, 0], 'b-', label='True') -plt.plot(time_points, okid_params_est[:, 0], 'r--', label='Estimated') -plt.ylabel('g_eta[0]') -plt.legend() -plt.subplot(412) -plt.plot(time_points, okid_params[:, 1], 'b-', label='True') -plt.plot(time_points, okid_params_est[:, 1], 'r--', label='Estimated') -plt.ylabel('g_eta[1]') -plt.legend() -plt.subplot(413) -plt.plot(time_points, okid_params[:, 2], 'b-', label='True') -plt.plot(time_points, okid_params_est[:, 2], 'r--', label='Estimated') -plt.ylabel('g_eta[2]') -plt.legend() -plt.subplot(414) -plt.plot(time_points, okid_params[:, 3], 'b-', label='True') -plt.plot(time_points, okid_params_est[:, 3], 'r--', label='Estimated') -plt.ylabel('g_eta[3]') -plt.xlabel('Time (s)') -plt.legend() -plt.tight_layout() - -plt.show() - diff --git a/navigation/ukf_okid/ukf_python/ukf_utils.py b/navigation/ukf_okid/ukf_python/ukf_utils.py deleted file mode 100644 index 7bf7cd4e3..000000000 --- a/navigation/ukf_okid/ukf_python/ukf_utils.py +++ /dev/null @@ -1,35 +0,0 @@ -import numpy as np -from ukf_okid_class import StateQuat - - -def print_StateQuat_list( - state_list: list[StateQuat], name="StateQuat List", print_covariance=True -): - """Custom print function to print a list of StateQuat objects in a formatted form.""" - print(f"{name}:") - for i, state in enumerate(state_list): - print(f"Index {i}:") - print_StateQuat(state, f"StateQuat {i}", print_covariance) - - -def print_StateQuat(state: StateQuat, name="StateQuat", print_covariance=True): - """Custom print function to print StateQuat objects in a formatted form.""" - print(f"{name}:") - print(f" Position: {state.position}") - print(f" Orientation: {state.orientation}") - print(f" Velocity: {state.velocity}") - print(f" Angular Velocity: {state.angular_velocity}") - print(f" okid state: {state.okid_params}") - # print(f" okid_params: {state.okid_params}") - if print_covariance: - print_matrix(state.covariance, "Covariance") - - -def print_matrix(matrix, name="Matrix"): - """Custom print function to print matrices in a formatted form.""" - print(f"{name}: {matrix.shape}") - if isinstance(matrix, np.ndarray): - for row in matrix: - print(" ".join(f"{val:.2f}" for val in row)) - else: - print(matrix) From 334519db45a7f64c862fa5143e7cd4f8e83432d3 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Sun, 5 Oct 2025 20:31:07 +0200 Subject: [PATCH 24/30] fix: removing tukf and some errors in eskf --- navigation/eskf/include/eskf/eskf_ros.hpp | 11 +- navigation/eskf/src/eskf_ros.cpp | 20 +- navigation/tukf_rsi/CMakeLists.txt | 61 ------ .../tukf_rsi/config/tusk_rsi_params.yaml | 12 -- .../tukf_rsi/include/tukf_rsi/tukf_rsi.hpp | 63 ------ .../include/tukf_rsi/tukf_rsi_model.hpp | 50 ----- .../include/tukf_rsi/tukf_rsi_ros.hpp | 64 ------ .../include/tukf_rsi/tukf_rsi_utils.hpp | 65 ------ .../tukf_rsi/include/tukf_rsi/typedefs.hpp | 145 ------------- navigation/tukf_rsi/launch/tukf_rsi.launch.py | 22 -- navigation/tukf_rsi/package.xml | 22 -- navigation/tukf_rsi/src/tukf_rsi.cpp | 84 -------- navigation/tukf_rsi/src/tukf_rsi_model.cpp | 125 ----------- navigation/tukf_rsi/src/tukf_rsi_node.cpp | 9 - navigation/tukf_rsi/src/tukf_rsi_ros.cpp | 150 ------------- navigation/tukf_rsi/src/tukf_rsi_utils.cpp | 199 ------------------ 16 files changed, 17 insertions(+), 1085 deletions(-) delete mode 100644 navigation/tukf_rsi/CMakeLists.txt delete mode 100644 navigation/tukf_rsi/config/tusk_rsi_params.yaml delete mode 100644 navigation/tukf_rsi/include/tukf_rsi/tukf_rsi.hpp delete mode 100644 navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_model.hpp delete mode 100644 navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_ros.hpp delete mode 100644 navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_utils.hpp delete mode 100644 navigation/tukf_rsi/include/tukf_rsi/typedefs.hpp delete mode 100644 navigation/tukf_rsi/launch/tukf_rsi.launch.py delete mode 100644 navigation/tukf_rsi/package.xml delete mode 100644 navigation/tukf_rsi/src/tukf_rsi.cpp delete mode 100644 navigation/tukf_rsi/src/tukf_rsi_model.cpp delete mode 100644 navigation/tukf_rsi/src/tukf_rsi_node.cpp delete mode 100644 navigation/tukf_rsi/src/tukf_rsi_ros.cpp delete mode 100644 navigation/tukf_rsi/src/tukf_rsi_utils.cpp diff --git a/navigation/eskf/include/eskf/eskf_ros.hpp b/navigation/eskf/include/eskf/eskf_ros.hpp index d4a770864..424e583f7 100644 --- a/navigation/eskf/include/eskf/eskf_ros.hpp +++ b/navigation/eskf/include/eskf/eskf_ros.hpp @@ -21,14 +21,14 @@ class ESKFNode : public rclcpp::Node { explicit ESKFNode(); private: - // @brief Callback function for the imu topic // @param msg: Imu message containing the imu data void imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg); // @brief Callback function for the dvl topic // @param msg: TwistWithCovarianceStamped message containing the dvl data - void dvl_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); + void dvl_callback( + const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); // @brief Publish the odometry message void publish_odom(); @@ -41,7 +41,8 @@ class ESKFNode : public rclcpp::Node { rclcpp::Subscription::SharedPtr imu_sub_; - rclcpp::Subscription::SharedPtr dvl_sub_; + rclcpp::Subscription< + geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr dvl_sub_; rclcpp::Publisher::SharedPtr odom_pub_; @@ -63,11 +64,11 @@ class ESKFNode : public rclcpp::Node { std::unique_ptr eskf_; - rclcpp::Time last_imu_time_; - bool first_imu_msg_received_ = false; Eigen::Matrix3d R_imu_eskf_; + + rclcpp::Time last_imu_time_; }; #endif // ESKF_ROS_HPP diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index cfa85172e..c379732e3 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -28,7 +28,8 @@ void ESKFNode::set_subscribers_and_publisher() { this->declare_parameter("dvl_topic"); std::string dvl_topic = this->get_parameter("dvl_topic").as_string(); - dvl_sub_ = this->create_subscription( + dvl_sub_ = this->create_subscription< + geometry_msgs::msg::TwistWithCovarianceStamped>( dvl_topic, qos_sensor_data, std::bind(&ESKFNode::dvl_callback, this, std::placeholders::_1)); @@ -95,21 +96,22 @@ void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { std::tie(nom_state_, error_state_) = eskf_->imu_update(imu_meas_, dt); } -void ESKFNode::dvl_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { - // Log that we received a DVL message - // spdlog::info("DVL message received"); - dvl_meas_.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, msg->twist.twist.linear.z; +void ESKFNode::dvl_callback( + const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { + dvl_meas_.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, + msg->twist.twist.linear.z; - dvl_meas_.cov << msg->twist.covariance[0], msg->twist.covariance[1], msg->twist.covariance[2], - msg->twist.covariance[6], msg->twist.covariance[7], msg->twist.covariance[8], - msg->twist.covariance[12], msg->twist.covariance[13], msg->twist.covariance[14]; + dvl_meas_.cov << msg->twist.covariance[0], msg->twist.covariance[1], + msg->twist.covariance[2], msg->twist.covariance[6], + msg->twist.covariance[7], msg->twist.covariance[8], + msg->twist.covariance[12], msg->twist.covariance[13], + msg->twist.covariance[14]; std::tie(nom_state_, error_state_) = eskf_->dvl_update(dvl_meas_); std_msgs::msg::Float64 nis_msg; nis_msg.data = eskf_->NIS_; nis_pub_->publish(nis_msg); - } void ESKFNode::publish_odom() { diff --git a/navigation/tukf_rsi/CMakeLists.txt b/navigation/tukf_rsi/CMakeLists.txt deleted file mode 100644 index f1ad5e0b1..000000000 --- a/navigation/tukf_rsi/CMakeLists.txt +++ /dev/null @@ -1,61 +0,0 @@ -cmake_minimum_required(VERSION 3.8) -project(tukf_rsi) - -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 20) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(nav_msgs REQUIRED) -find_package(geometry_msgs REQUIRED) -find_package(Eigen3 REQUIRED) -find_package(tf2 REQUIRED) -find_package(vortex_msgs REQUIRED) -find_package(spdlog REQUIRED) -find_package(fmt REQUIRED) - -if(NOT DEFINED EIGEN3_INCLUDE_DIR) - set(EIGEN3_INCLUDE_DIR ${EIGEN3_INCLUDE_DIRS}) -endif() -include_directories(${EIGEN3_INCLUDE_DIR}) - -include_directories(include) - -add_executable(tukf_rsi_node - src/tukf_rsi.cpp - src/tukf_rsi_ros.cpp - src/tukf_rsi_node.cpp - src/tukf_rsi_utils.cpp -) - -ament_target_dependencies(tukf_rsi_node - rclcpp - geometry_msgs - nav_msgs - Eigen3 - tf2 - vortex_msgs - spdlog - fmt -) - -target_link_libraries(tukf_rsi_node - fmt::fmt -) - -install(TARGETS - tukf_rsi_node - DESTINATION lib/${PROJECT_NAME}) - -install(DIRECTORY - config - launch - DESTINATION share/${PROJECT_NAME}/ -) - -ament_package() diff --git a/navigation/tukf_rsi/config/tusk_rsi_params.yaml b/navigation/tukf_rsi/config/tusk_rsi_params.yaml deleted file mode 100644 index c74717815..000000000 --- a/navigation/tukf_rsi/config/tusk_rsi_params.yaml +++ /dev/null @@ -1,12 +0,0 @@ -eskf_node: - ros__parameters: - gyro_topic: "/imu/data" - dvl_topic: "/orca/twist" - odom_topic: "/tukf/odom" - wrench_topic: "/orca/wrench_input" - diag_Q_std: [0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] - diag_P0_std: [2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 2.5, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05] - x0: [0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] - diag_Rgyro_std: [0.01, 0.01, 0.01] - diag_Rdvl_std: [0.05, 0.05, 0.05] - diff --git a/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi.hpp b/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi.hpp deleted file mode 100644 index a1e19edb5..000000000 --- a/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi.hpp +++ /dev/null @@ -1,63 +0,0 @@ -// tukf.hpp -#ifndef TUKF_HPP -#define TUKF_HPP - -#include "typedefs.hpp" // includes AUVState, MeasModel, and utility functions -#include - -class TUKF { -public: - TUKF(const AUVState& x0, - const Eigen::Matrix37d& Q_in, - double dt = 0.01); - - // @brief Generate sigma points for the current state - // @param current_state: Current state of the AUV - // @return A vector of sigma points - std::vector sigma_points(const AUVState& current_state); - - // @brief Unscented transform to predict the next state - // @param current_state: Current state of the AUV - // @param control_force: Control force applied to the AUV - // @return Predicted state after applying the control force - AUVState unscented_transform(const AUVState& current_state, - const Eigen::Vector3d& control_force); - - // @brief Perform measurement update using the measurement model - // @param current_state: Current state of the AUV - // @param measurement: Measurement model containing the measurement and covariance - // @return Updated state after measurement update - void measurement_update(const AUVState& current_state, - const MeasModel& measurement); - - // @brief Posterior estimate of the state after measurement update - // @param current_state: Current state of the AUV - // @param measurement: Measurement model containing the measurement and covariance - // @return Posterior estimate of the state - AUVState posterior_estimate(const AUVState& current_state, - const MeasModel& measurement); - - // public state and flags - AUVState x; - bool filter_failed; - -private: - - Eigen::Matrix37d Q; - - Eigen::Matrix delta; - - std::vector sigma_points_list; - - std::vector y_i; - - MeasModel measurement_updated; - - Eigen::Matrix cross_correlation; - - double dt; - - int flagg; -}; - -#endif // TUKF_HPP \ No newline at end of file diff --git a/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_model.hpp b/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_model.hpp deleted file mode 100644 index b536ca798..000000000 --- a/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_model.hpp +++ /dev/null @@ -1,50 +0,0 @@ -#ifndef TUKF_MODEL_HPP -#define TUKF_MODEL_HPP - -#include -#include "tukf_rsi/typedefs.hpp" - - -// @brief Tranformation matrix from quaternion orientation -// @param orientation: Quaternion representing the orientation -// @return 3x3 transformation matrix -Eigen::Matrix3d tranfromation_matrix(const Eigen::Quaterniond& orientation); - -// @brief Mass inertia system-matrix (6×6) -// @param inertia_vec: Vector containing the inertia parameters -Eigen::Matrix6d M_rb(const Eigen::Vector9d& inertia_vec); - -// @brief Added mass system-matrix (6×6) -// @param added_mass: Vector containing the added mass parameters -Eigen::Matrix6d M_a(const Eigen::Vector6d& added_mass); - -// @brief Corilos and centripetal forces system-matrix (6×6) -// @param inertia_vec: Vector containing the inertia parameters -// @param angular_velocity: Angular velocity vector -Eigen::Matrix6d C_rb(const Eigen::Vector9d& inertia_vec, - const Eigen::Vector3d& angular_velocity); - -// @brief added mass Corilos and centripetal forces system-matrix (6×6) -// @param added_mass: Vector containing the added mass parameters -// @param angular_velocity: Angular velocity vector -// @param velocity: Velocity linear vector -Eigen::Matrix6d C_a(const Eigen::Vector6d& added_mass, - const Eigen::Vector3d& angular_velocity, - const Eigen::Vector3d& velocity); - -// @brief Damping system-matrix (6×6) -// @param damping: Vector containing the damping parameters -Eigen::Matrix6d D_linear(const Eigen::Vector6d& damping); - -// @brief generalized froces (6×1) -// @param g_eta_params: Vector containing the g_eta parameters (buoyancy terms) -// @param euler_angles: Euler angles (roll, pitch, yaw) -Eigen::Vector6d G_eta(const Eigen::Vector4d& g_eta_params, - const Eigen::Vector3d& euler_angles); - -// @brief Dynamics function for the AUV -AUVState F_dynamics(const AUVState& state, - double dt, - const Eigen::Vector3d& control_input); - -#endif // TUKF_MODEL_HPP \ No newline at end of file diff --git a/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_ros.hpp b/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_ros.hpp deleted file mode 100644 index 98b0a547a..000000000 --- a/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_ros.hpp +++ /dev/null @@ -1,64 +0,0 @@ -#ifndef TUKF_NODE_HPP -#define TUKF_NODE_HPP - -#include -#include -#include -#include -#include -#include -#include -#include -#include "tukf_rsi/tukf.hpp" -#include "tukf_rsi/tukf_rsi_utils.hpp" -#include "tukf_rsi/typedefs.hpp" - -class TUKFNode : public rclcpp::Node { -public: - TUKFNode(); - -private: - - // @brief Callback function for the gyro topic - // @param msg: Imu message containing the gyro data - void gyro_callback(const sensor_msgs::msg::Imu::SharedPtr msg); - - // @brief Callback function for the DVL topic - // @param msg: TwistWithCovarianceStamped message containing the DVL data - void dvl_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); - - // @brief Callback function for the wrench topic - // @param msg: WrenchStamped message containing the wrench data - void wrench_callback(const geometry_msgs::msg::WrenchStamped::SharedPtr msg); - - // @brief Set the subscriber and publisher for the node - void set_subscribers_and_publisher(); - - // @brief Set the parameters for the eskf - void set_parameters(); - - // @brief Publish the odometry message - void publish_odom(); - - rclcpp::Subscription::SharedPtr gyro_sub_; - - rclcpp::Subscription::SharedPtr dvl_sub_; - - rclcpp::Subscription::SharedPtr wrench_sub_; - - rclcpp::Publisher::SharedPtr odom_pub_; - - rclcpp::TimerBase::SharedPtr odom_timer_; - - std::unique_ptr tukf_; - - AUVState state_; - - double dt_; - - Eigen::Matrix3d R_gyro_; - - Eigen::Matrix3d R_dvl_; -}; - -#endif // TUKF_NODE_HPP \ No newline at end of file diff --git a/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_utils.hpp b/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_utils.hpp deleted file mode 100644 index b3c31221f..000000000 --- a/navigation/tukf_rsi/include/tukf_rsi/tukf_rsi_utils.hpp +++ /dev/null @@ -1,65 +0,0 @@ -#ifndef TUKF_RSI_UTILS_HPP -#define TUKF_RSI_UTILS_HPP - -#include -#include -#include "tukf_rsi/typedefs.hpp" - -// @brief Compute mean quaternion from a set of quaternions -// @param quats: Vector of quaternions -// @param tol: Tolerance for convergence -// @param maxIter: Maximum number of iterations -Eigen::Quaterniond quaternion_mean( - const std::vector& quats, - double tol = 1e-6, - int maxIter = 100 -); - -// @brief Compute mean of a set of AUV states -// @param setPoints: Vector of AUVState objects -// @param tol: Tolerance for convergence -// @param maxIter: Maximum number of iterations -Eigen::Vector37d mean_set( - const std::vector& setPoints, - double tol = 1e-6, - int maxIter = 100 -); - -// @brief Compute mean of a set of measurements -// @param setPoints: Vector of MeasModel objects -Eigen::Vector3d mean_masurement(const std::vector& setPoints); - -// @brief Compute covariance of a set of AUV states -// @param setPoints: Vector of AUVState objects -// @param meanVec: Mean vector of the set -// @param tol: Tolerance for convergence -Eigen::Matrix37d covariance_set( - const std::vector& setPoints, - const Eigen::Vector37d& meanVec, - double tol = 1e-6 -); - -// @brief Compute covariance of a set of measurements -// @param setPoints: Vector of MeasModel objects -// @param mean: Mean vector of the measurements -Eigen::Matrix3d covariance_measurement( - const std::vector& setPoints, - const Eigen::Vector3d& mean -); - -// @brief Compute cross-covariance between AUV states and measurements -// @param setY: Vector of AUVState objects -// @param meanY: Mean vector of the AUV states -// @param setZ: Vector of MeasModel objects -// @param meanZ: Mean vector of the measurements -// @param tol: Tolerance for convergence -Eigen::Matrix cross_covariance( - const std::vector& setY, - const Eigen::Vector37d& meanY, - const std::vector& setZ, - const Eigen::Vector3d& meanZ, - double tol = 1e-6 -); - -#endif // TUKF_RSI_UTILS_HPP - diff --git a/navigation/tukf_rsi/include/tukf_rsi/typedefs.hpp b/navigation/tukf_rsi/include/tukf_rsi/typedefs.hpp deleted file mode 100644 index 0d724577d..000000000 --- a/navigation/tukf_rsi/include/tukf_rsi/typedefs.hpp +++ /dev/null @@ -1,145 +0,0 @@ -#ifndef AUV_TYPEDEFS_HPP -#define AUV_TYPEDEFS_HPP - -#include -#include -#include -#include - -namespace Eigen { - typedef Matrix Vector37d; - typedef Matrix Matrix37d; - typedef Matrix Vector25d; - typedef Matrix Vector12d; - typedef Matrix Vector9d; - typedef Matrix Vector6d; - typedef Matrix Vector4d; - typedef Matrix Matrix3x12d; - typedef Matrix Matrix3d; - typedef Matrix Matrix3x37d; - typedef Matrix Matrix37x74d; - typedef Matrix Matrix37x3d; -} - -struct AUVState { - Eigen::Vector3d position = Eigen::Vector3d::Zero(); - Eigen::Quaterniond orientation = Eigen::Quaterniond::Identity(); - Eigen::Vector3d velocity = Eigen::Vector3d::Zero(); - Eigen::Vector3d angular_velocity = Eigen::Vector3d::Zero(); - Eigen::Vector9d inertia = Eigen::Vector9d::Zero(); - Eigen::Vector6d added_mass = Eigen::Vector6d::Zero(); - Eigen::Vector6d damping = Eigen::Vector6d::Zero(); - Eigen::Vector4d g_eta = Eigen::Vector4d::Zero(); - Eigen::Matrix37d covariance = Eigen::Matrix37d::Zero(); - - Eigen::Vector3d error = Eigen::Vector3d::Zero(); - - AUVState() = default; - - Eigen::Vector12d dynamic_part() const { - Eigen::Vector12d x; - x << position, - orientation.vec(), - velocity, - angular_velocity; - return x; - } - - Eigen::Vector25d okid_part() const { - Eigen::Vector25d x; - x << inertia, - added_mass, - damping, - g_eta; - return x; - } - - Eigen::Vector37d as_vector() const { - Eigen::Vector37d x; - x << dynamic_part(), - okid_part(); - return x; - } - - AUVState operator+(const AUVState& other) const { - AUVState result; - result.position = position + other.position; - result.orientation = orientation * other.orientation; - result.velocity = velocity + other.velocity; - result.angular_velocity = angular_velocity + other.angular_velocity; - result.inertia = inertia + other.inertia; - result.added_mass = added_mass + other.added_mass; - result.damping = damping + other.damping; - result.g_eta = g_eta + other.g_eta; - return result; - } - - AUVState operator-(const AUVState& other) const { - AUVState result; - result.position = position - other.position; - result.orientation = orientation * other.orientation.inverse(); - result.velocity = velocity - other.velocity; - result.angular_velocity = angular_velocity - other.angular_velocity; - result.inertia = inertia - other.inertia; - result.added_mass = added_mass - other.added_mass; - result.damping = damping - other.damping; - result.g_eta = g_eta - other.g_eta; - return result; - } - - void fill_states(const Eigen::Vector37d& x) { - position = x.segment<3>(0); - Eigen::Vector3d ori_vec = x.segment<3>(3); - orientation = Eigen::Quaterniond(1, ori_vec.x(), ori_vec.y(), ori_vec.z()).normalized(); - velocity = x.segment<3>(6); - angular_velocity = x.segment<3>(9); - inertia = x.segment<9>(12); - added_mass = x.segment<6>(21); - damping = x.segment<6>(27); - g_eta = x.segment<4>(33); - } -}; - -struct MeasModel { - Eigen::Vector3d measurement = Eigen::Vector3d::Zero(); - Eigen::Matrix3d covariance = Eigen::Matrix3d::Zero(); - std::function H; - - MeasModel() - : H(default_h) - {} - - MeasModel(const Eigen::Vector3d& meas, - const Eigen::Matrix3d& cov, - std::function Hfunc = default_h) - : measurement(meas), covariance(cov), H(std::move(Hfunc)) - {} - - static MeasModel default_h(const AUVState& state) { - MeasModel z; - Eigen::Matrix3x12d Hmat = Eigen::Matrix3x12d::Zero(); - Hmat.block<3,3>(0,6) = Eigen::Matrix3d::Identity(); - z.measurement = Hmat * state.dynamic_part(); - return z; - } - - MeasModel operator+(const MeasModel& other) const { - MeasModel r; - r.measurement = measurement + other.measurement; - return r; - } - - MeasModel operator-(const MeasModel& other) const { - MeasModel r; - r.measurement = measurement - other.measurement; - return r; - } - - friend MeasModel operator*(double scalar, const MeasModel& m) { - MeasModel r; - r.measurement = scalar * m.measurement; - return r; - } -}; - -#endif // AUV_TYPEDEFS_HPP \ No newline at end of file diff --git a/navigation/tukf_rsi/launch/tukf_rsi.launch.py b/navigation/tukf_rsi/launch/tukf_rsi.launch.py deleted file mode 100644 index e238b3e1e..000000000 --- a/navigation/tukf_rsi/launch/tukf_rsi.launch.py +++ /dev/null @@ -1,22 +0,0 @@ -from os import path - -from ament_index_python.packages import get_package_share_directory -from launch import LaunchDescription -from launch_ros.actions import Node - -tukf_rsi_params = path.join( - get_package_share_directory("tukf_rsi"), "config", "tukf_rsi_params.yaml" -) - - -def generate_launch_description(): - tukf_rsi_node = Node( - package="tukf_rsi", - executable="tukf_rsi_node", - name="tukf_rsi_node", - parameters=[ - tukf_rsi_params, - ], - output="screen", - ) - return LaunchDescription([tukf_rsi_node]) diff --git a/navigation/tukf_rsi/package.xml b/navigation/tukf_rsi/package.xml deleted file mode 100644 index 989241795..000000000 --- a/navigation/tukf_rsi/package.xml +++ /dev/null @@ -1,22 +0,0 @@ - - - - tukf_rsi - 1.0.0 - Transformed Unscented Kalman Filter - talhanc - MIT - - ament_cmake - - rclcpp - geometry_msgs - nav_msgs - eigen - tf2 - vortex_msgs - - - ament_cmake - - diff --git a/navigation/tukf_rsi/src/tukf_rsi.cpp b/navigation/tukf_rsi/src/tukf_rsi.cpp deleted file mode 100644 index df0195d86..000000000 --- a/navigation/tukf_rsi/src/tukf_rsi.cpp +++ /dev/null @@ -1,84 +0,0 @@ -#include "tukf_rsi/tukf.hpp" -#include "tukf_rsi/tukf_rsi_utils.hpp" -#include "tukf_rsi/typedefs.hpp" -#include "tukf_rsi/tukf_rsi_model.hpp" -#include - -TUKF::TUKF(const AUVState& x0, - const Eigen::Matrix37d& Q_in, - double dt_in) - : x(x0), Q(Q_in), dt(dt_in), filter_failed(false), flagg(0) -{ - delta = generate_elta_matrix37() / std::sqrt(static_cast(x.as_sector().size())); - measurement_updated = MeasModel(); -} - -std::vector TUKF::sigma_points(const AUVState& current_state) { - int n = static_cast(current_state.covariance.rows()); - ++flagg; - Eigen::Matrix37d S; - bool chol_ok = true; - auto llt = current_state.covariance.llt(); - if(llt.info() == Eigen::NumericalIssue) { - chol_ok = false; - } else { - S = llt.matrixL(); - } - if (!chol_ok) { - filter_failed = true; - S = Eigen::Matrix37d::Identity() * 1e-6; - } - sigma_points_list.resize(2 * n); - for (int k = 0; k < 2 * n; ++k) { - Eigen::Vector37d v = current_state.as_vector() + S * delta.col(k); - sigma_points_list[k].fill_States(v); - } - return sigma_points_list; -} - -AUVState TUKF::unscented_transform(const AUVState& current_state, - const Eigen::Vector3d& control_force) { - int n = static_cast(current_state.covariance.rows()); - sigma_soints(current_state); - y_i.resize(2 * n); - for (int i = 0; i < 2 * n; ++i) { - y_i[i] = F_dynamics(sigma_points_list[i], dt, control_force); - } - AUVState state_est; - Eigen::Vector37d x_vec = mean_Set(y_i); - state_est.fill_States(x_vec); - state_est.covariance = covarianceSet(y_i, x_vec) + Q; - return state_est; -} - -void TUKF::measurement_update(const AUVState& current_state, - const MeasModel& measurement) { - int n = static_cast(current_state.covariance.rows()); - std::vector z_i(2 * n); - for (int i = 0; i < 2 * n; ++i) { - z_i[i] = measurement.H(sigma_points_list[i]); - } - measurement_updated.measurement = mean_seasurement(z_i); - measurement_updated.covariance = covariance_measurement( - z_i, measurement_updated.measurement); - cross_correlation = cross_covariance( - y_i, - current_state.as_vector(), - z_i, - measurement_updated.measurement); -} - -AUVState TUKF::posterior_estimate(const AUVState& current_state, - const MeasModel& measurement) { - MeasModel nu_k; - nu_k.measurement = measurement.measurement - measurement_updated.measurement; - nu_k.covariance = measurement_updated.covariance + measurement.covariance; - Eigen::Matrix K = cross_correlation * nu_k.covariance.inverse(); - AUVState post; - Eigen::Vector37d v = current_state.as_vector() + - K * nu_k.measurement; - post.fill_states(v); - post.covariance = current_state.covariance - - K * nu_k.covariance * K.transpose(); - return post; -} \ No newline at end of file diff --git a/navigation/tukf_rsi/src/tukf_rsi_model.cpp b/navigation/tukf_rsi/src/tukf_rsi_model.cpp deleted file mode 100644 index 97a91c024..000000000 --- a/navigation/tukf_rsi/src/tukf_rsi_model.cpp +++ /dev/null @@ -1,125 +0,0 @@ -#include "tukf_rsi/tukf_model.hpp" -#include "tukf_rsi/tukf_rsi_utils.hpp" -#include "tukf_rsi/typedefs.hpp" -#include -#include - - -Eigen::Matrix4x3d tranfromation_matrix(const Eigen::Quaterniond& q) { - Eigen::Matrix4x3d T; - T << -q.x(), -q.y(), -q.z(), - q.w(), -q.z(), q.y(), - q.z(), q.w(), -q.x(), - -q.y(), q.x(), q.w(); - return T; -} - -Eigen::Matrix6d M_rb(const Eigen::Vector& inertia_vec) { - const double mass = 30.0; - const Eigen::Matrix3d I_rb = Eigen::Map(inertia_vec.data()); - const Eigen::Vector3d r_b_bg(0.01, 0.0, 0.02); - - Eigen::Matrix6d M = Eigen::Matrix6d::Zero(); - M.block<3,3>(0,0) = mass * Eigen::Matrix3d::Identity(); - M.block<3,3>(0,3) = -mass * skewSymmetric(r_b_bg); - M.block<3,3>(3,0) = mass * skewSymmetric(r_b_bg); - M.block<3,3>(3,3) = I_rb; - - return M; -} - -Eigen::Matrix6d M_a(const Eigen::Vector& a_mass) { - Eigen::Matrix6d Ma = Eigen::Matrix6d::Zero(); - Ma.block<3,3>(0,0) = a_mass.head<3>().asDiagonal(); - Ma.block<3,3>(3,3) = a_mass.tail<3>().asDiagonal(); - return Ma; -} - -Eigen::Matrix6d C_rb(const Eigen::Vector& inertia_vec, const Eigen::Vector3d& w) { - const double mass = 30.0; - const Eigen::Vector3d r_b_bg(0.01, 0.0, 0.02); - const Eigen::Matrix3d I_rb = Eigen::Map(inertia_vec.data()); - - Eigen::Matrix6d C = Eigen::Matrix6d::Zero(); - C.block<3,3>(3,3) = -skewSymmetric(I_rb * w); - C.block<3,3>(0,3) = -mass * skewSymmetric(w) * skewSymmetric(r_b_bg); - C.block<3,3>(3,0) = mass * skewSymmetric(r_b_bg) * skewSymmetric(w); - - return C; -} - -Eigen::Matrix6d C_a(const Eigen::Vector& a_mass, const Eigen::Vector3d& w, const Eigen::Vector3d& v) { - Eigen::Matrix6d Ca = Eigen::Matrix6d::Zero(); - const Eigen::Matrix3d A11 = a_mass.head<3>().asDiagonal(); - const Eigen::Matrix3d A22 = a_mass.tail<3>().asDiagonal(); - - Ca.block<3,3>(0,3) = -skewSymmetric(A11 * v); - Ca.block<3,3>(3,0) = -skewSymmetric(A11 * v); - Ca.block<3,3>(3,3) = -skewSymmetric(A22 * w); - - return Ca; -} - -Eigen::Matrix6d D_linear(const Eigen::Vector& d) { - Eigen::Matrix6d D = Eigen::Matrix6d::Zero(); - D.block<3,3>(0,0) = -d.head<3>().asDiagonal(); - D.block<3,3>(3,3) = -d.tail<3>().asDiagonal(); - return D; -} - -Eigen::Vector6d G_eta(const Eigen::Vector& g_params, const Eigen::Quaterniond& q) { - const double Mx = g_params[1], My = g_params[2], Mz = g_params[3]; - const Eigen::Matrix3d R = q.toRotationMatrix(); - - Eigen::Vector6d G = Eigen::Vector6d::Zero(); - G(3) = -My*R(2,2) + Mz*R(1,2); - G(4) = -Mz*R(0,2) + Mx*R(2,2); - G(5) = -Mx*R(1,2) + My*R(0,2); - - return G; -} - -AUVState F_dynamics(const AUVState& state, double dt, const Eigen::Vector6d& u) { - const Eigen::Matrix6d Mrb = M_rb(state.inertia); - const Eigen::Matrix6d Ma = M_a(state.added_mass); - const Eigen::Matrix6d Mtotal = Mrb + Ma; - - const Eigen::Matrix6d Crb = C_rb(state.inertia, state.angular_velocity); - const Eigen::Matrix6d Ca = C_a(state.added_mass, state.angular_velocity, state.velocity); - const Eigen::Matrix6d Ctotal = Crb + Ca; - - const Eigen::Matrix6d Dl = D_linear(state.damping); - const Eigen::Vector6d G = G_eta(state.g_eta, state.orientation); - - Eigen::Vector6d nu; - nu << state.velocity, state.angular_velocity; - - AUVState sd; - sd.position = state.orientation.toRotationMatrix() * state.velocity; - sd.orientation = tranfromation_matrix(state.orientation) * state.angular_velocity; - - Eigen::Vector6d Nu = Mtotal.inverse() * (u - Ctotal*nu - Dl*nu - G); - sd.velocity = Nu.head<3>(); - sd.angular_velocity = Nu.tail<3>(); - - sd.inertia.setZero(); - sd.added_mass.setZero(); - sd.damping.setZero(); - sd.g_eta.setZero(); - - AUVState ns; - ns.position = state.position + sd.position * dt; - ns.orientation = state.orientation * Eigen::Quaterniond(1, 0.5*dt*sd.orientation.x(), - 0.5*dt*sd.orientation.y(), - 0.5*dt*sd.orientation.z()); - ns.orientation.normalize(); - ns.velocity = state.velocity + sd.velocity * dt; - ns.angular_velocity = state.angular_velocity + sd.angular_velocity * dt; - - ns.inertia = state.inertia; - ns.added_mass = state.added_mass; - ns.damping = state.damping; - ns.g_eta = state.g_eta; - - return ns; -} diff --git a/navigation/tukf_rsi/src/tukf_rsi_node.cpp b/navigation/tukf_rsi/src/tukf_rsi_node.cpp deleted file mode 100644 index d4f6eed17..000000000 --- a/navigation/tukf_rsi/src/tukf_rsi_node.cpp +++ /dev/null @@ -1,9 +0,0 @@ -#include "tukf_rsi/tukf_rsi_ros.hpp" - -int main(int argc, char** argv) { - rclcpp::init(argc, argv); - spdlog::info("Starting TUFK for RSI ROS2 Node"); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - return 0; -} \ No newline at end of file diff --git a/navigation/tukf_rsi/src/tukf_rsi_ros.cpp b/navigation/tukf_rsi/src/tukf_rsi_ros.cpp deleted file mode 100644 index 2be453191..000000000 --- a/navigation/tukf_rsi/src/tukf_rsi_ros.cpp +++ /dev/null @@ -1,150 +0,0 @@ -#include "tukf_node.hpp" -#include - -TUKFNode::TUKFNode() -: Node("tukf_node") -{ - - odom_timer_ = this->create_wall_timer( - std::chrono::duration(dt_), - std::bind(&TUKFNode::publishOdom, this)); - - set_subscribers_and_publisher(); - - set_parameters(); - - spdlog::info("TUKF Node Initialized"); -} - -void TUKFNode::set_subscribers_and_publisher() { - auto qos = rclcpp::QoS(rclcpp::SensorDataQoS()); - this->declare_parameter("gyro_topic"); - std::string gyro_topic = this->get_parameter("gyro_topic").as_string(); - gyro_sub_ = this->create_subscription( - gyro_topic, qos, - std::bind(&TUKFNode::gyroCallback, this, std::placeholders::_1)); - - this->declare_parameter("dvl_topic"); - std::string dvl_topic = this->get_parameter("dvl_topic").as_string(); - dvl_sub_ = this->create_subscription( - dvl_topic, qos, - std::bind(&TUKFNode::dvlCallback, this, std::placeholders::_1)); - - this->declare_parameter("wrench_topic"); - std::string dvl_topic = this->get_parameter("wrench_topic").as_string(); - wrench_sub_ = this->create_subscription( - wrench_sub_, qos, - std::bind(&TUKFNode::wrenchCallback, this, std::placeholders::_1)); - - this->declare_parameter("odom_topic"); - std::string odom_topic = this->get_parameter("odom_topic").as_string(); - odom_pub_ = this->create_publisher( - odom_topic, qos); -} - -void TUKFNode::set_parameters() { - this->declare_parameter>("diag_Q_std"); - auto diagQ = this->get_parameter("diag_Q_std").as_double_array(); - Eigen::Matrix37d Q = Eigen::Matrix37d::Zero(); - for (int i = 0; i < 37; ++i) { - Q(i,i) = diagQ[i] * diagQ[i]; - } - - this->declare_parameter>("diag_P0_std"); - auto diagP0 = this->get_parameter("diag_P0_std").as_double_array(); - Eigen::Matrix37d P0 = Eigen::Matrix37d::Zero(); - for (int i = 0; i < 37; ++i) { - P0(i,i) = diagP0[i] * diagP0[i]; - } - - this->declare_parameter>("x0"); - auto x0_vec = this->get_parameter("x0").as_double_array(); - Eigen::Vector37d x0_e; - for (int i = 0; i < 37; ++i) x0_e[i] = x0_vec[i]; - - this->declare_parameter("dt", 0.01); - dt_ = this->get_parameter("dt").as_double(); - - this->declare_parameter>("diag_Rgyro_std"); - auto diagRgyro = this->get_parameter("diag_Rgyro_std").as_double_array(); - R_gyro_ = Eigen::Matrix3d::Zero(); - for (int i = 0; i < 3; ++i) R_gyro_(i,i) = diagRgyro[i] * diagRgyro[i]; - - this->declare_parameter>("diag_Rdvl_std"); - auto diagRdvl = this->get_parameter("diag_Rdvl_std").as_double_array(); - R_dvl_ = Eigen::Matrix3d::Zero(); - for (int i = 0; i < 3; ++i) R_dvl_(i,i) = diagRdvl[i] * diagRdvl[i]; - - tukf_ = std::make_unique(x0, Q, dt_); - tukf_->x.covariance = P0; - tukf_->x.fill_states(x0_e); -} - -void TUKFNode::gyro_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { - Eigen::Vector3d gyro(msg->angular_velocity.x, - msg->angular_velocity.y, - msg->angular_velocity.z); - MeasModel m; - m.measurement = gyro; - m.covariance = R_gyro_; - m.H = [](const AUVState& s) { - MeasModel mm; - Eigen::Matrix3x12d Hm = Eigen::Matrix3x12d::Zero(); - Hm.block<3,3>(0,9) = Eigen::Matrix3d::Identity(); - mm.measurement = Hm * s.dynamic_part(); - return mm; - }; - - tukf_->measurement_update(state_, m); - state_ = tukf_->posterior_estimate(state_, m); -} - -void TUKFNode::dvl_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { - Eigen::Vector3d vel(msg->twist.twist.linear.x, - msg->twist.twist.linear.y, - msg->twist.twist.linear.z); - Eigen::Matrix3d cov; - cov << msg->twist.covariance[0], msg->twist.covariance[1], msg->twist.covariance[2], - msg->twist.covariance[6], msg->twist.covariance[7], msg->twist.covariance[8], - msg->twist.covariance[12], msg->twist.covariance[13], msg->twist.covariance[14]; - MeasModel m; - m.measurement = vel; - m.covariance = R_dvl_; - - tukf_->measurement_update(state_, m); - state_ = tukf_->posterior_estimate(state_, m); -} - -void TUKFNode::wrench_callback(const geometry_msgs::msg::WrenchStamped::SharedPtr msg) { - Eigen::Vector6d wrench_input(msg->wrench.force.x, - msg->wrench.force.y, - msg->wrench.force.z, - msg->wrench.torque.x, - msg->wrench.torque.y, - msg->wrench.torque.z); - - state_ = tukf_->unscented_transform(state_, control_force); -} - -void TUKFNode::publish_odom() { - nav_msgs::msg::Odometry odom; - odom.header.stamp = this->now(); - odom.header.frame_id = "odom"; - - odom.pose.pose.position.x = state_.position.x(); - odom.pose.pose.position.y = state_.position.y(); - odom.pose.pose.position.z = state_.position.z(); - odom.pose.pose.orientation.w = state_.orientation.w(); - odom.pose.pose.orientation.x = state_.orientation.x(); - odom.pose.pose.orientation.y = state_.orientation.y(); - odom.pose.pose.orientation.z = state_.orientation.z(); - - odom.twist.twist.linear.x = state_.velocity.x(); - odom.twist.twist.linear.y = state_.velocity.y(); - odom.twist.twist.linear.z = state_.velocity.z(); - odom.twist.twist.angular.x = state_.angular_velocity.x(); - odom.twist.twist.angular.y = state_.angular_velocity.y(); - odom.twist.twist.angular.z = state_.angular_velocity.z(); - - odom_pub_->publish(odom); -} diff --git a/navigation/tukf_rsi/src/tukf_rsi_utils.cpp b/navigation/tukf_rsi/src/tukf_rsi_utils.cpp deleted file mode 100644 index 882fe0cf8..000000000 --- a/navigation/tukf_rsi/src/tukf_rsi_utils.cpp +++ /dev/null @@ -1,199 +0,0 @@ - -#include "tukf_rsi_utils.hpp" -#include - -Eigen::Quaterniond quaternionMean( - const std::vector& quats, - double tol, - int maxIter -) { - Eigen::Quaterniond mean_q = quats.front(); - int n = int(quats.size()); - - for (int iter = 0; iter < maxIter; ++iter) { - Eigen::Vector3d errAvg = Eigen::Vector3d::Zero(); - - for (const auto& q : quats) { - - Eigen::Quaterniond e = q * mean_q.conjugate(); - - double w = std::clamp(e.w(), -1.0, 1.0); - double angle = 2 * std::acos(w); - - Eigen::Vector3d axis; - - if (std::abs(angle) < tol) { - axis.setZero(); - } else { - axis = (angle / std::sin(angle / 2.0)) * e.vec(); - } - errAvg += axis; - } - errAvg /= double(n); - - if (errAvg.norm() < tol) break; - double errNorm = errAvg.norm(); - Eigen::Quaterniond dq - - if (errNorm > tol) { - dq.w() = std::cos(errNorm/2.0); - dq.vec() = std::sin(errNorm/2.0) * (errAvg/errNorm); - } else { - dq = Eigen::Quaterniond::Identity(); - } - mean_q = dq * mean_q; - mean_q.normalize(); - } - return mean_q; -} - -Eigen::Vector37d mean_set( - const std::vector& setPoints, - double tol, - int maxIter -) { - int n = int(setPoints.size()); - - Eigen::Vector3d posAvg = Eigen::Vector3d::Zero(); - Eigen::Vector3d velAvg = Eigen::Vector3d::Zero(); - Eigen::Vector3d angVelAvg = Eigen::Vector3d::Zero(); - Eigen::Vector9d inAvg = Eigen::Vector9d::Zero(); - Eigen::Vector6d amAvg = Eigen::Vector6d::Zero(); - Eigen::Vector6d dAvg = Eigen::Vector6d::Zero(); - Eigen::Vector4d gAvg = Eigen::Vector4d::Zero(); - - std::vector quats; - quats.reserve(n); - - for (const auto& s : setPoints) { - posAvg += s.position; - velAvg += s.velocity; - angVelAvg += s.angular_velocity; - inAvg += s.inertia; - amAvg += s.added_mass; - dAvg += s.damping; - gAvg += s.g_eta; - quats.push_back(s.orientation); - } - posAvg /= double(n); - velAvg /= double(n); - angVelAvg /= double(n); - inAvg /= double(n); - amAvg /= double(n); - dAvg /= double(n); - gAvg /= double(n); - Eigen::Quaterniond qMean = quaternion_mean(quats, tol, maxIter); - - AUVState meanState; - meanState.position = posAvg; - meanState.orientation = qMean; - meanState.velocity = velAvg; - meanState.angular_velocity = angVelAvg; - meanState.inertia = inAvg; - meanState.added_mass = amAvg; - meanState.damping = dAvg; - meanState.g_eta = gAvg; - - return meanState.asVector(); -} - -Eigen::Vector3d mean_measurement(const std::vector& setPoints) { - Eigen::Vector3d avg = Eigen::Vector3d::Zero(); - for (const auto& m : setPoints) avg += m.measurement; - return avg / double(setPoints.size()); -} - -Eigen::Matrix37d covariance_set( - const std::vector& setPoints, - const Eigen::Vector37d& meanVec, - double tol -) { - int n = int(setPoints.size()); - AUVState meanState; - meanState.fillStates(meanVec); - std::vector quats; - quats.reserve(n); - - for (const auto& s : setPoints) quats.push_back(s.orientation); - meanState.orientation = quaternion_mean(quats, tol); - - Eigen::Matrix37d cov = Eigen::Matrix37d::Zero(); - for (const auto& s : setPoints) { - Eigen::Vector37d d = Eigen::Vector37d::Zero(); - - d.segment<3>(0) = s.position - meanState.position; - - Eigen::Quaterniond e = s.orientation * meanState.orientation.conjugate(); - double w = std::clamp(e.w(), -1.0, 1.0); - double angle = 2 * std::acos(w); - - - Eigen::Vector3d err; - if (std::abs(angle) < tol) err.setZero(); - else err = (angle / std::sin(angle/2.0)) * e.vec(); - - d.segment<3>(3) = err; - - d.segment<3>(6) = s.velocity - meanState.velocity; - d.segment<3>(9) = s.angular_velocity - meanState.angular_velocity; - d.segment<9>(12) = s.inertia - meanState.inertia; - d.segment<6>(21) = s.added_mass - meanState.added_mass; - d.segment<6>(27) = s.damping - meanState.damping; - d.segment<4>(33) = s.g_eta - meanState.g_eta; - cov += d * d.transpose(); - } - return cov / double(n); -} - -Eigen::Matrix3d covariance_measurement( - const std::vector& setPoints, - const Eigen::Vector3d& mean -) { - Eigen::Matrix3d cov = Eigen::Matrix3d::Zero(); - for (const auto& m : setPoints) { - Eigen::Vector3d d = m.measurement - mean; - cov += d * d.transpose(); - } - return cov / double(setPoints.size()); -} - -Eigen::Matrix cross_covariance( - const std::vector& setY, - const Eigen::Vector37d& meanY, - const std::vector& setZ, - const Eigen::Vector3d& meanZ, - double tol -) { - int n = int(setY.size()); - AUVState meanState; - meanState.fill_states(meanY); - std::vector quats; - quats.reserve(n); - for (const auto& s : setY) quats.push_back(s.orientation); - meanState.orientation = quaternion_cean(quats, tol); - - Eigen::Matrix cov = Eigen::Matrix::Zero(); - for (size_t i = 0; i < setY.size(); ++i) { - const auto& s = setY[i]; - - Eigen::Vector37d dY = Eigen::Vector37d::Zero(); - dY.segment<3>(0) = s.position - meanState.position; - Eigen::Quaterniond e = s.orientation * meanState.orientation.conjugate(); - double w = std::clamp(e.w(), -1.0, 1.0); - double angle = 2 * std::acos(w); - Eigen::Vector3d err; - if (std::abs(angle) < tol) err.setZero(); - else err = (angle / std::sin(angle/2.0)) * e.vec(); - dY.segment<3>(3) = err; - dY.segment<3>(6) = s.velocity - meanState.velocity; - dY.segment<3>(9) = s.angular_velocity - meanState.angular_velocity; - dY.segment<9>(12) = s.inertia - meanState.inertia; - dY.segment<6>(21) = s.added_mass - meanState.added_mass; - dY.segment<6>(27) = s.damping - meanState.damping; - dY.segment<4>(33) = s.g_eta - meanState.g_eta; - - Eigen::Vector3d dZ = setZ[i].measurement - meanZ; - cov += dY * dZ.transpose(); - } - return cov / double(n); -} \ No newline at end of file From 7d112b8d85508843250ad762e5992f3a470b2d5c Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Sun, 5 Oct 2025 18:54:00 +0000 Subject: [PATCH 25/30] [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci --- navigation/eskf/include/eskf/typedefs.hpp | 3 ++- navigation/eskf/src/eskf.cpp | 33 +++++++++++++++-------- 2 files changed, 24 insertions(+), 12 deletions(-) diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index 4dbdb6da3..d6433d46d 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -60,7 +60,8 @@ struct state_quat { euler_diff = (quat * other.quat.inverse()) .toRotationMatrix() - .eulerAngles(0, 1, 2) + Eigen::Vector3d(-M_PI, M_PI, -M_PI); + .eulerAngles(0, 1, 2) + + Eigen::Vector3d(-M_PI, M_PI, -M_PI); vec << pos - other.pos, vel - other.vel, euler_diff, gyro_bias - other.gyro_bias, accel_bias - other.accel_bias, diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index 3838e2f1a..4a5501405 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -61,12 +61,14 @@ Eigen::Matrix3x19d ESKF::calculate_hx() { Eigen::Vector3d q_vec(q.x(), q.y(), q.z()); Eigen::Matrix3d I3 = Eigen::Matrix3d::Identity(); - Eigen::Matrix dhdq; - dhdq.col(0) = 2*( qw*v_n + q_vec.cross(v_n) ); - dhdq.block<3,3>(0,1) = 2*( q_vec.dot(v_n)*I3 + q_vec*v_n.transpose() - v_n*q_vec.transpose() - qw*skew(v_n) ); + Eigen::Matrix dhdq; + dhdq.col(0) = 2 * (qw * v_n + q_vec.cross(v_n)); + dhdq.block<3, 3>(0, 1) = + 2 * (q_vec.dot(v_n) * I3 + q_vec * v_n.transpose() - + v_n * q_vec.transpose() - qw * skew(v_n)); // Assign quaternion derivative (3x4 block at columns 6:9) - Hx.block<3,4>(0,6) = dhdq; + Hx.block<3, 4>(0, 6) = dhdq; return Hx; } @@ -83,22 +85,28 @@ Eigen::Matrix3x18d ESKF::calculate_h_jacobian() { Eigen::Vector3d ESKF::calculate_h() { Eigen::Vector3d h; - Eigen::Matrix3d R_bn = current_nom_state_.quat.normalized().toRotationMatrix().transpose(); + Eigen::Matrix3d R_bn = + current_nom_state_.quat.normalized().toRotationMatrix().transpose(); h = R_bn * current_nom_state_.vel; - //0.027293, 0.028089, 0.028089, 0.00255253, 0.00270035, 0.00280294, + // 0.027293, 0.028089, 0.028089, 0.00255253, 0.00270035, 0.00280294, return h; } void ESKF::nominal_state_discrete(const imu_measurement& imu_meas, const double dt) { - Eigen::Vector3d acc = current_nom_state_.quat.normalized().toRotationMatrix() * (imu_meas.accel - current_nom_state_.accel_bias) + current_nom_state_.gravity; + Eigen::Vector3d acc = + current_nom_state_.quat.normalized().toRotationMatrix() * + (imu_meas.accel - current_nom_state_.accel_bias) + + current_nom_state_.gravity; Eigen::Vector3d gyro = (imu_meas.gyro - current_nom_state_.gyro_bias) * dt; - current_nom_state_.pos = current_nom_state_.pos + current_nom_state_.vel * dt + 0.5 * sq(dt) * acc; + current_nom_state_.pos = current_nom_state_.pos + + current_nom_state_.vel * dt + 0.5 * sq(dt) * acc; current_nom_state_.vel = current_nom_state_.vel + dt * acc; - current_nom_state_.quat = (current_nom_state_.quat * vector3d_to_quaternion(gyro)); + current_nom_state_.quat = + (current_nom_state_.quat * vector3d_to_quaternion(gyro)); current_nom_state_.quat.normalize(); current_nom_state_.gyro_bias = current_nom_state_.gyro_bias; @@ -132,7 +140,8 @@ void ESKF::error_state_prediction(const imu_measurement& imu_meas, std::tie(A_d, GQG_d) = van_loan_discretization(A_c, G_c, dt); state_euler next_error_state; - current_error_state_.covariance = A_d * current_error_state_.covariance * A_d.transpose() + GQG_d; + current_error_state_.covariance = + A_d * current_error_state_.covariance * A_d.transpose() + GQG_d; } void ESKF::NIS(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S) { @@ -160,7 +169,9 @@ void ESKF::measurement_update(const dvl_measurement& dvl_meas) { void ESKF::injection_and_reset() { current_nom_state_.pos = current_nom_state_.pos + current_error_state_.pos; current_nom_state_.vel = current_nom_state_.vel + current_error_state_.vel; - current_nom_state_.quat = current_nom_state_.quat * vector3d_to_quaternion(current_error_state_.euler); + current_nom_state_.quat = + current_nom_state_.quat * + vector3d_to_quaternion(current_error_state_.euler); current_nom_state_.quat.normalize(); current_nom_state_.gyro_bias = current_nom_state_.gyro_bias + current_error_state_.gyro_bias; From ccc834bc3318e9859303cfaa9f405112c45a86ed Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Anders=20H=C3=B8gden?= Date: Tue, 7 Oct 2025 10:41:25 +0200 Subject: [PATCH 26/30] ci: add node test for eskf --- .github/workflows/ros-node-tests.yml | 1 + navigation/eskf/CMakeLists.txt | 2 -- navigation/eskf/include/eskf/eskf_ros.hpp | 1 - navigation/eskf/launch/eskf.launch.py | 1 + tests/ros_node_tests/eskf_node_test.sh | 39 +++++++++++++++++++++++ 5 files changed, 41 insertions(+), 3 deletions(-) create mode 100644 tests/ros_node_tests/eskf_node_test.sh diff --git a/.github/workflows/ros-node-tests.yml b/.github/workflows/ros-node-tests.yml index c85fbe1f7..8ff052ded 100644 --- a/.github/workflows/ros-node-tests.yml +++ b/.github/workflows/ros-node-tests.yml @@ -14,6 +14,7 @@ jobs: matrix: test_script: - "tests/ros_node_tests/dp_node_test.sh" + - "tests/ros_node_tests/eskf_node_test.sh" uses: vortexntnu/vortex-ci/.github/workflows/reusable-ros2-simulator-test.yml@main with: vcs_repos_file: "tests/dependencies.repos" diff --git a/navigation/eskf/CMakeLists.txt b/navigation/eskf/CMakeLists.txt index c431c235f..6c8167609 100644 --- a/navigation/eskf/CMakeLists.txt +++ b/navigation/eskf/CMakeLists.txt @@ -18,7 +18,6 @@ find_package(tf2 REQUIRED) find_package(vortex_msgs REQUIRED) find_package(spdlog REQUIRED) find_package(fmt REQUIRED) -find_package(stonefish_ros2 REQUIRED) if(NOT DEFINED EIGEN3_INCLUDE_DIR) set(EIGEN3_INCLUDE_DIR ${EIGEN3_INCLUDE_DIRS}) @@ -43,7 +42,6 @@ ament_target_dependencies(eskf_node vortex_msgs spdlog fmt - stonefish_ros2 ) target_link_libraries(eskf_node diff --git a/navigation/eskf/include/eskf/eskf_ros.hpp b/navigation/eskf/include/eskf/eskf_ros.hpp index 424e583f7..5975d9cc7 100644 --- a/navigation/eskf/include/eskf/eskf_ros.hpp +++ b/navigation/eskf/include/eskf/eskf_ros.hpp @@ -11,7 +11,6 @@ #include #include #include -#include #include "eskf/eskf.hpp" #include "eskf/typedefs.hpp" #include "spdlog/spdlog.h" diff --git a/navigation/eskf/launch/eskf.launch.py b/navigation/eskf/launch/eskf.launch.py index 84284f804..1e9d64759 100644 --- a/navigation/eskf/launch/eskf.launch.py +++ b/navigation/eskf/launch/eskf.launch.py @@ -14,6 +14,7 @@ def generate_launch_description(): package="eskf", executable="eskf_node", name="eskf_node", + namespace="orca", parameters=[ eskf_params, ], diff --git a/tests/ros_node_tests/eskf_node_test.sh b/tests/ros_node_tests/eskf_node_test.sh new file mode 100644 index 000000000..35ba6e91e --- /dev/null +++ b/tests/ros_node_tests/eskf_node_test.sh @@ -0,0 +1,39 @@ +#!/bin/bash +set -e +set -o pipefail + +echo "Testing that the ESKF node is able to start up and publish odom" + +# Load ROS 2 environment +echo "Setting up ROS 2 environment..." +. /opt/ros/humble/setup.sh +. "${WORKSPACE:-$HOME/ros2_ws}/install/setup.bash" + +# Function to terminate processes safely on error +cleanup() { + echo "Error detected. Cleaning up..." + kill -TERM -"$ESKF_PID" || true + exit 1 +} +trap cleanup ERR + +# Launch eskf node +setsid ros2 launch eskf eskf.launch.py & +ESKF_PID=$! +echo "Launched eskf with PID: $ESKF_PID" + +# Check for ROS errors before continuing +if journalctl -u ros2 | grep -i "error"; then + echo "Error detected in ROS logs. Exiting..." + exit 1 +fi + +# Check if eskf correctly publishes odom +echo "Waiting for odom data..." +timeout 10s ros2 topic echo /orca/odom --once +echo "Got odom data" + +# Terminate processes +kill -TERM -"$ESKF_PID" + +echo "Test completed successfully." From 916fe462b4e1e16d80f71242a75670b1aa27727d Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Tue, 7 Oct 2025 20:28:48 +0200 Subject: [PATCH 27/30] feat: Added fancy text for starting filter --- navigation/eskf/include/eskf/eskf.hpp | 12 ++---------- navigation/eskf/include/eskf/eskf_utils.hpp | 20 ++++++++++++++++++++ navigation/eskf/include/eskf/typedefs.hpp | 11 +++++------ navigation/eskf/launch/eskf.launch.py | 2 +- navigation/eskf/package.xml | 4 ++-- navigation/eskf/src/eskf.cpp | 15 +-------------- navigation/eskf/src/eskf_ros.cpp | 10 +++++++++- navigation/eskf/src/eskf_utils.cpp | 13 +++++++++++++ 8 files changed, 53 insertions(+), 34 deletions(-) diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp index 214f462c4..87221a3b6 100644 --- a/navigation/eskf/include/eskf/eskf.hpp +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -24,8 +24,8 @@ class ESKF { std::pair dvl_update( const dvl_measurement& dvl_meas); - // NIS - double NIS_; + // Normalized Innovation Squared + double NIS_{}; private: // @brief Predict the nominal state @@ -63,23 +63,15 @@ class ESKF { const Eigen::Matrix18x12d& G_c, const double dt); - // @brief Calculate the delta quaternion matrix - // @param nom_state: Nominal state - // @return Delta quaternion matrix - Eigen::Matrix4x3d calculate_q_delta(); - // @brief Calculate the measurement matrix jakobian - // @param nom_state: Nominal state // @return Measurement matrix Eigen::Matrix3x19d calculate_hx(); // @brief Calculate the full measurement matrix - // @param nom_state: Nominal state // @return Measurement matrix Eigen::Matrix3x18d calculate_h_jacobian(); // @brief Calculate the measurement - // @param nom_state: Nominal state // @return Measurement Eigen::Vector3d calculate_h(); diff --git a/navigation/eskf/include/eskf/eskf_utils.hpp b/navigation/eskf/include/eskf/eskf_utils.hpp index 4fcaed412..4481f2787 100644 --- a/navigation/eskf/include/eskf/eskf_utils.hpp +++ b/navigation/eskf/include/eskf/eskf_utils.hpp @@ -5,14 +5,34 @@ #include "eigen3/Eigen/Dense" #include "eskf/typedefs.hpp" +// @brief Compute the skew-symmetric matrix of a vector +// @param v: Input vector +// @return Skew-symmetric matrix Eigen::Matrix3d skew(const Eigen::Vector3d& v); +// @brief Square a value +// @param value: Input value +// @return Squared value double sq(const double& value); +// @brief Normalize an angle to the range [-pi, pi] +// @param angle: Input angle in radians +// @return Normalized angle in radians double ssa(const double& angle); +// @brief Calculate the transformation matrix using a quaternion +// @param quat: Input quaternion +// @return Transformation matrix +Eigen::Matrix4x3d calculate_T_q(const Eigen::Quaterniond& quat); + +// @brief Convert a rotation vector to a quaternion +// @param vector: Input rotation vector +// @return Corresponding quaternion Eigen::Quaterniond vector3d_to_quaternion(const Eigen::Vector3d& vector); +// @brief Convert Euler angles to a quaternion +// @param euler: Input Euler angles (roll, pitch, yaw) in radians +// @return Corresponding quaternion Eigen::Quaterniond euler_to_quaternion(const Eigen::Vector3d& euler); #endif // ESKF_UTILS_HPP diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index d6433d46d..54a88032a 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -36,16 +36,15 @@ Eigen::Matrix createDiagonalMatrix( return Eigen::Map>(diag.data()) .asDiagonal(); } - struct state_quat { - Eigen::Vector3d pos = Eigen::Vector3d(5.58, 0.66, 0.12); + Eigen::Vector3d pos = Eigen::Vector3d::Zero(); Eigen::Vector3d vel = Eigen::Vector3d::Zero(); - Eigen::Quaterniond quat = Eigen::Quaterniond(0.98, -0.047, 0.028, -0.18); + Eigen::Quaterniond quat = Eigen::Quaterniond::Identity(); Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero(); Eigen::Vector3d accel_bias = Eigen::Vector3d::Zero(); - Eigen::Vector3d gravity = Eigen::Vector3d::Zero(); + Eigen::Vector3d gravity = Eigen::Vector3d(0, 0, 9.81); - state_quat() { gravity << 0, 0, 9.81; } + state_quat() = default; Eigen::Vector19d as_vector() const { Eigen::Vector19d vec; @@ -87,7 +86,7 @@ struct state_euler { Eigen::Vector3d euler = Eigen::Vector3d::Zero(); Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero(); Eigen::Vector3d accel_bias = Eigen::Vector3d::Zero(); - Eigen::Vector3d gravity = Eigen::Vector3d::Zero(); + Eigen::Vector3d gravity = Eigen::Vector3d(0, 0, 9.81); Eigen::Matrix18d covariance = Eigen::Matrix18d::Zero(); diff --git a/navigation/eskf/launch/eskf.launch.py b/navigation/eskf/launch/eskf.launch.py index 1e9d64759..d7b3a8a4e 100644 --- a/navigation/eskf/launch/eskf.launch.py +++ b/navigation/eskf/launch/eskf.launch.py @@ -14,7 +14,7 @@ def generate_launch_description(): package="eskf", executable="eskf_node", name="eskf_node", - namespace="orca", + # namespace="orca", parameters=[ eskf_params, ], diff --git a/navigation/eskf/package.xml b/navigation/eskf/package.xml index d3d8dc416..015e6f71c 100644 --- a/navigation/eskf/package.xml +++ b/navigation/eskf/package.xml @@ -2,9 +2,9 @@ eskf - 1.0.0 + 2.0.0 Error-state Kalman filter - talhanc + talhanc MIT ament_cmake diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index 4a5501405..8507244e9 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -31,19 +31,6 @@ std::pair ESKF::van_loan_discretization( return {A_d, GQG_d}; } -Eigen::Matrix4x3d ESKF::calculate_q_delta() { - Eigen::Matrix4x3d q_delta_theta = Eigen::Matrix4x3d::Zero(); - double qw = current_nom_state_.quat.w(); - double qx = current_nom_state_.quat.x(); - double qy = current_nom_state_.quat.y(); - double qz = current_nom_state_.quat.z(); - - q_delta_theta << -qx, -qy, -qz, qw, -qz, qy, qz, qw, -qx, -qy, qx, qw; - - q_delta_theta *= 0.5; - return q_delta_theta; -} - Eigen::Matrix3x19d ESKF::calculate_hx() { Eigen::Matrix3x19d Hx = Eigen::Matrix3x19d::Zero(); @@ -76,7 +63,7 @@ Eigen::Matrix3x19d ESKF::calculate_hx() { Eigen::Matrix3x18d ESKF::calculate_h_jacobian() { Eigen::Matrix19x18d x_delta = Eigen::Matrix19x18d::Zero(); x_delta.block<6, 6>(0, 0) = Eigen::Matrix6d::Identity(); - x_delta.block<4, 3>(6, 6) = calculate_q_delta(); + x_delta.block<4, 3>(6, 6) = calculate_T_q(current_nom_state_.quat); x_delta.block<9, 9>(10, 9) = Eigen::Matrix9d::Identity(); Eigen::Matrix3x18d H = calculate_hx() * x_delta; diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index c379732e3..a79ae09bb 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -12,7 +12,15 @@ ESKFNode::ESKFNode() : Node("eskf_node") { set_parameters(); - spdlog::info("ESKF Node Initialized"); + auto start_message{R"( + ________ ______ ___ ____ ________ + |_ __ |.' ____ \ |_ ||_ _| |_ __ | + | |_ \_|| (___ \_| | |_/ / | |_ \_| + | _| _ _.____`. | __'. | _| + _| |__/ || \____) | _| | \ \_ _| |_ + |________| \______.'|____||____||_____| + )"}; + spdlog::info("\n{}", start_message); } void ESKFNode::set_subscribers_and_publisher() { diff --git a/navigation/eskf/src/eskf_utils.cpp b/navigation/eskf/src/eskf_utils.cpp index 88d04c3d5..0b9ae007f 100644 --- a/navigation/eskf/src/eskf_utils.cpp +++ b/navigation/eskf/src/eskf_utils.cpp @@ -17,6 +17,19 @@ double ssa(const double& angle) { return angle_ssa; } +Eigen::Matrix4x3d calculate_T_q(const Eigen::Quaterniond& quat) { + Eigen::Matrix4x3d T_q = Eigen::Matrix4x3d::Zero(); + double qw = quat.w(); + double qx = quat.x(); + double qy = quat.y(); + double qz = quat.z(); + + T_q << -qx, -qy, -qz, qw, -qz, qy, qz, qw, -qx, -qy, qx, qw; + + T_q *= 0.5; + return T_q; +} + Eigen::Quaterniond vector3d_to_quaternion(const Eigen::Vector3d& vector) { double angle = vector.norm(); if (angle < 1e-8) { From c6f948ee8fca7a557a0f010c5b231119a27fd280 Mon Sep 17 00:00:00 2001 From: Talha Nauman Choudhry Date: Tue, 7 Oct 2025 22:06:01 +0200 Subject: [PATCH 28/30] fix: moved the fancy text variable outside the initiation --- navigation/eskf/CMakeLists.txt | 34 +++++++++++++++------ navigation/eskf/include/eskf/eskf.hpp | 6 ++-- navigation/eskf/include/eskf/eskf_ros.hpp | 17 ++++++----- navigation/eskf/include/eskf/eskf_utils.hpp | 4 +-- navigation/eskf/include/eskf/typedefs.hpp | 10 +++--- navigation/eskf/src/eskf_node.cpp | 9 ------ navigation/eskf/src/eskf_ros.cpp | 25 +++++++++------ navigation/eskf/src/eskf_utils.cpp | 4 +-- 8 files changed, 61 insertions(+), 48 deletions(-) delete mode 100644 navigation/eskf/src/eskf_node.cpp diff --git a/navigation/eskf/CMakeLists.txt b/navigation/eskf/CMakeLists.txt index 6c8167609..8fc8a02cc 100644 --- a/navigation/eskf/CMakeLists.txt +++ b/navigation/eskf/CMakeLists.txt @@ -11,6 +11,7 @@ endif() find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) +find_package(rclcpp_components REQUIRED) find_package(nav_msgs REQUIRED) find_package(geometry_msgs REQUIRED) find_package(Eigen3 REQUIRED) @@ -22,19 +23,22 @@ find_package(fmt REQUIRED) if(NOT DEFINED EIGEN3_INCLUDE_DIR) set(EIGEN3_INCLUDE_DIR ${EIGEN3_INCLUDE_DIRS}) endif() + include_directories(${EIGEN3_INCLUDE_DIR}) include_directories(include) -add_executable(eskf_node +set(LIB_NAME "${PROJECT_NAME}_component") + +add_library(${LIB_NAME} SHARED src/eskf.cpp src/eskf_ros.cpp - src/eskf_node.cpp src/eskf_utils.cpp ) -ament_target_dependencies(eskf_node +ament_target_dependencies(${LIB_NAME} PUBLIC rclcpp + rclcpp_components geometry_msgs nav_msgs Eigen3 @@ -44,17 +48,29 @@ ament_target_dependencies(eskf_node fmt ) -target_link_libraries(eskf_node - fmt::fmt +rclcpp_components_register_node( + ${LIB_NAME} + PLUGIN "ESKFNode" + EXECUTABLE ${PROJECT_NAME}_node +) + +ament_export_targets(export_${LIB_NAME}) + +install(TARGETS ${LIB_NAME} + EXPORT export_${LIB_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin ) -install(TARGETS - eskf_node - DESTINATION lib/${PROJECT_NAME}) +install( + DIRECTORY include/ + DESTINATION include +) install(DIRECTORY - config launch + config DESTINATION share/${PROJECT_NAME}/ ) diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp index 87221a3b6..ea3a72159 100644 --- a/navigation/eskf/include/eskf/eskf.hpp +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -76,13 +76,13 @@ class ESKF { Eigen::Vector3d calculate_h(); // Process noise covariance matrix - Eigen::Matrix12d Q_; + Eigen::Matrix12d Q_{}; // Member variable for the current error state - state_euler current_error_state_; + state_euler current_error_state_{}; // Member variable for the current nominal state - state_quat current_nom_state_; + state_quat current_nom_state_{}; }; #endif // ESKF_HPP diff --git a/navigation/eskf/include/eskf/eskf_ros.hpp b/navigation/eskf/include/eskf/eskf_ros.hpp index 5975d9cc7..431e93ea1 100644 --- a/navigation/eskf/include/eskf/eskf_ros.hpp +++ b/navigation/eskf/include/eskf/eskf_ros.hpp @@ -17,7 +17,8 @@ class ESKFNode : public rclcpp::Node { public: - explicit ESKFNode(); + explicit ESKFNode( + const rclcpp::NodeOptions& options = rclcpp::NodeOptions()); private: // @brief Callback function for the imu topic @@ -51,23 +52,23 @@ class ESKFNode : public rclcpp::Node { rclcpp::TimerBase::SharedPtr odom_pub_timer_; - state_quat nom_state_; + state_quat nom_state_{}; - state_euler error_state_; + state_euler error_state_{}; - imu_measurement imu_meas_; + imu_measurement imu_meas_{}; - dvl_measurement dvl_meas_; + dvl_measurement dvl_meas_{}; - eskf_params eskf_params_; + eskf_params eskf_params_{}; std::unique_ptr eskf_; bool first_imu_msg_received_ = false; - Eigen::Matrix3d R_imu_eskf_; + Eigen::Matrix3d R_imu_eskf_{}; - rclcpp::Time last_imu_time_; + rclcpp::Time last_imu_time_{}; }; #endif // ESKF_ROS_HPP diff --git a/navigation/eskf/include/eskf/eskf_utils.hpp b/navigation/eskf/include/eskf/eskf_utils.hpp index 4481f2787..0fe06ee7a 100644 --- a/navigation/eskf/include/eskf/eskf_utils.hpp +++ b/navigation/eskf/include/eskf/eskf_utils.hpp @@ -13,12 +13,12 @@ Eigen::Matrix3d skew(const Eigen::Vector3d& v); // @brief Square a value // @param value: Input value // @return Squared value -double sq(const double& value); +double sq(double value); // @brief Normalize an angle to the range [-pi, pi] // @param angle: Input angle in radians // @return Normalized angle in radians -double ssa(const double& angle); +double ssa(double angle); // @brief Calculate the transformation matrix using a quaternion // @param quat: Input quaternion diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index 54a88032a..77432ecca 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -47,15 +47,15 @@ struct state_quat { state_quat() = default; Eigen::Vector19d as_vector() const { - Eigen::Vector19d vec; + Eigen::Vector19d vec{}; vec << pos, vel, quat.w(), quat.x(), quat.y(), quat.z(), gyro_bias, accel_bias, gravity; return vec; } Eigen::Vector18d nees_error(const state_quat& other) const { - Eigen::Vector18d vec; - Eigen::Vector3d euler_diff; + Eigen::Vector18d vec{}; + Eigen::Vector3d euler_diff{}; euler_diff = (quat * other.quat.inverse()) .toRotationMatrix() @@ -69,7 +69,7 @@ struct state_quat { } state_quat operator-(const state_quat& other) const { - state_quat diff; + state_quat diff{}; diff.pos = pos - other.pos; diff.vel = vel - other.vel; diff.quat = quat * other.quat.inverse(); @@ -91,7 +91,7 @@ struct state_euler { Eigen::Matrix18d covariance = Eigen::Matrix18d::Zero(); Eigen::Vector18d as_vector() const { - Eigen::Vector18d vec; + Eigen::Vector18d vec{}; vec << pos, vel, euler, gyro_bias, accel_bias, gravity; return vec; } diff --git a/navigation/eskf/src/eskf_node.cpp b/navigation/eskf/src/eskf_node.cpp deleted file mode 100644 index 196fa7916..000000000 --- a/navigation/eskf/src/eskf_node.cpp +++ /dev/null @@ -1,9 +0,0 @@ -#include "eskf/eskf_ros.hpp" - -int main(int argc, char** argv) { - rclcpp::init(argc, argv); - spdlog::info("Starting ESKF Node"); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - return 0; -} diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index a79ae09bb..ce9e229ed 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -1,9 +1,20 @@ #include "eskf/eskf_ros.hpp" #include +#include #include "eskf/eskf_utils.hpp" #include "eskf/typedefs.hpp" -ESKFNode::ESKFNode() : Node("eskf_node") { +auto start_message{R"( + ________ ______ ___ ____ ________ + |_ __ |.' ____ \ |_ ||_ _| |_ __ | + | |_ \_|| (___ \_| | |_/ / | |_ \_| + | _| _ _.____`. | __'. | _| + _| |__/ || \____) | _| | \ \_ _| |_ + |________| \______.'|____||____||_____| +)"}; + +ESKFNode::ESKFNode(const rclcpp::NodeOptions& options) + : Node("eskf_node", options) { time_step = std::chrono::milliseconds(1); odom_pub_timer_ = this->create_wall_timer( time_step, std::bind(&ESKFNode::publish_odom, this)); @@ -12,15 +23,7 @@ ESKFNode::ESKFNode() : Node("eskf_node") { set_parameters(); - auto start_message{R"( - ________ ______ ___ ____ ________ - |_ __ |.' ____ \ |_ ||_ _| |_ __ | - | |_ \_|| (___ \_| | |_/ / | |_ \_| - | _| _ _.____`. | __'. | _| - _| |__/ || \____) | _| | \ \_ _| |_ - |________| \______.'|____||____||_____| - )"}; - spdlog::info("\n{}", start_message); + spdlog::info(start_message); } void ESKFNode::set_subscribers_and_publisher() { @@ -149,3 +152,5 @@ void ESKFNode::publish_odom() { odom_msg.header.stamp = this->now(); odom_pub_->publish(odom_msg); } + +RCLCPP_COMPONENTS_REGISTER_NODE(ESKFNode) diff --git a/navigation/eskf/src/eskf_utils.cpp b/navigation/eskf/src/eskf_utils.cpp index 0b9ae007f..e7dc4e5e3 100644 --- a/navigation/eskf/src/eskf_utils.cpp +++ b/navigation/eskf/src/eskf_utils.cpp @@ -8,10 +8,10 @@ Eigen::Matrix3d skew(const Eigen::Vector3d& v) { return S; } -double sq(const double& value) { +double sq(const double value) { return value * value; } -double ssa(const double& angle) { +double ssa(const double angle) { double result = fmod(angle + M_PI, 2 * M_PI); double angle_ssa = result < 0 ? result + M_PI : result - M_PI; return angle_ssa; From 80cbd2d1895368064078b85d6c4ced9dc05208ef Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christopher=20Str=C3=B8m?= Date: Sun, 19 Oct 2025 14:25:35 +0200 Subject: [PATCH 29/30] We do a little bit of refactoring MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Christopher Strøm --- navigation/eskf/include/eskf/eskf.hpp | 34 +++++++----- navigation/eskf/include/eskf/eskf_ros.hpp | 10 ---- navigation/eskf/include/eskf/typedefs.hpp | 21 ++++--- navigation/eskf/src/eskf.cpp | 35 ++++++------ navigation/eskf/src/eskf_ros.cpp | 67 +++++++++++++---------- 5 files changed, 83 insertions(+), 84 deletions(-) diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp index ea3a72159..98e12f229 100644 --- a/navigation/eskf/include/eskf/eskf.hpp +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -8,38 +8,39 @@ class ESKF { public: - ESKF(const eskf_params& params); + ESKF(const EskfParams& params); // @brief Update the nominal state and error state // @param imu_meas: IMU measurement // @param dt: Time step - // @return Updated nominal state and error state - std::pair imu_update( - const imu_measurement& imu_meas, - const double dt); + void imu_update(const ImuMeasurement& imu_meas, const double dt); // @brief Update the nominal state and error state // @param dvl_meas: DVL measurement - // @return Updated nominal state and error state - std::pair dvl_update( - const dvl_measurement& dvl_meas); + void dvl_update(const DvlMeasurement& dvl_meas); + + inline StateQuat get_nominal_state() const { + return current_nom_state_; + } + + inline double get_nis() const { + return nis_; + } - // Normalized Innovation Squared - double NIS_{}; private: // @brief Predict the nominal state // @param imu_meas: IMU measurement // @param dt: Time step // @return Predicted nominal state - void nominal_state_discrete(const imu_measurement& imu_meas, + void nominal_state_discrete(const ImuMeasurement& imu_meas, const double dt); // @brief Predict the error state // @param imu_meas: IMU measurement // @param dt: Time step // @return Predicted error state - void error_state_prediction(const imu_measurement& imu_meas, + void error_state_prediction(const ImuMeasurement& imu_meas, const double dt); // @brief Calculate the NIS @@ -49,7 +50,7 @@ class ESKF { // @brief Update the error state // @param dvl_meas: DVL measurement - void measurement_update(const dvl_measurement& dvl_meas); + void measurement_update(const DvlMeasurement& dvl_meas); // @brief Inject the error state into the nominal state and reset the error void injection_and_reset(); @@ -78,11 +79,14 @@ class ESKF { // Process noise covariance matrix Eigen::Matrix12d Q_{}; + // Normalized Innovation Squared + double nis_{}; + // Member variable for the current error state - state_euler current_error_state_{}; + StateEuler current_error_state_{}; // Member variable for the current nominal state - state_quat current_nom_state_{}; + StateQuat current_nom_state_{}; }; #endif // ESKF_HPP diff --git a/navigation/eskf/include/eskf/eskf_ros.hpp b/navigation/eskf/include/eskf/eskf_ros.hpp index 431e93ea1..4a9e699aa 100644 --- a/navigation/eskf/include/eskf/eskf_ros.hpp +++ b/navigation/eskf/include/eskf/eskf_ros.hpp @@ -52,16 +52,6 @@ class ESKFNode : public rclcpp::Node { rclcpp::TimerBase::SharedPtr odom_pub_timer_; - state_quat nom_state_{}; - - state_euler error_state_{}; - - imu_measurement imu_meas_{}; - - dvl_measurement dvl_meas_{}; - - eskf_params eskf_params_{}; - std::unique_ptr eskf_; bool first_imu_msg_received_ = false; diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index 77432ecca..3b4b990bd 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -36,7 +36,7 @@ Eigen::Matrix createDiagonalMatrix( return Eigen::Map>(diag.data()) .asDiagonal(); } -struct state_quat { +struct StateQuat { Eigen::Vector3d pos = Eigen::Vector3d::Zero(); Eigen::Vector3d vel = Eigen::Vector3d::Zero(); Eigen::Quaterniond quat = Eigen::Quaterniond::Identity(); @@ -44,7 +44,7 @@ struct state_quat { Eigen::Vector3d accel_bias = Eigen::Vector3d::Zero(); Eigen::Vector3d gravity = Eigen::Vector3d(0, 0, 9.81); - state_quat() = default; + StateQuat() = default; Eigen::Vector19d as_vector() const { Eigen::Vector19d vec{}; @@ -53,7 +53,7 @@ struct state_quat { return vec; } - Eigen::Vector18d nees_error(const state_quat& other) const { + Eigen::Vector18d nees_error(const StateQuat& other) const { Eigen::Vector18d vec{}; Eigen::Vector3d euler_diff{}; @@ -68,8 +68,8 @@ struct state_quat { return vec; } - state_quat operator-(const state_quat& other) const { - state_quat diff{}; + StateQuat operator-(const StateQuat& other) const { + StateQuat diff{}; diff.pos = pos - other.pos; diff.vel = vel - other.vel; diff.quat = quat * other.quat.inverse(); @@ -80,7 +80,7 @@ struct state_quat { } }; -struct state_euler { +struct StateEuler { Eigen::Vector3d pos = Eigen::Vector3d::Zero(); Eigen::Vector3d vel = Eigen::Vector3d::Zero(); Eigen::Vector3d euler = Eigen::Vector3d::Zero(); @@ -106,20 +106,19 @@ struct state_euler { } }; -struct imu_measurement { +struct ImuMeasurement { Eigen::Vector3d accel = Eigen::Vector3d::Zero(); Eigen::Vector3d gyro = Eigen::Vector3d::Zero(); }; -struct dvl_measurement { +struct DvlMeasurement { Eigen::Vector3d vel = Eigen::Vector3d::Zero(); Eigen::Matrix3d cov = Eigen::Matrix3d::Zero(); }; -struct eskf_params { - double temp = 0.0; +struct EskfParams { Eigen::Matrix12d Q = Eigen::Matrix12d::Zero(); - double dt = 0.0; + Eigen::Matrix18d P = Eigen::Matrix18d::Zero(); }; #endif // ESKF_TYPEDEFS_H diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index 8507244e9..c9d0824e3 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -7,7 +7,14 @@ #include "eskf/typedefs.hpp" #include "iostream" -ESKF::ESKF(const eskf_params& params) : Q_(params.Q) {} +double compute_nis(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S) { + Eigen::Matrix3d S_inv = S.inverse(); + return innovation.transpose() * S_inv * innovation; +} + +ESKF::ESKF(const EskfParams& params) : Q_(params.Q) { + // current_error_state_.covariance = params.P; +} std::pair ESKF::van_loan_discretization( const Eigen::Matrix18d& A_c, @@ -80,7 +87,7 @@ Eigen::Vector3d ESKF::calculate_h() { return h; } -void ESKF::nominal_state_discrete(const imu_measurement& imu_meas, +void ESKF::nominal_state_discrete(const ImuMeasurement& imu_meas, const double dt) { Eigen::Vector3d acc = current_nom_state_.quat.normalized().toRotationMatrix() * @@ -101,7 +108,7 @@ void ESKF::nominal_state_discrete(const imu_measurement& imu_meas, current_nom_state_.gravity = current_nom_state_.gravity; } -void ESKF::error_state_prediction(const imu_measurement& imu_meas, +void ESKF::error_state_prediction(const ImuMeasurement& imu_meas, const double dt) { Eigen::Matrix3d R = current_nom_state_.quat.normalized().toRotationMatrix(); Eigen::Vector3d acc = (imu_meas.accel - current_nom_state_.accel_bias); @@ -126,16 +133,12 @@ void ESKF::error_state_prediction(const imu_measurement& imu_meas, Eigen::Matrix18d A_d, GQG_d; std::tie(A_d, GQG_d) = van_loan_discretization(A_c, G_c, dt); - state_euler next_error_state; + StateEuler next_error_state; current_error_state_.covariance = A_d * current_error_state_.covariance * A_d.transpose() + GQG_d; } -void ESKF::NIS(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S) { - Eigen::Matrix3d S_inv = S.inverse(); - NIS_ = innovation.transpose() * S_inv * innovation; -} -void ESKF::measurement_update(const dvl_measurement& dvl_meas) { +void ESKF::measurement_update(const DvlMeasurement& dvl_meas) { Eigen::Matrix3x18d H = calculate_h_jacobian(); Eigen::Matrix18d P = current_error_state_.covariance; Eigen::Matrix3d R = dvl_meas.cov; @@ -144,7 +147,7 @@ void ESKF::measurement_update(const dvl_measurement& dvl_meas) { Eigen::Matrix18x3d K = P * H.transpose() * S.inverse(); Eigen::Vector3d innovation = dvl_meas.vel - calculate_h(); - NIS(innovation, S); + nis_ = compute_nis(innovation, S); current_error_state_.set_from_vector(K * innovation); Eigen::Matrix18d I_KH = Eigen::Matrix18d::Identity() - K * H; @@ -174,19 +177,15 @@ void ESKF::injection_and_reset() { current_error_state_.set_from_vector(Eigen::Vector18d::Zero()); } -std::pair ESKF::imu_update( - const imu_measurement& imu_meas, +void ESKF::imu_update( + const ImuMeasurement& imu_meas, const double dt) { nominal_state_discrete(imu_meas, dt); error_state_prediction(imu_meas, dt); - - return {current_nom_state_, current_error_state_}; } -std::pair ESKF::dvl_update( - const dvl_measurement& dvl_meas) { +void ESKF::dvl_update( + const DvlMeasurement& dvl_meas) { measurement_update(dvl_meas); injection_and_reset(); - - return {current_nom_state_, current_error_state_}; } diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index ce9e229ed..f516d68df 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -15,9 +15,9 @@ auto start_message{R"( ESKFNode::ESKFNode(const rclcpp::NodeOptions& options) : Node("eskf_node", options) { - time_step = std::chrono::milliseconds(1); - odom_pub_timer_ = this->create_wall_timer( - time_step, std::bind(&ESKFNode::publish_odom, this)); + // time_step = std::chrono::milliseconds(1); + // odom_pub_timer_ = this->create_wall_timer( + // time_step, std::bind(&ESKFNode::publish_odom, this)); set_subscribers_and_publisher(); @@ -64,21 +64,24 @@ void ESKFNode::set_parameters() { diag_Q_std = this->get_parameter("diag_Q_std").as_double_array(); + // EskfParams eskf_params{}; + Eigen::Matrix12d Q; Q.setZero(); Q.diagonal() << sq(diag_Q_std[0]), sq(diag_Q_std[1]), sq(diag_Q_std[2]), sq(diag_Q_std[3]), sq(diag_Q_std[4]), sq(diag_Q_std[5]), sq(diag_Q_std[6]), sq(diag_Q_std[7]), sq(diag_Q_std[8]), sq(diag_Q_std[9]), sq(diag_Q_std[10]), sq(diag_Q_std[11]); - eskf_params_.Q = Q; - - eskf_ = std::make_unique(eskf_params_); std::vector diag_p_init = this->declare_parameter>("diag_p_init"); Eigen::Matrix18d P = createDiagonalMatrix<18>(diag_p_init); + EskfParams eskf_params{ + .Q = Q, + .P = P + }; - error_state_.covariance = P; + eskf_ = std::make_unique(eskf_params); } void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { @@ -97,57 +100,61 @@ void ESKFNode::imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg) { msg->linear_acceleration.y, msg->linear_acceleration.z); - imu_meas_.accel = R_imu_eskf_ * raw_accel; + ImuMeasurement imu_measurement{}; + imu_measurement.accel = R_imu_eskf_ * raw_accel; Eigen::Vector3d raw_gyro(msg->angular_velocity.x, msg->angular_velocity.y, msg->angular_velocity.z); - imu_meas_.gyro = R_imu_eskf_ * raw_gyro; + imu_measurement.gyro = R_imu_eskf_ * raw_gyro; - std::tie(nom_state_, error_state_) = eskf_->imu_update(imu_meas_, dt); + eskf_->imu_update(imu_measurement, dt); + publish_odom(); } void ESKFNode::dvl_callback( const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { - dvl_meas_.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, + DvlMeasurement dvl_measurement{}; + dvl_measurement.vel << msg->twist.twist.linear.x, msg->twist.twist.linear.y, msg->twist.twist.linear.z; - dvl_meas_.cov << msg->twist.covariance[0], msg->twist.covariance[1], + dvl_measurement.cov << msg->twist.covariance[0], msg->twist.covariance[1], msg->twist.covariance[2], msg->twist.covariance[6], msg->twist.covariance[7], msg->twist.covariance[8], msg->twist.covariance[12], msg->twist.covariance[13], msg->twist.covariance[14]; - std::tie(nom_state_, error_state_) = eskf_->dvl_update(dvl_meas_); + eskf_->dvl_update(dvl_measurement); std_msgs::msg::Float64 nis_msg; - nis_msg.data = eskf_->NIS_; + nis_msg.data = eskf_->get_nis(); nis_pub_->publish(nis_msg); + + publish_odom(); } void ESKFNode::publish_odom() { nav_msgs::msg::Odometry odom_msg; + StateQuat nom_state = eskf_->get_nominal_state(); - odom_msg.pose.pose.position.x = nom_state_.pos.x(); - odom_msg.pose.pose.position.y = nom_state_.pos.y(); - odom_msg.pose.pose.position.z = nom_state_.pos.z(); + odom_msg.pose.pose.position.x = nom_state.pos.x(); + odom_msg.pose.pose.position.y = nom_state.pos.y(); + odom_msg.pose.pose.position.z = nom_state.pos.z(); - odom_msg.pose.pose.orientation.w = nom_state_.quat.w(); - odom_msg.pose.pose.orientation.x = nom_state_.quat.x(); - odom_msg.pose.pose.orientation.y = nom_state_.quat.y(); - odom_msg.pose.pose.orientation.z = nom_state_.quat.z(); + odom_msg.pose.pose.orientation.w = nom_state.quat.w(); + odom_msg.pose.pose.orientation.x = nom_state.quat.x(); + odom_msg.pose.pose.orientation.y = nom_state.quat.y(); + odom_msg.pose.pose.orientation.z = nom_state.quat.z(); - odom_msg.twist.twist.linear.x = nom_state_.vel.x(); - odom_msg.twist.twist.linear.y = nom_state_.vel.y(); - odom_msg.twist.twist.linear.z = nom_state_.vel.z(); + odom_msg.twist.twist.linear.x = nom_state.vel.x(); + odom_msg.twist.twist.linear.y = nom_state.vel.y(); + odom_msg.twist.twist.linear.z = nom_state.vel.z(); - // Add bias values to the angular velocity field of twist - odom_msg.twist.twist.angular.x = nom_state_.accel_bias.x(); - odom_msg.twist.twist.angular.y = nom_state_.accel_bias.y(); - odom_msg.twist.twist.angular.z = nom_state_.accel_bias.z(); + odom_msg.twist.twist.angular.x = nom_state.accel_bias.x(); + odom_msg.twist.twist.angular.y = nom_state.accel_bias.y(); + odom_msg.twist.twist.angular.z = nom_state.accel_bias.z(); - // If you also want to include gyro bias, you could add it to the covariance - // matrix or publish a separate topic for biases + // TODO: Covariance out odom_msg.header.stamp = this->now(); odom_pub_->publish(odom_msg); From 3a1b03c82c6b70e0c416185c4ef7b4d059651452 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Anders=20H=C3=B8gden?= Date: Sun, 19 Oct 2025 21:01:17 +0200 Subject: [PATCH 30/30] refactor(eskf): vortex-utils enjoyer --- navigation/eskf/CMakeLists.txt | 3 +- navigation/eskf/include/eskf/eskf.hpp | 9 +--- navigation/eskf/include/eskf/eskf_utils.hpp | 38 --------------- navigation/eskf/include/eskf/typedefs.hpp | 3 +- navigation/eskf/package.xml | 1 + navigation/eskf/src/eskf.cpp | 38 ++++++++------- navigation/eskf/src/eskf_ros.cpp | 32 ++++++------- navigation/eskf/src/eskf_utils.cpp | 52 --------------------- 8 files changed, 43 insertions(+), 133 deletions(-) delete mode 100644 navigation/eskf/include/eskf/eskf_utils.hpp delete mode 100644 navigation/eskf/src/eskf_utils.cpp diff --git a/navigation/eskf/CMakeLists.txt b/navigation/eskf/CMakeLists.txt index 8fc8a02cc..e9f464906 100644 --- a/navigation/eskf/CMakeLists.txt +++ b/navigation/eskf/CMakeLists.txt @@ -17,6 +17,7 @@ find_package(geometry_msgs REQUIRED) find_package(Eigen3 REQUIRED) find_package(tf2 REQUIRED) find_package(vortex_msgs REQUIRED) +find_package(vortex_utils REQUIRED) find_package(spdlog REQUIRED) find_package(fmt REQUIRED) @@ -33,7 +34,6 @@ set(LIB_NAME "${PROJECT_NAME}_component") add_library(${LIB_NAME} SHARED src/eskf.cpp src/eskf_ros.cpp - src/eskf_utils.cpp ) ament_target_dependencies(${LIB_NAME} PUBLIC @@ -44,6 +44,7 @@ ament_target_dependencies(${LIB_NAME} PUBLIC Eigen3 tf2 vortex_msgs + vortex_utils spdlog fmt ) diff --git a/navigation/eskf/include/eskf/eskf.hpp b/navigation/eskf/include/eskf/eskf.hpp index 98e12f229..6219335c7 100644 --- a/navigation/eskf/include/eskf/eskf.hpp +++ b/navigation/eskf/include/eskf/eskf.hpp @@ -19,14 +19,9 @@ class ESKF { // @param dvl_meas: DVL measurement void dvl_update(const DvlMeasurement& dvl_meas); - inline StateQuat get_nominal_state() const { - return current_nom_state_; - } - - inline double get_nis() const { - return nis_; - } + inline StateQuat get_nominal_state() const { return current_nom_state_; } + inline double get_nis() const { return nis_; } private: // @brief Predict the nominal state diff --git a/navigation/eskf/include/eskf/eskf_utils.hpp b/navigation/eskf/include/eskf/eskf_utils.hpp deleted file mode 100644 index 0fe06ee7a..000000000 --- a/navigation/eskf/include/eskf/eskf_utils.hpp +++ /dev/null @@ -1,38 +0,0 @@ -#ifndef ESKF_UTILS_HPP -#define ESKF_UTILS_HPP - -#include -#include "eigen3/Eigen/Dense" -#include "eskf/typedefs.hpp" - -// @brief Compute the skew-symmetric matrix of a vector -// @param v: Input vector -// @return Skew-symmetric matrix -Eigen::Matrix3d skew(const Eigen::Vector3d& v); - -// @brief Square a value -// @param value: Input value -// @return Squared value -double sq(double value); - -// @brief Normalize an angle to the range [-pi, pi] -// @param angle: Input angle in radians -// @return Normalized angle in radians -double ssa(double angle); - -// @brief Calculate the transformation matrix using a quaternion -// @param quat: Input quaternion -// @return Transformation matrix -Eigen::Matrix4x3d calculate_T_q(const Eigen::Quaterniond& quat); - -// @brief Convert a rotation vector to a quaternion -// @param vector: Input rotation vector -// @return Corresponding quaternion -Eigen::Quaterniond vector3d_to_quaternion(const Eigen::Vector3d& vector); - -// @brief Convert Euler angles to a quaternion -// @param euler: Input Euler angles (roll, pitch, yaw) in radians -// @return Corresponding quaternion -Eigen::Quaterniond euler_to_quaternion(const Eigen::Vector3d& euler); - -#endif // ESKF_UTILS_HPP diff --git a/navigation/eskf/include/eskf/typedefs.hpp b/navigation/eskf/include/eskf/typedefs.hpp index 3b4b990bd..9360a5903 100644 --- a/navigation/eskf/include/eskf/typedefs.hpp +++ b/navigation/eskf/include/eskf/typedefs.hpp @@ -5,9 +5,9 @@ #ifndef ESKF_TYPEDEFS_H #define ESKF_TYPEDEFS_H -#include #include #include +#include namespace Eigen { typedef Eigen::Matrix Vector19d; @@ -28,6 +28,7 @@ typedef Eigen::Matrix Matrix6d; typedef Eigen::Matrix Matrix9d; typedef Eigen::Matrix Matrix15d; typedef Eigen::Matrix Vector15d; +typedef Eigen::Matrix Vector12d; } // namespace Eigen template diff --git a/navigation/eskf/package.xml b/navigation/eskf/package.xml index 015e6f71c..588855609 100644 --- a/navigation/eskf/package.xml +++ b/navigation/eskf/package.xml @@ -15,6 +15,7 @@ eigen tf2 vortex_msgs + vortex_utils ament_cmake diff --git a/navigation/eskf/src/eskf.cpp b/navigation/eskf/src/eskf.cpp index c9d0824e3..a478be43f 100644 --- a/navigation/eskf/src/eskf.cpp +++ b/navigation/eskf/src/eskf.cpp @@ -1,13 +1,12 @@ #include "eskf/eskf.hpp" -#include #include #include #include -#include "eskf/eskf_utils.hpp" +#include #include "eskf/typedefs.hpp" -#include "iostream" -double compute_nis(const Eigen::Vector3d& innovation, const Eigen::Matrix3d& S) { +double compute_nis(const Eigen::Vector3d& innovation, + const Eigen::Matrix3d& S) { Eigen::Matrix3d S_inv = S.inverse(); return innovation.transpose() * S_inv * innovation; } @@ -59,7 +58,8 @@ Eigen::Matrix3x19d ESKF::calculate_hx() { dhdq.col(0) = 2 * (qw * v_n + q_vec.cross(v_n)); dhdq.block<3, 3>(0, 1) = 2 * (q_vec.dot(v_n) * I3 + q_vec * v_n.transpose() - - v_n * q_vec.transpose() - qw * skew(v_n)); + v_n * q_vec.transpose() - + qw * vortex::utils::math::get_skew_symmetric_matrix(v_n)); // Assign quaternion derivative (3x4 block at columns 6:9) Hx.block<3, 4>(0, 6) = dhdq; @@ -70,7 +70,9 @@ Eigen::Matrix3x19d ESKF::calculate_hx() { Eigen::Matrix3x18d ESKF::calculate_h_jacobian() { Eigen::Matrix19x18d x_delta = Eigen::Matrix19x18d::Zero(); x_delta.block<6, 6>(0, 0) = Eigen::Matrix6d::Identity(); - x_delta.block<4, 3>(6, 6) = calculate_T_q(current_nom_state_.quat); + x_delta.block<4, 3>(6, 6) = + vortex::utils::math::get_transformation_matrix_attitude_quat( + current_nom_state_.quat); x_delta.block<9, 9>(10, 9) = Eigen::Matrix9d::Identity(); Eigen::Matrix3x18d H = calculate_hx() * x_delta; @@ -96,11 +98,12 @@ void ESKF::nominal_state_discrete(const ImuMeasurement& imu_meas, Eigen::Vector3d gyro = (imu_meas.gyro - current_nom_state_.gyro_bias) * dt; current_nom_state_.pos = current_nom_state_.pos + - current_nom_state_.vel * dt + 0.5 * sq(dt) * acc; + current_nom_state_.vel * dt + 0.5 * dt * dt * acc; current_nom_state_.vel = current_nom_state_.vel + dt * acc; current_nom_state_.quat = - (current_nom_state_.quat * vector3d_to_quaternion(gyro)); + (current_nom_state_.quat * + vortex::utils::math::eigen_vector3d_to_quaternion(gyro)); current_nom_state_.quat.normalize(); current_nom_state_.gyro_bias = current_nom_state_.gyro_bias; @@ -116,8 +119,10 @@ void ESKF::error_state_prediction(const ImuMeasurement& imu_meas, Eigen::Matrix18d A_c = Eigen::Matrix18d::Zero(); A_c.block<3, 3>(0, 3) = Eigen::Matrix3d::Identity(); - A_c.block<3, 3>(3, 6) = -R * skew(acc); - A_c.block<3, 3>(6, 6) = -skew(gyro); + A_c.block<3, 3>(3, 6) = + -R * vortex::utils::math::get_skew_symmetric_matrix(acc); + A_c.block<3, 3>(6, 6) = + -vortex::utils::math::get_skew_symmetric_matrix(gyro); A_c.block<3, 3>(3, 9) = -R; A_c.block<3, 3>(9, 9) = -Eigen::Matrix3d::Identity(); A_c.block<3, 3>(12, 12) = -Eigen::Matrix3d::Identity(); @@ -159,9 +164,9 @@ void ESKF::measurement_update(const DvlMeasurement& dvl_meas) { void ESKF::injection_and_reset() { current_nom_state_.pos = current_nom_state_.pos + current_error_state_.pos; current_nom_state_.vel = current_nom_state_.vel + current_error_state_.vel; - current_nom_state_.quat = - current_nom_state_.quat * - vector3d_to_quaternion(current_error_state_.euler); + current_nom_state_.quat = current_nom_state_.quat * + vortex::utils::math::eigen_vector3d_to_quaternion( + current_error_state_.euler); current_nom_state_.quat.normalize(); current_nom_state_.gyro_bias = current_nom_state_.gyro_bias + current_error_state_.gyro_bias; @@ -177,15 +182,12 @@ void ESKF::injection_and_reset() { current_error_state_.set_from_vector(Eigen::Vector18d::Zero()); } -void ESKF::imu_update( - const ImuMeasurement& imu_meas, - const double dt) { +void ESKF::imu_update(const ImuMeasurement& imu_meas, const double dt) { nominal_state_discrete(imu_meas, dt); error_state_prediction(imu_meas, dt); } -void ESKF::dvl_update( - const DvlMeasurement& dvl_meas) { +void ESKF::dvl_update(const DvlMeasurement& dvl_meas) { measurement_update(dvl_meas); injection_and_reset(); } diff --git a/navigation/eskf/src/eskf_ros.cpp b/navigation/eskf/src/eskf_ros.cpp index f516d68df..02e1c44fc 100644 --- a/navigation/eskf/src/eskf_ros.cpp +++ b/navigation/eskf/src/eskf_ros.cpp @@ -1,7 +1,7 @@ #include "eskf/eskf_ros.hpp" #include #include -#include "eskf/eskf_utils.hpp" +#include #include "eskf/typedefs.hpp" auto start_message{R"( @@ -27,9 +27,7 @@ ESKFNode::ESKFNode(const rclcpp::NodeOptions& options) } void ESKFNode::set_subscribers_and_publisher() { - rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto qos_sensor_data = rclcpp::QoS( - rclcpp::QoSInitialization(qos_profile.history, 1), qos_profile); + auto qos_sensor_data = vortex::utils::qos_profiles::sensor_data_profile(1); this->declare_parameter("imu_topic"); std::string imu_topic = this->get_parameter("imu_topic").as_string(); @@ -49,7 +47,8 @@ void ESKFNode::set_subscribers_and_publisher() { odom_pub_ = this->create_publisher( odom_topic, qos_sensor_data); - nis_pub_ = create_publisher("dvl/nis", 10); + nis_pub_ = create_publisher( + "dvl/nis", vortex::utils::qos_profiles::reliable_profile()); } void ESKFNode::set_parameters() { @@ -64,22 +63,23 @@ void ESKFNode::set_parameters() { diag_Q_std = this->get_parameter("diag_Q_std").as_double_array(); - // EskfParams eskf_params{}; + if (diag_Q_std.size() != 12) { + throw std::runtime_error("diag_Q_std must have length 12"); + } - Eigen::Matrix12d Q; - Q.setZero(); - Q.diagonal() << sq(diag_Q_std[0]), sq(diag_Q_std[1]), sq(diag_Q_std[2]), - sq(diag_Q_std[3]), sq(diag_Q_std[4]), sq(diag_Q_std[5]), - sq(diag_Q_std[6]), sq(diag_Q_std[7]), sq(diag_Q_std[8]), - sq(diag_Q_std[9]), sq(diag_Q_std[10]), sq(diag_Q_std[11]); + Eigen::Matrix12d Q = Eigen::Map(diag_Q_std.data()) + .array() + .square() + .matrix() + .asDiagonal(); std::vector diag_p_init = this->declare_parameter>("diag_p_init"); + if (diag_p_init.size() != 18) { + throw std::runtime_error("diag_p_init must have length 18"); + } Eigen::Matrix18d P = createDiagonalMatrix<18>(diag_p_init); - EskfParams eskf_params{ - .Q = Q, - .P = P - }; + EskfParams eskf_params{.Q = Q, .P = P}; eskf_ = std::make_unique(eskf_params); } diff --git a/navigation/eskf/src/eskf_utils.cpp b/navigation/eskf/src/eskf_utils.cpp deleted file mode 100644 index e7dc4e5e3..000000000 --- a/navigation/eskf/src/eskf_utils.cpp +++ /dev/null @@ -1,52 +0,0 @@ - -#include "eskf/eskf_utils.hpp" -#include "eskf/typedefs.hpp" - -Eigen::Matrix3d skew(const Eigen::Vector3d& v) { - Eigen::Matrix3d S; - S << 0, -v.z(), v.y(), v.z(), 0, -v.x(), -v.y(), v.x(), 0; - return S; -} - -double sq(const double value) { - return value * value; -} -double ssa(const double angle) { - double result = fmod(angle + M_PI, 2 * M_PI); - double angle_ssa = result < 0 ? result + M_PI : result - M_PI; - return angle_ssa; -} - -Eigen::Matrix4x3d calculate_T_q(const Eigen::Quaterniond& quat) { - Eigen::Matrix4x3d T_q = Eigen::Matrix4x3d::Zero(); - double qw = quat.w(); - double qx = quat.x(); - double qy = quat.y(); - double qz = quat.z(); - - T_q << -qx, -qy, -qz, qw, -qz, qy, qz, qw, -qx, -qy, qx, qw; - - T_q *= 0.5; - return T_q; -} - -Eigen::Quaterniond vector3d_to_quaternion(const Eigen::Vector3d& vector) { - double angle = vector.norm(); - if (angle < 1e-8) { - return Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0); - } else { - Eigen::Vector3d axis = vector / angle; - Eigen::Quaterniond quat = - Eigen::Quaterniond(Eigen::AngleAxisd(angle, axis)); - return quat.normalized(); - } -} - -Eigen::Quaterniond euler_to_quaternion(const Eigen::Vector3d& euler) { - Eigen::Quaterniond q; - q = Eigen::AngleAxisd(euler.z(), Eigen::Vector3d::UnitZ()) * - Eigen::AngleAxisd(euler.y(), Eigen::Vector3d::UnitY()) * - Eigen::AngleAxisd(euler.x(), Eigen::Vector3d::UnitX()); - q.normalize(); - return q; -}