From d02c6cab5a31359695c3ccdf2daea235e89fac8e Mon Sep 17 00:00:00 2001 From: Shivangi Chandel Date: Fri, 24 Apr 2026 11:55:15 +0530 Subject: [PATCH] docs(sensor-models): update and review doc/3_sensor_models Sync chapter 3 docs with current sensor source code. Add GNSS and optional UKF extrinsic calibration coverage. Improve English grammar and wording across all 3_sensor_models docs. Refs #72 --- doc/3_sensor_models/3_1_obstacle.md | 241 ++--------- doc/3_sensor_models/3_2_lidar.md | 539 ++++--------------------- doc/3_sensor_models/3_3_sensors.md | 329 ++++----------- doc/3_sensor_models/3_sensor_models.md | 9 +- 4 files changed, 219 insertions(+), 899 deletions(-) diff --git a/doc/3_sensor_models/3_1_obstacle.md b/doc/3_sensor_models/3_1_obstacle.md index 99a02434..4f3fc26f 100644 --- a/doc/3_sensor_models/3_1_obstacle.md +++ b/doc/3_sensor_models/3_1_obstacle.md @@ -1,233 +1,74 @@ ## 3.1 Obstacle -In this section, Obstacle class and Landmark class are implemented. These class are used for locating the obstacles object in the world. The located obstacles can be observed by an sensor model. +This section explains the obstacle models used by the sensor simulations. The repository provides two modules: -### 3.1.1 Rectangle obstacle -The obstacle class is implemented as follow. [State class implemented in Chapter 2](/doc/2_vehicle_model/2_vehicle_model.md) is given to the constructor for computing the position and pose of the obstacle. And then, [XYArray class](/doc/2_vehicle_model/2_vehicle_model.md) is also imported in the class for representing the shape as rectangle. - -[obstacle.py](/src/components/obstacle/obstacle.py) -```python -""" -obstacle.py - -Author: Shisato Yano -""" - -import numpy as np -import sys -from pathlib import Path - -sys.path.append(str(Path(__file__).absolute().parent) + "/../array") -from xy_array import XYArray +- [obstacle.py](/src/components/obstacle/obstacle.py): Represents one obstacle (static or dynamic). +- [obstacle_list.py](/src/components/obstacle/obstacle_list.py): Manages multiple obstacles. +### 3.1.1 Rectangle Obstacle +The `Obstacle` class stores its own state and geometric shape. The constructor takes a [State class](/doc/2_vehicle_model/2_vehicle_model.md) instance and shape/motion parameters. +```python class Obstacle: - """ - Obstacle's data and logic class - """ - def __init__(self, state, accel_mps2=0.0, yaw_rate_rps=0.0, length_m=2.0, width_m=2.0): - """ - Constructor - state: Obstacle's state object - accel_mps2: acceleration input to move[m/s2] - yaw_rate_rps: yaw rate input to move[rad/s] - length_m: Obstacle's longitudinal size[m] - width_m: Obstacle's half of lateral size[m] - """ - self.state = state self.accel_mps2 = accel_mps2 self.yaw_rate_rps = yaw_rate_rps - - contour = np.array([[length_m, -length_m, -length_m, length_m, length_m], - [width_m, width_m, -width_m, -width_m, width_m]]) - self.array = XYArray(contour) + self.length_m = length_m + self.width_m = width_m ``` -The given arguments, accel_mps2 and yaw_rate_rps are used for making the obstacle moved as a dynamic obstacle. If these values are default 0.0, the obstacle is represented as a static obstacle. Additionally, length_m and width_m are used for setting the size of the obstacle. +Notes: -The member methods, update, draw and vertex_xy are implemented. The method, update is used to compute the state including position(x, y) and yaw angle of the obstacle. -```python - def update(self, time_s): - """ - Function to update obstacle's state - time_s: Time interval value[sec] - """ - - self.state.update(self.accel_mps2, self.yaw_rate_rps, time_s) -``` +- `accel_mps2` and `yaw_rate_rps` control obstacle motion. +- When both are `0.0`, the obstacle behaves as a static object. +- `width_m` is treated as half-width in the class contour definition. -The method, draw is used to visualize the obstacle in the world. The vertexes and lines of obstacle are transformed based on the state and visualized. -```python - def draw(self, axes, elems): - """ - Function to draw obstacle - axes: Axes object of figure - elems: List of plot objects - """ - - x_m = self.state.get_x_m() - y_m = self.state.get_y_m() - yaw_rad = self.state.get_yaw_rad() - - transformed_array = self.array.homogeneous_transformation(x_m, y_m, yaw_rad) - obstacle_plot, = axes.plot(transformed_array.get_x_data(), - transformed_array.get_y_data(), - lw=1.0, color='k', ls='-') - elems.append(obstacle_plot) -``` +The update function advances obstacle motion using the state model: -The method, vertex_xy is used to get the vertexes coordinates (x, y) of the obstacle and to generate a point cloud by the sensor models. ```python - def vertex_xy(self): - """ - Function to get obstacle's vertex point coordinates - """ - - x_m = self.state.get_x_m() - y_m = self.state.get_y_m() - yaw_rad = self.state.get_yaw_rad() - - transformed_array = self.array.homogeneous_transformation(x_m, y_m, yaw_rad) - - return transformed_array.get_x_data(), transformed_array.get_y_data() +def update(self, time_s): + self.state.update(self.accel_mps2, self.yaw_rate_rps, time_s) ``` -### 3.1.2 Obstacles list -ObstacleList class is implemented to execute update and draw the data of multiple obstacles sequencially. An object of this list is given to a visualizer object and a sensor model object. +The draw function transforms the rectangle contour from obstacle coordinates to global coordinates and plots it: -[obstacle_list.py](/src/components/obstacle/obstacle_list.py) ```python -""" -obstacle_list.py +def draw(self, axes, elems): + x_m = self.state.get_x_m() + y_m = self.state.get_y_m() + yaw_rad = self.state.get_yaw_rad() + + transformed_array = self.array.homogeneous_transformation(x_m, y_m, yaw_rad) + obstacle_plot, = axes.plot(transformed_array.get_x_data(), + transformed_array.get_y_data(), + lw=1.0, color='k', ls='-') + elems.append(obstacle_plot) +``` -Author: Shisato Yano -""" +The `vertex_xy()` method returns transformed corner coordinates for downstream modules such as LiDAR point-cloud generation. +### 3.1.2 Obstacles List +`ObstacleList` is a small container class for multiple obstacles: + +```python class ObstacleList: - """ - Obstacles list class - """ - def __init__(self): - """ - Constructor - """ - self.list = [] - + def add_obstacle(self, obstacle): - """ - Function to add obstacle object into list - obstacle: Obstacle class's object - """ - self.list.append(obstacle) - - def update(self, times_s): - """ - Function to update each obstacle's state in list - time_s: Time interval value[sec] - """ - - for obst in self.list: obst.update(times_s) - - def draw(self, axes, elems): - """ - Function to draw each obstacles in list - axes: Axes object of figure - elems: List of plot objects - """ - - for obst in self.list: obst.draw(axes, elems) - - def get_list(self): - """ - Function to get obstacle's list - """ - - return self.list ``` -This class has a list to store each obstacle objects as a member. Each obstacles can be stored by using a method, add_obstacle. The data of the obstacles can be updated and drawn sequencially by using update and draw methods. Finally, get_list method is implemented to get the list for a sensor model object. +It also provides batch `update()` and `draw()` calls, plus `get_list()` for other modules (for example, LiDAR). ### 3.1.3 Visualization -A sample program for visualizing some obstacles in the simulation world is implemented as follow. A static obstacle and two dynamic obstacles can be drawn by giving an acceleration input and a yaw rate input. +A sample script for obstacle visualization is provided: -[visualize_obstacle.py](/doc/3_sensor_models/visualize_obstacle.py) -```python -""" -visualize_obstacle.py - -Author: Shisato Yano -""" - -# import path setting -import numpy as np -import sys -from pathlib import Path - -abs_dir_path = str(Path(__file__).absolute().parent) -relative_path = "/../../src/components/" - -sys.path.append(abs_dir_path + relative_path + "visualization") -sys.path.append(abs_dir_path + relative_path + "state") -sys.path.append(abs_dir_path + relative_path + "vehicle") -sys.path.append(abs_dir_path + relative_path + "obstacle") - - -# import component modules -from global_xy_visualizer import GlobalXYVisualizer -from min_max import MinMax -from time_parameters import TimeParameters -from vehicle_specification import VehicleSpecification -from state import State -from four_wheels_vehicle import FourWheelsVehicle -from obstacle import Obstacle -from obstacle_list import ObstacleList - - -# flag to show plot figure -# when executed as unit test, this flag is set as false -show_plot = True - - -def main(): - """ - Main process function - """ - - # set simulation parameters - x_lim, y_lim = MinMax(-30, 30), MinMax(-30, 30) - vis = GlobalXYVisualizer(x_lim, y_lim, TimeParameters(span_sec=20)) - - # create obstacle instances - obst_list = ObstacleList() - obst1 = Obstacle(State(x_m=-5.0, y_m=15.0, speed_mps=1.0), yaw_rate_rps=np.deg2rad(10), width_m=1.0) - obst_list.add_obstacle(obst1) - obst2 = Obstacle(State(x_m=-15.0, y_m=-15.0), length_m=10.0, width_m=5.0) - obst_list.add_obstacle(obst2) - obst3 = Obstacle(State(x_m=20.0), yaw_rate_rps=np.deg2rad(15)) - obst_list.add_obstacle(obst3) - vis.add_object(obst_list) - - # create vehicle instance - spec = VehicleSpecification(area_size=30.0) # spec instance - vehicle = FourWheelsVehicle(State(color=spec.color), spec) # set state, spec as arguments - vis.add_object(vehicle) - - # plot figure is not shown when executed as unit test - if not show_plot: vis.not_show_plot() - - # show plot figure - vis.draw() - - -# execute main process -if __name__ == "__main__": - main() -``` +- [visualize_obstacle.py](/doc/3_sensor_models/visualize_obstacle.py) + +This script creates one static obstacle and two dynamic obstacles, then draws them in the simulation world together with a vehicle model. + +The output example is: -The following simulation can be visualized by executing the above program. -![](/doc/3_sensor_models/visualize_obstacle.gif) \ No newline at end of file +![](/doc/3_sensor_models/visualize_obstacle.gif) diff --git a/doc/3_sensor_models/3_2_lidar.md b/doc/3_sensor_models/3_2_lidar.md index c74843ad..fea67feb 100644 --- a/doc/3_sensor_models/3_2_lidar.md +++ b/doc/3_sensor_models/3_2_lidar.md @@ -1,197 +1,51 @@ -## 3.2 LiDAR model -In this section, a simple 2D LiDAR model class are implemented for generating a 2D point cloud data. The obstacles in the simulation world can be observed with this LiDAR model. +## 3.2 LiDAR Model +This section explains the 2D LiDAR implementation used in the simulation. The LiDAR stack is composed of: -### 3.2.1 Sensor parameters -A parameters class, SensorParameters is implemented here. This class has the following parameters for a sensor installation and observation. +- [sensor_parameters.py](/src/components/sensors/sensor_parameters.py) +- [scan_point.py](/src/components/sensors/lidar/scan_point.py) +- [omni_directional_lidar.py](/src/components/sensors/lidar/omni_directional_lidar.py) +- [ukf_ext_params_calibrator.py](/src/components/sensors/lidar/ukf_ext_params_calibrator.py) -* Longitudinal installation position on a vehicle coordinate system[m] -* Lateral installation position on a vehicle coordinate system[m] -* Yaw angle of installation pose on a vehicle coordinate system[deg] -* Minimum sensing range[m] -* Maximum sensing range[m] -* Resolution of sensing angle[deg] -* Scale of an angle standard deviation -* Rate of a distance standard deviation +### 3.2.1 Sensor Parameters +`SensorParameters` stores installation parameters and LiDAR measurement parameters. -SensorParameters class is implemented as follow. [XYArray class](/doc/2_vehicle_model/2_vehicle_model.md) is imported in the class for representing a x-y vector of the position of the sensor. The above parameters can be given to the constructor as arguments. - -[sensor_parameters.py](/src/components/sensors/sensor_parameters.py) ```python -""" -sensor_parameters.py - -Author: Shisato Yano -""" - -import numpy as np -import sys -from pathlib import Path - -sys.path.append(str(Path(__file__).absolute().parent) + "/../array") -from xy_array import XYArray - - class SensorParameters: - """ - Parameters class for sensor - """ - def __init__(self, lon_m=0.0, lat_m=0.0, yaw_deg=0.0, min_m=0.5, max_m=40, reso_deg=2.0, - angle_std_scale=0.01, dist_std_rate=0.005): - """ - Constructor - lon_m: longitudinal installation position on vehicle coordinate system[m] - lat_m: lateral installation position on vehicle coordinate system[m] - yaw_deg: yaw angle of installation position on vehicle coordinate system[deg] - min_m: minimum sensing range[m] - max_m: maximum sensing range[m] - reso_deg: resolution of sensing angle[deg] - angle_std_scale: scale of angle's standard deviation - dist_std_rate: rate of distance's standard deviation - """ - - self.INST_LON_M = lon_m - self.INST_LAT_M = lat_m - self.INST_YAW_RAD = np.deg2rad(yaw_deg) - - self.MIN_RANGE_M = min_m - self.MAX_RANGE_M = max_m - - self.RESO_RAD = np.deg2rad(reso_deg) - - self.ANGLE_STD_SCALE = angle_std_scale - self.DIST_STD_RATE = dist_std_rate - - self.inst_pos_array = XYArray(np.array([[self.INST_LON_M], [self.INST_LAT_M]])) - self.global_x_m = None - self.global_y_m = None + angle_std_scale=0.01, dist_std_rate=0.005, calibrator=None): ``` -And then, some member methods, calculate_global_pos, get_global_x_m, get_global_y_m and draw_pos are implemented. calculate_global_pos method is used for transforming the position and pose of the sensor from the vehicle coordinate system to the global coordinate system based on the state of the vehicle. -```python - def calculate_global_pos(self, state): - """ - Function to calculate sensor's installation position on global coordinate system - state: vehicle's state object - """ - - pose = state.x_y_yaw() - transformed_array = self.inst_pos_array.homogeneous_transformation(pose[0, 0], pose[1, 0], pose[2, 0]) - - self.global_x_m = transformed_array.get_x_data() - self.global_y_m = transformed_array.get_y_data() -``` +Key parameters: -get_global_x_m and get_global_y_m are used for getting the global position of the sensor. -```python - def get_global_x_m(self): - """ - Getter of sensor's x installation position on global coordinate system - """ - - return self.global_x_m[0] - - def get_global_y_m(self): - """ - Getter of sensor's y installation position on global coordinate system - """ - - return self.global_y_m[0] -``` +- Installation pose on the vehicle coordinate system (`lon_m`, `lat_m`, `yaw_deg`) +- Sensing range and angular resolution (`min_m`, `max_m`, `reso_deg`) +- Noise model parameters (`angle_std_scale`, `dist_std_rate`) +- Optional calibration module (`calibrator`) -draw_pos is used for visualizing the position of the sensor in the simulation world. In this method, the position of the sensor is transformed into the global position and visualized. -```python - def draw_pos(self, axes, elems, state): - """ - Function to draw sensor's installation position on vehicle - axes: axes object of figure - elems: list of plot object - state: vehicle state object - """ - - self.calculate_global_pos(state) - pos_plot, = axes.plot(self.global_x_m, self.global_y_m, marker='.', color='b') - elems.append(pos_plot) -``` - -### 3.2.2 Homogeneous transformation matrix -For transforming the generated point cloud, some utility methods of transformation matrix. These methods can process homogeneous 2D transformation and rotation. -[matrix_lib.py](/src/components/common/matrix_lib.py) -```python -""" -matrix_lib.py +Main methods: -Author: Shisato Yano -""" +- `calculate_global_pos(state)`: Converts sensor installation position from vehicle coordinates to global coordinates. +- `calculate_sensor_odometry(state)`: Stores previous and current sensor poses as homogeneous transforms. +- `calibrate_extrinsic_params(vehicle_state)`: If a calibrator is attached, estimates extrinsic parameters using sensor and vehicle odometry. +- `draw_pos(axes, elems, state)`: Draws sensor position, and also draws calibration results when a calibrator exists. -import numpy as np -from math import sin, cos +### 3.2.2 Transformation Utilities +LiDAR point transformation uses homogeneous transformation matrices from: +- [matrix_lib.py](/src/components/common/matrix_lib.py) -def hom_mat_33(x, y, yaw): - """ - Homogeneous transformation matrix 3x3 - x: x direction translation[m] - y: y direction translation[m] - yaw: yaw direction rotation[rad] - """ +`hom_mat_33(x, y, yaw)` is used to convert points from sensor coordinates to vehicle/global coordinates. - cos_yaw, sin_yaw = cos(yaw), sin(yaw) +### 3.2.3 ScanPoint +`ScanPoint` represents one LiDAR return in the point cloud. - return np.array([[cos_yaw, -sin_yaw, x], - [sin_yaw, cos_yaw, y], - [0.0, 0.0, 1.0]]) +- distance and angle in sensor coordinates +- local point coordinates (`x_m`, `y_m`) +- transformed global coordinates used for drawing - -def rot_mat_22(yaw): - cos_yaw, sin_yaw = cos(yaw), sin(yaw) - - return np.array([[cos_yaw, -sin_yaw], - [sin_yaw, cos_yaw]]) -``` - -### 3.2.3 Scan point -ScanPoint class is implemented to represent a scan point in a point cloud from LiDAR. [XYArray class](/doc/2_vehicle_model/2_vehicle_model.md) is imported in the class for representing a x-y vector of the position of the scan point. The scan point object has the following data. - -* Distance from the LiDAR to the scan point[m] -* Horizontal angle from the LiDAR to the scan point[rad] -* X-Y position array of the scan point[m] -* Trasformed x coordinate of the scan point on a specific coordinate system -* Trasformed y coordinate of the scan point on a specific coordinate system - -The constructor of ScanPoint class is implemented as follow. A distance, horizontal angle, x coordinate and y coordinate are given as arguments. -[scan_point.py](/src/components/sensors/lidar/scan_point.py) ```python -""" -scan_point.py - -Author: Shisato Yano -""" - -import numpy as np -import sys -from pathlib import Path - -sys.path.append(str(Path(__file__).absolute().parent) + "/../../array") -sys.path.append(str(Path(__file__).absolute().parent) + "/../../common") -from xy_array import XYArray -from matrix_lib import hom_mat_33 - - class ScanPoint: - """ - Scan point of sensor class includes each sensing data - """ - def __init__(self, distance_m, angle_rad, x_m, y_m): - """ - Constructor - distance_m: sensed distance data[m] - angle_rad: sensed angle data[rad] - x_m: sensed point's x coordinate data[m] - y_m: sensed point's y coordinate data[m] - """ - self.distance_m = distance_m self.angle_rad = angle_rad self.point_array = XYArray(np.array([[x_m], [y_m]])) @@ -199,127 +53,20 @@ class ScanPoint: self.transformed_y = None ``` -Then, some member methods for accessing or visualizing the data. The getter methods for a dimension of x-y array, distance and x-y array of point are implemented as follow. -```python - def get_dimension(self): - """ - Return point's x-y array data's dimension value - """ - - return self.point_array.get_dimension() - - def get_distance_m(self): - """ - Return point's distance data[m] - """ - - return self.distance_m - - def get_point_array(self): - """ - Return point's x-y array data - Type is ndarray object - """ - - return self.point_array.get_data() -``` - -To transform the scan point data, the following functions are implemented. These functions are used to get the transformed scan point by other class. -```python - def get_transformed_data(self, sensor_lon, sensor_lat, sensor_yaw, - vehicle_x, vehicle_y, vehicle_yaw): - """ - Return transformed x-y array data based on specific coordinate system - Type is ndarray object - sensor_lon: longitudinal position of sensor on vehicle coordinate[m] - sensor_lat: lateral position of sensor on vehicle coordinate[m] - sensor_yaw: yaw angle of sensor on vehicle coordinate[rad] - vehicle_x: x position of vehicle on global coordinate[m] - vehicle_y: y position of vehicle on global coordinate[m] - vehicle_yaw: yaw angle of vehicle on global coordinate[rad] - """ - - # transformation matrix on sensor coordinate - point_xy = self.point_array.get_data() - sensor_tf = hom_mat_33(point_xy[0, 0], point_xy[1, 0], 0.0) - - # transformation matrix on vehicle coordinate - vehicle_tf = hom_mat_33(sensor_lon, sensor_lat, sensor_yaw) - - # transformation matrix on global coordinate - global_tf = hom_mat_33(vehicle_x, vehicle_y, vehicle_yaw) - - # homegeneous transformation from sensor to global coordinate - transformed_points_matrix = global_tf @ vehicle_tf @ sensor_tf - - return transformed_points_matrix[0, 2], transformed_points_matrix[1, 2] - - def calculate_transformed_point(self, sensor_lon, sensor_lat, sensor_yaw, - vehicle_x, vehicle_y, vehicle_yaw): - """ - Function to calculate transformed x-y point based on specific coordinate system - sensor_lon: longitudinal position of sensor on vehicle coordinate[m] - sensor_lat: lateral position of sensor on vehicle coordinate[m] - sensor_yaw: yaw angle of sensor on vehicle coordinate[rad] - vehicle_x: x position of vehicle on global coordinate[m] - vehicle_y: y position of vehicle on global coordinate[m] - vehicle_yaw: yaw angle of vehicle on global coordinate[rad] - """ - - self.transformed_x, self.transformed_y = \ - self.get_transformed_data(sensor_lon, sensor_lat, sensor_yaw, - vehicle_x, vehicle_y, vehicle_yaw) -``` +To transform coordinates, `ScanPoint` chains three transforms: -Finally, a function to draw the scan point is implemented as follow. -```python - def draw(self, axes, elems): - """ - Function to draw scan point's x-y coordinate data - axes: Axes object of figure - elems: List of plot objects - """ - - if self.transformed_x and self.transformed_y: - point_plot, = axes.plot(self.transformed_x, self.transformed_y, marker='.', color='b') - elems.append(point_plot) -``` +1. Point on sensor coordinates +2. Sensor pose on vehicle coordinates +3. Vehicle pose on global coordinates -### 3.2.4 Omni Directional LiDAR -Omni directional LiDAR class is implemented to generate the point cloud by importing [Scan point class](#323-scan-point). This class has the following data. +This is implemented in `get_transformed_data(...)` and `calculate_transformed_point(...)`. -* List of obstacle objects -* Sensor parameters object -* Size of distance database at each angles -* Maximum value of distance database -* List of delta values list for interpolating obstacle contour +### 3.2.4 OmniDirectionalLidar +`OmniDirectionalLidar` generates a 2D point cloud from obstacle contours. -The constructor of this class is implemented as follow. The list of obstacles objects and sensor parameters object are given as the arguments. And then, the above member data is initialized. ```python -""" -omni_directional_lidar.py - -Author: Shisato Yano -""" - -import numpy as np -from math import atan2, sin, cos -from scipy.stats import norm - -from scan_point import ScanPoint - class OmniDirectionalLidar: - """ - Sensing simulation class with Omni directional LiDAR - """ - def __init__(self, obst_list, params): - """ - Constructor - obst_list: List of Obstacle objects - params: Sensor parameters object - """ - self.obst_list = obst_list self.params = params self.DIST_DB_SIZE = int(np.floor((np.pi * 2.0) / self.params.RESO_RAD)) + 1 @@ -328,179 +75,61 @@ class OmniDirectionalLidar: self.latest_point_cloud = [] ``` -The installation position of this LiDAR need to be computed for transformation of the coordinate of the point cloud. The following function to compute the installation position on global coordinate system is implemented. -```python - def install(self, state): - """ - Function to calculate installed position on global coordinate - state: Vehicle's state object - """ - - self.params.calculate_global_pos(state) -``` +Main processing flow in `update(state)`: -The obstacles within the coverage of LiDAR can be observed. The private function, _visible(self, distance_m) is used to check the obstacle is within the coverage. -```python - def _visible(self, distance_m): - """ - Private function to check object is visible according to sensing distance - distance_m: Sensing distance[m] - """ - - return (self.params.MIN_RANGE_M <= distance_m <= self.params.MAX_RANGE_M) -``` +1. Update sensor global position +2. Update sensor odometry +3. Run optional extrinsic calibration +4. Generate contour points for each obstacle +5. Convert contour points to range/angle measurements +6. Apply ray-casting filter (occlusion handling + nearest point per angle bin) +7. Inject distance/angle noise and generate `ScanPoint` objects -For normalizing an angle of scan point data, the following private functions are implemented. -```python - def _normalize_angle_until_2pi(self, angle_rad): - """ - Private function to normalize sensing angle between 0 and 360 deg - angle_rad: Sensing angle[rad] - """ - - if 0.0 > angle_rad: return (angle_rad + np.pi * 2.0) - else: return angle_rad - - def _normalize_angle_pi_2_pi(self, angle_rad): - """ - Private function to normalize sensing angle between -180 and 180 deg - angle_rad: Sensing angle[rad] - """ - - if angle_rad > np.pi: return (angle_rad - np.pi * 2.0) - else: return angle_rad -``` +Current implementation: -The above normalization functions are used to compute a scan point data and a point cloud data. A function to compute a point cloud with ray casting algorithm is implemented considering occlusion. ```python - def _ray_casting_filter(self, distance_list, angle_list, state): - """ - Private function to filter point cloud by Ray casting - distance_list: List of sensing distance[m] - angle_list: List of sensing angle[rad] - """ - - point_cloud = [] - dist_db = [self.MAX_DB_VALUE for _ in range(self.DIST_DB_SIZE)] - - for i in range(len(angle_list)): - normalized_angle_2pi = self._normalize_angle_until_2pi(angle_list[i]) - angle_id = int(round(normalized_angle_2pi / self.params.RESO_RAD)) % self.DIST_DB_SIZE - if dist_db[angle_id] > distance_list[i]: - dist_db[angle_id] = distance_list[i] - - for i in range(len(dist_db)): - angle_rad = i * self.params.RESO_RAD - angle_pi_2_pi = self._normalize_angle_pi_2_pi(angle_rad) - distance_m = dist_db[i] - if (distance_m != self.MAX_DB_VALUE) and self._visible(distance_m): - angle_with_noise = norm.rvs(loc=angle_pi_2_pi, scale=self.params.ANGLE_STD_SCALE) - dist_with_noise = norm.rvs(loc=distance_m, scale=self.params.DIST_STD_RATE*distance_m) - x_m = dist_with_noise * cos(angle_with_noise) - y_m = dist_with_noise * sin(angle_with_noise) - point = ScanPoint(dist_with_noise, angle_with_noise, x_m, y_m) - vehicle_pose = state.x_y_yaw() - point.calculate_transformed_point(self.params.INST_LON_M, self.params.INST_LAT_M, self.params.INST_YAW_RAD, - vehicle_pose[0, 0], vehicle_pose[1, 0], vehicle_pose[2, 0]) - point_cloud.append(point) - - self.latest_point_cloud = point_cloud -``` +def update(self, state): + self.params.calculate_global_pos(state) + self.params.calculate_sensor_odometry(state) + self.params.calibrate_extrinsic_params(state) -For generating a scan point data, the following two functions need to be implemented. By using these functions, a line between two vertexes of the obstacle can be interpolated with multiple points. The coordinate of each points can be used as the scan points. -```python - def _interpolate(self, x_1, x_2, delta): - """ - Private function to interpolate between two values - x_1: value 1 - x_2: value 2 - delta: resolution between value 1 and 2 - """ - - return ((1.0 - delta) * x_1 + delta * x_2) - - def _calculate_contour_xy(self, vertex_x, vertex_y): - """ - Private function to calculate contour coordinates x-y - vertex_x: List of vertex's x coordinate - vertex_y: List of vertex's y coordinate - """ - - contour_x, contour_y = [], [] - len_vertex = len(vertex_x) - - for i in range(len_vertex - 1): - contour_x.extend([self._interpolate(vertex_x[i], vertex_x[i+1], delta) for delta in self.DELTA_LIST]) - contour_y.extend([self._interpolate(vertex_y[i], vertex_y[i+1], delta) for delta in self.DELTA_LIST]) - - contour_x.extend([self._interpolate(vertex_x[len_vertex-1], vertex_x[1], delta) for delta in self.DELTA_LIST]) - contour_y.extend([self._interpolate(vertex_y[len_vertex-1], vertex_y[1], delta) for delta in self.DELTA_LIST]) - - return contour_x, contour_y -``` + distance_list, angle_list = [], [] + for obst in self.obst_list.get_list(): + vertex_x, vertex_y = obst.vertex_xy() + contour_x, contour_y = self._calculate_contour_xy(vertex_x, vertex_y) + for x, y in zip(contour_x, contour_y): + diff_x = x - self.params.get_global_x_m() + diff_y = y - self.params.get_global_y_m() + distance_m = np.hypot(diff_x, diff_y) + angle_rad = atan2(diff_y, diff_x) - state.get_yaw_rad() + distance_list.append(distance_m) + angle_list.append(angle_rad) -A function to update the point cloud data including the above functions is implemented. This function is called in the main process of the simulation. -```python - def update(self, state): - """ - Function to update sensed point cloud data - state: Vehicle's state - """ - - self.params.calculate_global_pos(state) - - distance_list, angle_list = [], [] - for obst in self.obst_list.get_list(): - vertex_x, vertex_y = obst.vertex_xy() - contour_x, contour_y = self._calculate_contour_xy(vertex_x, vertex_y) - for x, y in zip(contour_x, contour_y): - diff_x = x - self.params.get_global_x_m() - diff_y = y - self.params.get_global_y_m() - distance_m = np.hypot(diff_x, diff_y) - angle_rad = atan2(diff_y, diff_x) - state.get_yaw_rad() - distance_list.append(distance_m) - angle_list.append(angle_rad) - - self._ray_casting_filter(distance_list, angle_list, state) + self._ray_casting_filter(distance_list, angle_list, state) ``` -Additionally, a function to draw the generated point cloud in the simulation is implemented. Then, the global position of the LiDAR on the vehicle is also drawn simultaneously. -```python - def draw(self, axes, elems, state): - """ - Function to draw sensed point cloud data - axes: Axes object of figure - elems: List of plot objects - state: Vehicle's state object - """ - - self.params.draw_pos(axes, elems, state) - - for point in self.latest_point_cloud: - point.draw(axes, elems) -``` +`draw(axes, elems, state)` draws both LiDAR position and point cloud. -Finally, some getters for an external class are implemented as follow. The array of point cloud, global x-y coordinates of the LiDAR can be got. -```python - def get_point_cloud(self): - """ - Function to get latest point cloud data - Each points are calculated on sensor coordinate system - """ - - return self.latest_point_cloud - - def get_global_x_m(self): - """ - Function to get installation position x in global coordinate[m] - """ - - return self.params.get_global_x_m() - - def get_global_y_m(self): - """ - Function to get installation position y in global coordinate[m] - """ - - return self.params.get_global_y_m() -``` \ No newline at end of file +### 3.2.5 Extrinsic Parameter Auto Calibration (Optional) +`UkfExtParamsCalibrator` estimates LiDAR extrinsic parameters on the vehicle coordinate system: + +- Longitudinal position +- Lateral position +- Yaw angle + +Source: + +- [ukf_ext_params_calibrator.py](/src/components/sensors/lidar/ukf_ext_params_calibrator.py) + +The module uses an Unscented Kalman Filter (UKF): + +- Predicts static extrinsic state via sigma points +- Predicts sensor odometry from vehicle odometry and candidate extrinsics +- Updates state using innovation between predicted and measured sensor odometry + +When this calibrator is passed into `SensorParameters(calibrator=...)`, the calibration process runs automatically during LiDAR updates and the estimated parameter values are drawn in the simulation. + +Example simulation: + +- [sensor_auto_calibration.py](/src/simulations/perception/sensor_auto_calibration/sensor_auto_calibration.py) +- Output GIF: ![](/src/simulations/perception/sensor_auto_calibration/sensor_auto_calibration.gif) diff --git a/doc/3_sensor_models/3_3_sensors.md b/doc/3_sensor_models/3_3_sensors.md index 8e7cf1cc..ca44ffe1 100644 --- a/doc/3_sensor_models/3_3_sensors.md +++ b/doc/3_sensor_models/3_3_sensors.md @@ -1,269 +1,114 @@ ## 3.3 Sensors -In this section, Sensors class is implemented for managing and processing data of each sensor models. This class can initialize, update and draw the data of each sensor models. +This section explains the `Sensors` wrapper class, which manages installed sensor modules and provides a single interface to the vehicle model. -### 3.3.1 Constructor -An object of [LiDAR class](/doc/3_sensor_models/3_2_lidar.md) is given to a constructor of this class as an argument. The argument is None as default and is stored as a member variable. -```python -""" -sensors.py +Source: -Author: Shisato Yano -""" +- [sensors.py](/src/components/sensors/sensors.py) -class Sensors: - """ - Each sensors logic class - """ - - def __init__(self, lidar=None): - """ - Constructor - lidar: lidar object - """ +### 3.3.1 Constructor +The current constructor accepts both LiDAR and GNSS modules. +```python +class Sensors: + def __init__(self, lidar=None, gnss=None): self.lidar = lidar + self.gnss = gnss ``` +- `lidar`: Object that provides LiDAR update/draw APIs +- `gnss`: Object that provides GNSS update/draw APIs + ### 3.3.2 Installation -A function to install each sensors is implemented to compute the global position coordinate on the vehicle. It is computed only when the object of LiDAR class is given to the constructor. -```python - def install(self, state): - """ - Function to calculate each sensor's installation position on vehicle - state: vehicle's state object - """ +`install(state)` computes installation-dependent data for sensors that require it. - if self.lidar: self.lidar.install(state) +```python +def install(self, state): + if self.lidar: + self.lidar.install(state) ``` +In the current implementation, LiDAR requires explicit installation. GNSS does not require a separate install step. + ### 3.3.3 Update and Draw -Two functions to update data and to draw data are implemented. These processes are executed only when the object of LiDAR class is installed. +`Sensors` updates and draws each installed sensor module. + ```python - def update_data(self, state): - """ - Function to update each sensor's data - state: vehicle's state object - """ - - if self.lidar: self.lidar.update(state) - - def draw_data(self, axes, elems, state): - """ - Function to draw each sensor's data - axes: axes object of figure - elems: list of plot object - state: vehicle's state object - """ - - if self.lidar: self.lidar.draw(axes, elems, state) +def update_data(self, state): + if self.lidar: + self.lidar.update(state) + if self.gnss: + self.gnss.update(state) + + +def draw_data(self, axes, elems, state): + if self.lidar: + self.lidar.draw(axes, elems, state) + if self.gnss: + self.gnss.draw(axes, elems) ``` ### 3.3.4 Getters -The following three functions to get data of LiDAR are implemented. First one is to get an array of a point cloud. Second one is to get global x coordinate of the LiDAR. Third one is to get global y coordinate of the LiDAR. -```python - def get_point_cloud_from_lidar(self): - """ - Function to get point cloud list from LiDAR - If LiDAR was not installed, would return empty list - """ - - if self.lidar: return self.lidar.get_point_cloud() - else: return [] - - def get_lidar_global_x_m(self): - """ - Function to get LiDAR's global position x[m] - When LiDAR is not installed, return 0.0 - """ - - if self.lidar: return self.lidar.get_global_x_m() - else: return 0.0 - - def get_lidar_global_y_m(self): - """ - Function to get LiDAR's global position x[m] - When LiDAR is not installed, return 0.0 - """ - - if self.lidar: return self.lidar.get_global_y_m() - else: return 0.0 -``` +The wrapper also provides helper getters used by other modules. -### 3.3.5 Vehicle class -For installing the object of sensors class on the vehicle model, [Four wheels vehicle class](/src/components/vehicle/four_wheels_vehicle.py) need to be modified. Firstly, an argument, sensors is added to the constructor. This argument is None as default. When it is None, any processes are not executed. -```python -class FourWheelsVehicle: - """ - Four Wheels Vehicle model class - """ - - def __init__(self, state, spec, sensors=None, show_zoom=True): - """ - Constructor - state: Vehicle's state object - spec: Vehicle's specification object - sensors: Sencors object - show_zoom: Flag for zoom around vehicle - """ -``` +LiDAR getters: -A private function to install sensors is implemented. This function is used to compute the global position coordinate of the sensors based on the current state of the vehicle. The function, install in Sensors class is called. -```python - def _install_sensors(self, state): - """ - Private function to calculate each sensor's installation position on vehicle - state: Vehicle's state object - """ +- `get_point_cloud_from_lidar()` +- `get_lidar_global_x_m()` +- `get_lidar_global_y_m()` - if self.sensors: self.sensors.install(state) -``` -The added argument, sensors is stored in a member variable and the above function, _install_sensors() is called in the constructor. -```python - self.sensors = sensors - self._install_sensors(self.state) -``` +GNSS getter: + +- `get_xy_pos_from_gnss()` -For updating and drawing the data, the following two private functions are implemented. ```python - def _update_sensors_data(self, state): - """ - Private function to update each sensor's data - state: Vehicle's state object - """ - - if self.sensors: self.sensors.update_data(state) - - def _draw_sensors_data(self, axes, elems, state): - """ - Private function to draw each sensor's data - axes: Axes object of figure - elems: List of plot object - state: Vehicle's state object - """ - - if self.sensors: self.sensors.draw_data(axes, elems, state) +def get_xy_pos_from_gnss(self): + if self.gnss: + return self.gnss.get_xy_pos() + else: + return None ``` -These functions are called in the update function and draw function of the vehicle class. + +### 3.3.5 Vehicle Integration +`Sensors` is integrated into [FourWheelsVehicle](/src/components/vehicle/four_wheels_vehicle.py). + +Current constructor: + ```python - def update(self, time_s): - """ - Function to update each member objects - time_s: Simulation interval time[sec] - """ - - self._update_sensors_data(self.state) - - def draw(self, axes, elems): - """ - Function to draw each member object's data - axes: Axes object of figure - elems: List of plot object - """ - - self._draw_sensors_data(axes, elems, self.state) - - self.state.draw(axes, elems) - x_y_yaw_array = self.state.x_y_yaw() - x_m = self.state.get_x_m() - y_m = self.state.get_y_m() - - self.body.draw(axes, x_y_yaw_array, elems) - self.chassis.draw(axes, x_y_yaw_array, elems) - self.front_left_tire.draw(axes, x_y_yaw_array, steer_rad, elems) - self.front_right_tire.draw(axes, x_y_yaw_array, steer_rad, elems) - self.rear_left_tire.draw(axes, x_y_yaw_array, elems) - self.rear_right_tire.draw(axes, x_y_yaw_array, elems) - self.front_axle.draw(axes, x_y_yaw_array, elems) - self.rear_axle.draw(axes, x_y_yaw_array, elems) - - if self.show_zoom: - axes.set_xlim(x_m - self.spec.area_size, x_m + self.spec.area_size) - axes.set_ylim(y_m - self.spec.area_size, y_m + self.spec.area_size) - else: - axes.set_xlim(self.spec.x_lim.min_value(), self.spec.x_lim.max_value()) - axes.set_ylim(self.spec.y_lim.min_value(), self.spec.y_lim.max_value()) +def __init__(self, state, spec, controller=None, sensors=None, + detector=None, mapper=None, localizer=None, show_zoom=True): ``` -### 3.3.6 LiDAR Sensing Simulation -The object sesning with 2D LiDAR can be simulated by executing the following sample program. A single 2D LiDAR senses multiple obstacles and the point cloud data is generated. -[lidar_obstacle_sensing.py](/src/simulations/perception/lidar_obstacle_sensing/lidar_obstacle_sensing.py) -```python -""" -lidar_obstacle_sensing.py - -Author: Shisato Yano -""" - -# import path setting -import numpy as np -import sys -from pathlib import Path - -abs_dir_path = str(Path(__file__).absolute().parent) -relative_path = "/../../../components/" - -sys.path.append(abs_dir_path + relative_path + "visualization") -sys.path.append(abs_dir_path + relative_path + "state") -sys.path.append(abs_dir_path + relative_path + "vehicle") -sys.path.append(abs_dir_path + relative_path + "obstacle") -sys.path.append(abs_dir_path + relative_path + "sensors") -sys.path.append(abs_dir_path + relative_path + "sensors/lidar") - - -# import component modules -from global_xy_visualizer import GlobalXYVisualizer -from min_max import MinMax -from time_parameters import TimeParameters -from vehicle_specification import VehicleSpecification -from state import State -from four_wheels_vehicle import FourWheelsVehicle -from obstacle import Obstacle -from obstacle_list import ObstacleList -from sensors import Sensors -from sensor_parameters import SensorParameters -from omni_directional_lidar import OmniDirectionalLidar - - -# flag to show plot figure -# when executed as unit test, this flag is set as false -show_plot = True - - -def main(): - """ - Main process function - """ - - # set simulation parameters - x_lim, y_lim = MinMax(-30, 30), MinMax(-30, 30) - vis = GlobalXYVisualizer(x_lim, y_lim, TimeParameters(span_sec=20)) - - # create obstacle instances - obst_list = ObstacleList() - obst1 = Obstacle(State(x_m=-5.0, y_m=15.0, speed_mps=1.0), yaw_rate_rps=np.deg2rad(10), width_m=1.0) - obst_list.add_obstacle(obst1) - obst2 = Obstacle(State(x_m=-15.0, y_m=-15.0), length_m=10.0, width_m=5.0) - obst_list.add_obstacle(obst2) - obst3 = Obstacle(State(x_m=20.0), yaw_rate_rps=np.deg2rad(15)) - obst_list.add_obstacle(obst3) - vis.add_object(obst_list) - - # create vehicle instance - spec = VehicleSpecification(area_size=30.0) # spec instance - lidar = OmniDirectionalLidar(obst_list, SensorParameters(lon_m=spec.wheel_base_m/2)) # lidar instance - vehicle = FourWheelsVehicle(State(color=spec.color), spec, sensors=Sensors(lidar=lidar)) # set state, spec, lidar as arguments - vis.add_object(vehicle) - - # plot figure is not shown when executed as unit test - if not show_plot: vis.not_show_plot() - - # show plot figure - vis.draw() - - -# execute main process -if __name__ == "__main__": - main() +Current update sequence in the vehicle class: -``` -![](/src/simulations/perception/lidar_obstacle_sensing/lidar_obstacle_sensing.gif) \ No newline at end of file +1. Update sensor data +2. Update detection data +3. Update map data +4. Update control command +5. Update localization/state + +Because of this flow, LiDAR/GNSS data can be consumed by detector, mapper, and localizer modules in the same simulation loop. + +### 3.3.6 GNSS Module +GNSS module source: + +- [gnss.py](/src/components/sensors/gnss/gnss.py) + +The module provides noisy `(x, y)` observations based on vehicle state: + +- `observation_model(state)` extracts ideal position +- `update(state)` adds observation noise +- `draw(axes, elems)` visualizes observation history +- `get_xy_pos()` returns latest observation for localization modules + +Example usage appears in: + +- [extended_kalman_filter_localization.py](/src/simulations/localization/extended_kalman_filter_localization/extended_kalman_filter_localization.py) + +### 3.3.7 LiDAR Sensing Simulation +A LiDAR sensing example is available here: + +- [lidar_obstacle_sensing.py](/src/simulations/perception/lidar_obstacle_sensing/lidar_obstacle_sensing.py) + +This simulation installs a LiDAR module through `Sensors(lidar=...)`, senses multiple obstacles, and visualizes point-cloud outputs. + +![](/src/simulations/perception/lidar_obstacle_sensing/lidar_obstacle_sensing.gif) diff --git a/doc/3_sensor_models/3_sensor_models.md b/doc/3_sensor_models/3_sensor_models.md index cf6ef530..49dfab90 100644 --- a/doc/3_sensor_models/3_sensor_models.md +++ b/doc/3_sensor_models/3_sensor_models.md @@ -1,8 +1,13 @@ # 3. Sensor Models -This chapter provides the Python programs design and implementation of sensor models. It includes the following contents. +This chapter explains the design and implementation of the sensor-related modules used in this project. + +The documents in this chapter are: ## 3.1 [Obstacle](/doc/3_sensor_models/3_1_obstacle.md) +Covers obstacle data structures used as sensing targets in simulation. ## 3.2 [LiDAR](/doc/3_sensor_models/3_2_lidar.md) +Covers LiDAR point-cloud generation, scan-point representation, and optional extrinsic-parameter auto-calibration. -## 3.3 [Sensors](/doc/3_sensor_models/3_3_sensors.md) \ No newline at end of file +## 3.3 [Sensors](/doc/3_sensor_models/3_3_sensors.md) +Covers the sensor wrapper class that manages LiDAR and GNSS modules and how it is connected to the vehicle model.