diff --git a/applications/tests/test_autoware/Cargo.toml b/applications/tests/test_autoware/Cargo.toml new file mode 100644 index 000000000..bb1aab646 --- /dev/null +++ b/applications/tests/test_autoware/Cargo.toml @@ -0,0 +1,17 @@ +[package] +name = "test_autoware" +version = "0.1.0" +edition = "2021" + +[lib] +path = "src/lib.rs" +crate-type = ["rlib"] + +[dependencies] +log = "0.4" +libm = "0.2" +csv-core = "0.1" +awkernel_async_lib = { path = "../../../awkernel_async_lib", default-features = false } +awkernel_lib = { path = "../../../awkernel_lib", default-features = false } +imu_driver = { path = "./imu_driver", default-features = false } +vehicle_velocity_converter = { path = "./vehicle_velocity_converter", default-features = false } diff --git a/applications/tests/test_autoware/imu_driver/Cargo.toml b/applications/tests/test_autoware/imu_driver/Cargo.toml new file mode 100644 index 000000000..da816a55f --- /dev/null +++ b/applications/tests/test_autoware/imu_driver/Cargo.toml @@ -0,0 +1,6 @@ +[package] +name = "imu_driver" +version = "0.1.0" +edition = "2021" + +[dependencies] diff --git a/applications/tests/test_autoware/imu_driver/src/lib.rs b/applications/tests/test_autoware/imu_driver/src/lib.rs new file mode 100644 index 000000000..a7abc330f --- /dev/null +++ b/applications/tests/test_autoware/imu_driver/src/lib.rs @@ -0,0 +1,356 @@ +#![no_std] +extern crate alloc; + +use alloc::{format, string::String, vec, vec::Vec}; +use core::f64::consts::PI; + +#[derive(Clone, Debug)] +pub struct ImuMsg { + pub header: Header, + pub orientation: Quaternion, + pub angular_velocity: Vector3, + pub linear_acceleration: Vector3, +} + +#[derive(Clone, Debug)] +pub struct ImuCsvRow { + pub timestamp: u64, + pub orientation: Quaternion, + pub angular_velocity: Vector3, + pub linear_acceleration: Vector3, +} + +#[derive(Clone, Debug)] +pub struct Header { + pub frame_id: &'static str, + pub timestamp: u64, +} + +#[derive(Debug, Clone)] +pub struct Quaternion { + pub x: f64, + pub y: f64, + pub z: f64, + pub w: f64, +} + +#[derive(Clone, Debug)] +pub struct Vector3 { + pub x: f64, + pub y: f64, + pub z: f64, +} + +impl Vector3 { + pub fn new(x: f64, y: f64, z: f64) -> Self { + Self { x, y, z } + } +} + +impl Default for ImuMsg { + fn default() -> Self { + Self { + header: Header { + frame_id: "imu", + timestamp: 0, + }, + orientation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, + angular_velocity: Vector3::new(0.0, 0.0, 0.0), + linear_acceleration: Vector3::new(0.0, 0.0, 0.0), + } + } +} + +pub fn build_imu_msg_from_csv_row( + row: &ImuCsvRow, + frame_id: &'static str, + timestamp: u64, +) -> ImuMsg { + ImuMsg { + header: Header { + frame_id, + timestamp, + }, + orientation: row.orientation.clone(), + angular_velocity: row.angular_velocity.clone(), + linear_acceleration: row.linear_acceleration.clone(), + } +} + +pub struct TamagawaImuParser { + frame_id: &'static str, + dummy_counter: u16, +} + +impl TamagawaImuParser { + pub fn new(frame_id: &'static str) -> Self { + Self { + frame_id, + dummy_counter: 0, + } + } + + pub fn parse_binary_data(&self, data: &[u8], timestamp: u64) -> Option { + if data.len() != 58 || data[0..9] != *b"$TSC,BIN," { + return None; + } + + let mut imu_msg = ImuMsg::default(); + imu_msg.header.frame_id = self.frame_id; + imu_msg.header.timestamp = timestamp; + + let _counter = ((data[11] as u16) << 8) | (data[12] as u16); + let raw_data = self.parse_signed_16bit(&data[15..17]); + imu_msg.angular_velocity.x = self.convert_angular_velocity(raw_data); + let raw_data = self.parse_signed_16bit(&data[17..19]); + imu_msg.angular_velocity.y = self.convert_angular_velocity(raw_data); + let raw_data = self.parse_signed_16bit(&data[19..21]); + imu_msg.angular_velocity.z = self.convert_angular_velocity(raw_data); + let raw_data = self.parse_signed_16bit(&data[21..23]); + imu_msg.linear_acceleration.x = self.convert_acceleration(raw_data); + let raw_data = self.parse_signed_16bit(&data[23..25]); + imu_msg.linear_acceleration.y = self.convert_acceleration(raw_data); + let raw_data = self.parse_signed_16bit(&data[25..27]); + imu_msg.linear_acceleration.z = self.convert_acceleration(raw_data); + + Some(imu_msg) + } + + pub fn generate_dummy_binary_data( + &mut self, + _timestamp: u64, + angular_velocity: Vector3, + linear_acceleration: Vector3, + ) -> Vec { + let mut data = vec![0u8; 58]; + + data[0..5].copy_from_slice(b"$TSC,"); + data[5] = b'B'; + data[6] = b'I'; + data[7] = b'N'; + data[8] = b','; + data[11] = (self.dummy_counter >> 8) as u8; + data[12] = (self.dummy_counter & 0xFF) as u8; + self.dummy_counter = self.dummy_counter.wrapping_add(1); + + let angular_vel_x_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.x); + let angular_vel_y_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.y); + let angular_vel_z_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.z); + let accel_x_lsb = self.convert_acceleration_to_lsb(linear_acceleration.x); + let accel_y_lsb = self.convert_acceleration_to_lsb(linear_acceleration.y); + let accel_z_lsb = self.convert_acceleration_to_lsb(linear_acceleration.z); + + data[15] = (angular_vel_x_lsb >> 8) as u8; + data[16] = (angular_vel_x_lsb & 0xFF) as u8; + data[17] = (angular_vel_y_lsb >> 8) as u8; + data[18] = (angular_vel_y_lsb & 0xFF) as u8; + data[19] = (angular_vel_z_lsb >> 8) as u8; + data[20] = (angular_vel_z_lsb & 0xFF) as u8; + data[21] = (accel_x_lsb >> 8) as u8; + data[22] = (accel_x_lsb & 0xFF) as u8; + data[23] = (accel_y_lsb >> 8) as u8; + data[24] = (accel_y_lsb & 0xFF) as u8; + data[25] = (accel_z_lsb >> 8) as u8; + data[26] = (accel_z_lsb & 0xFF) as u8; + + data + } + + pub fn generate_static_dummy_data(&mut self, timestamp: u64) -> Vec { + let angular_velocity = Vector3::new(0.1, 0.2, 0.01); + let linear_acceleration = Vector3::new(0.0, 0.0, 9.80665); + + self.generate_dummy_binary_data(timestamp, angular_velocity, linear_acceleration) + } + + fn convert_angular_velocity_to_lsb(&self, rad_per_sec: f64) -> i16 { + let deg_per_sec = rad_per_sec * 180.0 / PI; + let lsb = deg_per_sec / (200.0 / (1 << 15) as f64); + lsb as i16 + } + + fn convert_acceleration_to_lsb(&self, m_per_sec_squared: f64) -> i16 { + let lsb = m_per_sec_squared / (100.0 / (1 << 15) as f64); + lsb as i16 + } + + fn parse_signed_16bit(&self, data: &[u8]) -> i16 { + if data.len() != 2 { + return 0; + } + let high_byte = (data[0] as i32) << 8; + let low_byte = data[1] as i32; + let result = (high_byte & 0xFFFFFF00u32 as i32) | (low_byte & 0x000000FF); + result as i16 + } + + fn convert_angular_velocity(&self, raw_data: i16) -> f64 { + let lsb_to_deg_per_sec = 200.0 / (1 << 15) as f64; + let deg_to_rad = PI / 180.0; + (raw_data as f64) * lsb_to_deg_per_sec * deg_to_rad + } + + fn convert_acceleration(&self, raw_data: i16) -> f64 { + let lsb_to_m_per_sec_squared = 100.0 / (1 << 15) as f64; + (raw_data as f64) * lsb_to_m_per_sec_squared + } + + pub fn generate_version_request() -> &'static [u8] { + b"$TSC,VER*29\r\n" + } + + pub fn generate_offset_cancel_request(offset_value: i32) -> String { + format!("$TSC,OFC,{}\r\n", offset_value) + } + + pub fn generate_heading_reset_request() -> &'static [u8] { + b"$TSC,HRST*29\r\n" + } + + pub fn generate_binary_request(rate_hz: u32) -> String { + format!("$TSC,BIN,{}\r\n", rate_hz) + } +} + +#[cfg(test)] +mod tests { + use super::*; + use core::f64::consts::PI; + + fn assert_approx_eq(actual: f64, expected: f64, eps: f64) { + assert!( + (actual - expected).abs() <= eps, + "left: {actual}, right: {expected}" + ); + } + + fn expected_ang_vel(raw: i16) -> f64 { + let lsb_to_deg_per_sec = 200.0 / (1 << 15) as f64; + let deg_to_rad = PI / 180.0; + (raw as f64) * lsb_to_deg_per_sec * deg_to_rad + } + + fn expected_acc(raw: i16) -> f64 { + let lsb_to_m_per_sec_squared = 100.0 / (1 << 15) as f64; + (raw as f64) * lsb_to_m_per_sec_squared + } + + fn put_i16_be(buf: &mut [u8], value: i16) { + let raw = value as u16; + buf[0] = (raw >> 8) as u8; + buf[1] = (raw & 0xFF) as u8; + } + + #[test] + fn parse_rejects_invalid_length() { + let parser = TamagawaImuParser::new("imu_link"); + let data = [0u8; 57]; + + assert!(parser.parse_binary_data(&data, 1).is_none()); + } + + #[test] + fn parse_rejects_non_bin_header() { + let parser = TamagawaImuParser::new("imu_link"); + let mut data = [0u8; 58]; + data[0..5].copy_from_slice(b"$TSC,"); + data[5..9].copy_from_slice(b"XIN,"); + + assert!(parser.parse_binary_data(&data, 1).is_none()); + } + + #[test] + fn parse_rejects_invalid_tsc_prefix() { + let parser = TamagawaImuParser::new("imu_link"); + let mut data = [0u8; 58]; + data[0..9].copy_from_slice(b"@TSC,BIN,"); + + assert!(parser.parse_binary_data(&data, 1).is_none()); + } + + #[test] + fn parse_extracts_fields_and_converts_units() { + let parser = TamagawaImuParser::new("imu_link"); + let timestamp = 123456789u64; + + let mut data = [0u8; 58]; + data[0..5].copy_from_slice(b"$TSC,"); + data[5..9].copy_from_slice(b"BIN,"); + + let gx: i16 = 1; + let gy: i16 = -2; + let gz: i16 = 1234; + let ax: i16 = -300; + let ay: i16 = 0; + let az: i16 = 32767; + + put_i16_be(&mut data[15..17], gx); + put_i16_be(&mut data[17..19], gy); + put_i16_be(&mut data[19..21], gz); + put_i16_be(&mut data[21..23], ax); + put_i16_be(&mut data[23..25], ay); + put_i16_be(&mut data[25..27], az); + + let imu = parser + .parse_binary_data(&data, timestamp) + .expect("should parse"); + + assert_eq!(imu.header.frame_id, "imu_link"); + assert_eq!(imu.header.timestamp, timestamp); + + let eps = 1e-12; + assert_approx_eq(imu.angular_velocity.x, expected_ang_vel(gx), eps); + assert_approx_eq(imu.angular_velocity.y, expected_ang_vel(gy), eps); + assert_approx_eq(imu.angular_velocity.z, expected_ang_vel(gz), eps); + + assert_approx_eq(imu.linear_acceleration.x, expected_acc(ax), eps); + assert_approx_eq(imu.linear_acceleration.y, expected_acc(ay), eps); + assert_approx_eq(imu.linear_acceleration.z, expected_acc(az), eps); + } + + #[test] + fn generate_dummy_data_roundtrip_is_close() { + let mut parser = TamagawaImuParser::new("imu_link"); + let timestamp = 42u64; + + let input_angular_velocity = Vector3::new(0.5, -0.3, 1.2); + let input_linear_acceleration = Vector3::new(8.5, 2.1, 10.2); + + let data = parser.generate_dummy_binary_data( + timestamp, + input_angular_velocity.clone(), + input_linear_acceleration.clone(), + ); + let imu = parser + .parse_binary_data(&data, timestamp) + .expect("should parse"); + + let ang_eps = (200.0 / (1 << 15) as f64) * (PI / 180.0); + let acc_eps = 100.0 / (1 << 15) as f64; + + assert_approx_eq(imu.angular_velocity.x, input_angular_velocity.x, ang_eps); + assert_approx_eq(imu.angular_velocity.y, input_angular_velocity.y, ang_eps); + assert_approx_eq(imu.angular_velocity.z, input_angular_velocity.z, ang_eps); + + assert_approx_eq( + imu.linear_acceleration.x, + input_linear_acceleration.x, + acc_eps, + ); + assert_approx_eq( + imu.linear_acceleration.y, + input_linear_acceleration.y, + acc_eps, + ); + assert_approx_eq( + imu.linear_acceleration.z, + input_linear_acceleration.z, + acc_eps, + ); + } +} diff --git a/applications/tests/test_autoware/src/lib.rs b/applications/tests/test_autoware/src/lib.rs new file mode 100644 index 000000000..438b2d083 --- /dev/null +++ b/applications/tests/test_autoware/src/lib.rs @@ -0,0 +1,4 @@ +#![no_std] +extern crate alloc; + +pub async fn run() {} diff --git a/applications/tests/test_autoware/vehicle_velocity_converter/Cargo.toml b/applications/tests/test_autoware/vehicle_velocity_converter/Cargo.toml new file mode 100644 index 000000000..24f988e6e --- /dev/null +++ b/applications/tests/test_autoware/vehicle_velocity_converter/Cargo.toml @@ -0,0 +1,6 @@ +[package] +name = "vehicle_velocity_converter" +version = "0.1.0" +edition = "2021" + +[dependencies] diff --git a/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs new file mode 100644 index 000000000..f7a96dc43 --- /dev/null +++ b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs @@ -0,0 +1,321 @@ +// Copyright 2021 TierIV +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#![no_std] + +#[derive(Debug, Clone)] +pub struct Header { + pub frame_id: &'static str, + pub timestamp: u64, +} + +#[derive(Debug, Clone)] +pub struct Vector3 { + pub x: f64, + pub y: f64, + pub z: f64, +} + +#[derive(Debug, Clone)] +pub struct VelocityReport { + pub header: Header, + pub longitudinal_velocity: f64, + pub lateral_velocity: f64, + pub heading_rate: f64, +} + +#[derive(Debug, Clone)] +pub struct VelocityCsvRow { + pub timestamp: u64, + pub longitudinal_velocity: f64, + pub lateral_velocity: f64, + pub heading_rate: f64, +} + +pub fn build_velocity_report_from_csv_row( + row: &VelocityCsvRow, + frame_id: &'static str, + timestamp: u64, +) -> VelocityReport { + VelocityReport { + header: Header { + frame_id, + timestamp, + }, + longitudinal_velocity: row.longitudinal_velocity, + lateral_velocity: row.lateral_velocity, + heading_rate: row.heading_rate, + } +} + +#[derive(Debug, Clone)] +pub struct TwistWithCovarianceStamped { + pub header: Header, + pub twist: TwistWithCovariance, +} + +#[derive(Debug, Clone)] +pub struct TwistWithCovariance { + pub twist: Twist, + pub covariance: [f64; 36], +} + +#[derive(Debug, Clone)] +pub struct Twist { + pub linear: Vector3, + pub angular: Vector3, +} + +#[repr(C)] +pub struct Odometry { + pub velocity: f64, +} + +pub struct VehicleVelocityConverter { + frame_id: &'static str, + stddev_vx: f64, + stddev_wz: f64, + speed_scale_factor: f64, +} + +impl VehicleVelocityConverter { + pub fn new( + frame_id: &'static str, + stddev_vx: f64, + stddev_wz: f64, + speed_scale_factor: f64, + ) -> Self { + Self { + frame_id, + stddev_vx, + stddev_wz, + speed_scale_factor, + } + } + + pub fn from_params_array( + velocity_stddev_xx: Option, + angular_velocity_stddev_zz: Option, + speed_scale_factor: Option, + frame_id: &'static str, + ) -> Self { + let stddev_vx = velocity_stddev_xx.unwrap_or(0.2); + let stddev_wz = angular_velocity_stddev_zz.unwrap_or(0.1); + let speed_scale_factor = speed_scale_factor.unwrap_or(1.0); + + Self::new(frame_id, stddev_vx, stddev_wz, speed_scale_factor) + } + + pub fn default() -> Self { + Self::new("base_link", 0.2, 0.1, 1.0) + } + + pub fn convert_velocity_report(&self, msg: &VelocityReport) -> TwistWithCovarianceStamped { + TwistWithCovarianceStamped { + header: msg.header.clone(), + twist: TwistWithCovariance { + twist: Twist { + linear: Vector3 { + x: msg.longitudinal_velocity * self.speed_scale_factor, + y: msg.lateral_velocity, + z: 0.0, + }, + angular: Vector3 { + x: 0.0, + y: 0.0, + z: msg.heading_rate, + }, + }, + covariance: self.create_covariance_matrix(), + }, + } + } + + fn create_covariance_matrix(&self) -> [f64; 36] { + let mut covariance = [0.0; 36]; + covariance[0 + 0 * 6] = self.stddev_vx * self.stddev_vx; + covariance[1 + 1 * 6] = 10000.0; + covariance[2 + 2 * 6] = 10000.0; + covariance[3 + 3 * 6] = 10000.0; + covariance[4 + 4 * 6] = 10000.0; + covariance[5 + 5 * 6] = self.stddev_wz * self.stddev_wz; + + covariance + } + + pub fn get_frame_id(&self) -> &'static str { + self.frame_id + } + + pub fn get_stddev_vx(&self) -> f64 { + self.stddev_vx + } + + pub fn get_stddev_wz(&self) -> f64 { + self.stddev_wz + } + + pub fn get_speed_scale_factor(&self) -> f64 { + self.speed_scale_factor + } +} + +pub mod reactor_helpers { + use super::*; + + pub fn create_empty_twist(timestamp: u64) -> TwistWithCovarianceStamped { + TwistWithCovarianceStamped { + header: Header { + frame_id: "base_link", + timestamp, + }, + twist: TwistWithCovariance { + twist: Twist { + linear: Vector3 { + x: 0.0, + y: 0.0, + z: 0.0, + }, + angular: Vector3 { + x: 0.0, + y: 0.0, + z: 0.0, + }, + }, + covariance: [0.0; 36], + }, + } + } +} + +#[cfg(test)] +mod tests { + use super::*; + + fn assert_approx_eq(actual: f64, expected: f64, eps: f64) { + assert!( + (actual - expected).abs() <= eps, + "left: {actual}, right: {expected}" + ); + } + + #[test] + fn node_instantiation() { + let converter = VehicleVelocityConverter::from_params_array( + Some(0.2), + Some(0.1), + Some(1.0), + "base_link", + ); + + assert_eq!(converter.get_frame_id(), "base_link"); + assert_eq!(converter.get_stddev_vx(), 0.2); + assert_eq!(converter.get_stddev_wz(), 0.1); + assert_eq!(converter.get_speed_scale_factor(), 1.0); + } + + #[test] + fn message_conversion() { + let converter = VehicleVelocityConverter::from_params_array( + Some(0.2), + Some(0.1), + Some(1.5), + "base_link", + ); + let velocity_report = VelocityReport { + header: Header { + frame_id: "base_link", + timestamp: 1234567890, + }, + longitudinal_velocity: 2.0, + lateral_velocity: 0.1, + heading_rate: 0.3, + }; + + let twist_msg = converter.convert_velocity_report(&velocity_report); + + assert_eq!(twist_msg.header.frame_id, velocity_report.header.frame_id); + assert_eq!( + twist_msg.twist.twist.linear.x, + velocity_report.longitudinal_velocity * 1.5 + ); + assert_eq!( + twist_msg.twist.twist.linear.y, + velocity_report.lateral_velocity + ); + assert_eq!( + twist_msg.twist.twist.angular.z, + velocity_report.heading_rate + ); + assert_approx_eq(twist_msg.twist.covariance[0], 0.2 * 0.2, 1e-12); + assert_eq!(twist_msg.twist.covariance[7], 10000.0); + assert_eq!(twist_msg.twist.covariance[14], 10000.0); + assert_eq!(twist_msg.twist.covariance[21], 10000.0); + assert_eq!(twist_msg.twist.covariance[28], 10000.0); + assert_approx_eq(twist_msg.twist.covariance[35], 0.1 * 0.1, 1e-12); + } + + #[test] + fn different_frame_id() { + let converter = VehicleVelocityConverter::from_params_array( + Some(0.2), + Some(0.1), + Some(1.0), + "base_link", + ); + + let velocity_report = VelocityReport { + header: Header { + frame_id: "different_frame", + timestamp: 1234567890, + }, + longitudinal_velocity: 2.0, + lateral_velocity: 0.1, + heading_rate: 0.3, + }; + + let twist_msg = converter.convert_velocity_report(&velocity_report); + + // As in the original C++ test, conversion still succeeds even with a different frame_id. + assert_eq!(twist_msg.header.frame_id, velocity_report.header.frame_id); + assert_eq!( + twist_msg.twist.twist.linear.x, + velocity_report.longitudinal_velocity + ); + assert_eq!( + twist_msg.twist.twist.linear.y, + velocity_report.lateral_velocity + ); + assert_eq!( + twist_msg.twist.twist.angular.z, + velocity_report.heading_rate + ); + } + + #[test] + fn from_params_array_with_defaults() { + let converter = VehicleVelocityConverter::from_params_array(None, None, None, "base_link"); + + assert_eq!(converter.get_stddev_vx(), 0.2); + assert_eq!(converter.get_stddev_wz(), 0.1); + assert_eq!(converter.get_speed_scale_factor(), 1.0); + } + + #[test] + fn reactor_helpers() { + let empty_twist = reactor_helpers::create_empty_twist(1234567890); + assert_eq!(empty_twist.header.frame_id, "base_link"); + assert_eq!(empty_twist.twist.twist.linear.x, 0.0); + } +} diff --git a/userland/Cargo.toml b/userland/Cargo.toml index 664ec35f3..222256a19 100644 --- a/userland/Cargo.toml +++ b/userland/Cargo.toml @@ -66,6 +66,10 @@ optional = true path = "../applications/tests/test_dag" optional = true +[dependencies.test_autoware] +path = "../applications/tests/test_autoware" +optional = true + [dependencies.test_dvfs] path = "../applications/tests/test_dvfs" optional = true @@ -93,4 +97,5 @@ test_gedf = ["dep:test_gedf"] test_measure_channel = ["dep:test_measure_channel"] test_measure_channel_heavy = ["dep:test_measure_channel_heavy"] test_dag = ["dep:test_dag"] +test_autoware = ["dep:test_autoware"] test_voluntary_preemption = ["dep:test_voluntary_preemption"] diff --git a/userland/src/lib.rs b/userland/src/lib.rs index 01a66fe18..7082e1eba 100644 --- a/userland/src/lib.rs +++ b/userland/src/lib.rs @@ -46,6 +46,9 @@ pub async fn main() -> Result<(), Cow<'static, str>> { #[cfg(feature = "test_dag")] test_dag::run().await; // test for DAG + #[cfg(feature = "test_autoware")] + test_autoware::run().await; // test for Autoware + #[cfg(feature = "test_dvfs")] test_dvfs::run().await; // test for DVFS