simulation.py
Go to the documentation of this file.
1 # simulation.py
2 import numpy as np
3 
4 import gtsam
5 
6 
8  num_landmarks,
9  world_size,
10  robot_radius,
11  robot_angular_vel,
12  num_steps,
13  dt,
14  odometry_noise_model,
15  measurement_noise_model,
16  max_sensor_range,
17  X, # Symbol generator function
18  L, # Symbol generator function
19  odom_seed=42,
20  meas_seed=42,
21  landmark_seed=42,
22 ):
23  """Generates ground truth and simulated measurements for SLAM.
24 
25  Args:
26  num_landmarks: Number of landmarks to generate.
27  world_size: Size of the square world environment.
28  robot_radius: Radius of the robot's circular path.
29  robot_angular_vel: Angular velocity of the robot (rad/step).
30  num_steps: Number of simulation steps.
31  dt: Time step duration.
32  odometry_noise_model: GTSAM noise model for odometry.
33  measurement_noise_model: GTSAM noise model for bearing-range.
34  max_sensor_range: Maximum range of the bearing-range sensor.
35  X: GTSAM symbol shorthand function for poses.
36  L: GTSAM symbol shorthand function for landmarks.
37  odom_seed: Random seed for odometry noise.
38  meas_seed: Random seed for measurement noise.
39  landmark_seed: Random seed for landmark placement.
40 
41  Returns:
42  tuple: Contains:
43  - landmarks_gt_dict (dict): L(i) -> gtsam.Point2 ground truth.
44  - poses_gt (list): List of gtsam.Pose2 ground truth poses.
45  - odometry_measurements (list): List of noisy gtsam.Pose2 odometry.
46  - measurements_sim (list): List of lists, measurements_sim[k] contains
47  tuples (L(lm_id), bearing, range) for step k.
48  - landmarks_gt_array (np.array): 2xN numpy array of landmark positions.
49  """
50  np.random.seed(landmark_seed)
51  odometry_noise_sampler = gtsam.Sampler(odometry_noise_model, odom_seed)
52  measurement_noise_sampler = gtsam.Sampler(measurement_noise_model, meas_seed)
53 
54  # 1. Ground Truth Landmarks
55  landmarks_gt_array = (np.random.rand(2, num_landmarks) - 0.5) * world_size
56  landmarks_gt_dict = {
57  L(i): gtsam.Point2(landmarks_gt_array[:, i]) for i in range(num_landmarks)
58  }
59 
60  # 2. Ground Truth Robot Path
61  poses_gt = []
62  current_pose_gt = gtsam.Pose2(robot_radius, 0, np.pi / 2) # Start on circle edge
63  poses_gt.append(current_pose_gt)
64 
65  for _ in range(num_steps):
66  delta_theta = robot_angular_vel * dt
67  arc_length = robot_angular_vel * robot_radius * dt
68  motion_command = gtsam.Pose2(arc_length, 0, delta_theta)
69  current_pose_gt = current_pose_gt.compose(motion_command)
70  poses_gt.append(current_pose_gt)
71 
72  # 3. Simulate Noisy Odometry Measurements
73  odometry_measurements = []
74  for k in range(num_steps):
75  pose_k = poses_gt[k]
76  pose_k1 = poses_gt[k + 1]
77  true_odom = pose_k.between(pose_k1)
78 
79  # Sample noise directly for Pose2 composition (approximate)
80  odom_noise_vec = odometry_noise_sampler.sample()
81  noisy_odom = true_odom.compose(
82  gtsam.Pose2(odom_noise_vec[0], odom_noise_vec[1], odom_noise_vec[2])
83  )
84  odometry_measurements.append(noisy_odom)
85 
86  # 4. Simulate Noisy Bearing-Range Measurements
87  measurements_sim = [[] for _ in range(num_steps + 1)]
88  for k in range(num_steps + 1):
89  robot_pose = poses_gt[k]
90  for lm_id in range(num_landmarks):
91  lm_gt_pt = landmarks_gt_dict[L(lm_id)]
92  try:
93  measurement_factor = gtsam.BearingRangeFactor2D(
94  X(k),
95  L(lm_id),
96  robot_pose.bearing(lm_gt_pt),
97  robot_pose.range(lm_gt_pt),
98  measurement_noise_model,
99  )
100  true_range = measurement_factor.measured().range()
101  true_bearing = measurement_factor.measured().bearing()
102 
103  # Check sensor limits (range and Field of View - e.g. +/- 45 degrees)
104  if (
105  true_range <= max_sensor_range
106  and abs(true_bearing.theta()) < np.pi / 2
107  ):
108  # Sample noise
109  noise_vec = measurement_noise_sampler.sample()
110  noisy_bearing = true_bearing.retract(
111  np.array([noise_vec[0]])
112  ) # Retract on SO(2)
113  noisy_range = true_range + noise_vec[1]
114 
115  if noisy_range > 0: # Ensure range is positive
116  measurements_sim[k].append(
117  (L(lm_id), noisy_bearing, noisy_range)
118  )
119  except Exception as e:
120  # Catch potential errors like point being too close to the pose
121  # print(f"Sim Warning at step {k}, landmark {lm_id}: {e}") # Can be verbose
122  pass
123 
124  print(f"Simulation Generated: {num_landmarks} landmarks.")
125  print(
126  f"Simulation Generated: {num_steps + 1} ground truth poses and {num_steps} odometry measurements."
127  )
128  num_meas_total = sum(len(m_list) for m_list in measurements_sim)
129  print(f"Simulation Generated: {num_meas_total} bearing-range measurements.")
130 
131  return (
132  landmarks_gt_dict,
133  poses_gt,
134  odometry_measurements,
135  measurements_sim,
136  landmarks_gt_array,
137  )
X
#define X
Definition: icosphere.cpp:20
gtsam::range
Double_ range(const Point2_ &p, const Point2_ &q)
Definition: slam/expressions.h:30
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:145
gtsam.examples.simulation.generate_simulation_data
def generate_simulation_data(num_landmarks, world_size, robot_radius, robot_angular_vel, num_steps, dt, odometry_noise_model, measurement_noise_model, max_sensor_range, X, L, odom_seed=42, meas_seed=42, landmark_seed=42)
Definition: simulation.py:7
L
MatrixXd L
Definition: LLT_example.cpp:6
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
abs
#define abs(x)
Definition: datatypes.h:17
len
size_t len(handle h)
Get the length of a Python object.
Definition: pytypes.h:2448
gtsam::Sampler
Definition: Sampler.h:31
gtsam::Pose2
Definition: Pose2.h:39


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:03:18