Skip to content

Commit 376c3ed

Browse files
tuned covariances ... drift is noticeable
1 parent fcabb26 commit 376c3ed

2 files changed

Lines changed: 33 additions & 21 deletions

File tree

src/hangar_sim/config/fuse/fuse.yaml

Lines changed: 18 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@ state_estimator:
55
# Fixed-lag smoother configuration
66
optimization_frequency: 20.0
77
transaction_timeout: 0.01
8-
lag_duration: 0.5
8+
lag_duration: 1.0
99

1010
# Motion model for mobile base (3D omnidirectional)
1111
motion_models:
@@ -15,7 +15,8 @@ state_estimator:
1515
mobile_base_motion:
1616
# Process noise for state variables
1717
# Order: x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az
18-
process_noise_diagonal: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 1.0, 1.0, 1.0]
18+
# Ground robot: z, roll, pitch tightly constrained
19+
process_noise_diagonal: [0.005, 0.005, 0.0001, 0.0001, 0.0001, 0.005, 0.005, 0.005, 0.0001, 0.0001, 0.0001, 0.005, 0.05, 0.05, 0.001]
1920

2021
sensor_models:
2122
initial_localization_sensor:
@@ -33,41 +34,41 @@ state_estimator:
3334
publish_on_startup: true
3435
# Order: x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az
3536
initial_state: [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]
36-
initial_sigma: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1]
37+
# Order: x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az
38+
# Moderate x,y,yaw sigma: some initial position uncertainty
39+
# Tight z,roll,pitch: ground robot constraints
40+
initial_sigma: [1.0, 1.0, 0.01, 0.01, 0.01, 0.5, 0.1, 0.1, 0.01, 0.01, 0.01, 0.1, 0.1, 0.1, 0.01]
3741

3842
wheel_odom_sensor:
3943
# Using /odom_reliable from QoS relay (bridges BEST_EFFORT to RELIABLE)
4044
topic: /odom_reliable
4145
queue_size: 10
42-
# 2D position from wheels (no z)
43-
position_dimensions: ['x', 'y']
46+
# Position from wheels (z=0 from odom_zero_z anchors the ground plane)
47+
position_dimensions: ['x', 'y', 'z']
4448
# Heading only
4549
orientation_dimensions: ['yaw']
4650
# Forward velocity
4751
linear_velocity_dimensions: ['x']
4852
# Turn rate
4953
angular_velocity_dimensions: ['yaw']
50-
# Use relative constraints (pose changes rather than absolute poses)
54+
# Use relative constraints (physically correct - wheel odom errors are correlated)
5155
differential: true
5256
# Covariances - use large values for unused dimensions
5357
# Order: x, y, z, roll, pitch, yaw
54-
pose_covariance_diagonal: [0.05, 0.05, 1e9, 1e9, 1e9, 0.05]
58+
pose_covariance_diagonal: [0.01, 0.01, 0.0001, 1e9, 1e9, 0.01]
5559
# Order: vx, vy, vz, vroll, vpitch, vyaw
56-
twist_covariance_diagonal: [0.05, 1e9, 1e9, 1e9, 1e9, 0.05]
60+
twist_covariance_diagonal: [0.01, 1e9, 1e9, 1e9, 1e9, 0.01]
5761

5862
imu_sensor:
5963
topic: /imu_sensor_broadcaster/imu
60-
# Orientation from IMU
61-
orientation_dimensions: ['roll', 'pitch', 'yaw']
62-
# Angular velocity from gyroscope
64+
# Orientation from IMU (roll/pitch only - yaw reference frame
65+
# from MuJoCo framequat is in world frame, not odom frame)
66+
orientation_dimensions: ['roll', 'pitch']
67+
# Angular velocity from gyroscope (helps with short-term heading)
6368
angular_velocity_dimensions: ['roll', 'pitch', 'yaw']
64-
# Linear acceleration from accelerometer
65-
linear_acceleration_dimensions: ['x', 'y', 'z']
66-
# Transform accelerations into base frame
67-
acceleration_target_frame: 'ridgeback_base_link'
69+
# No linear acceleration - accelerometer biases double-integrate
70+
# into large position drift on a ground robot with good wheel odom
6871
twist_target_frame: 'ridgeback_base_link'
69-
# Remove gravity from acceleration measurements
70-
remove_gravitational_acceleration: true
7172
queue_size: 10
7273

7374
# Publish filtered odometry

src/hangar_sim/launch/sim/robot_drivers_to_persist_sim.launch.py

Lines changed: 15 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -41,11 +41,13 @@
4141
from launch.launch_description_sources import PythonLaunchDescriptionSource
4242
from launch.substitutions import (
4343
LaunchConfiguration,
44+
PathJoinSubstitution,
4445
PythonExpression,
4546
)
4647
from launch_ros.actions import Node
4748
from launch_ros.actions import PushRosNamespace
4849
from launch_ros.descriptions import ParameterFile
50+
from launch_ros.substitutions import FindPackageShare
4951
from nav2_common.launch import RewrittenYaml, ReplaceString
5052

5153

@@ -282,10 +284,6 @@ def generate_launch_description():
282284
output="log",
283285
)
284286

285-
<<<<<<< HEAD
286-
287-
=======
288-
>>>>>>> 5c3330bb (adding IMU fuse plugin to hangar_sim)
289287
# Create the launch description and populate
290288
ld = LaunchDescription()
291289

@@ -317,4 +315,17 @@ def generate_launch_description():
317315
ld.add_action(odom_to_joint_state_repub)
318316
ld.add_action(odom_qos_relay)
319317

318+
# Fuse state estimator for mobile base localization
319+
hangar_sim_pkg = FindPackageShare("hangar_sim")
320+
fuse_state_estimator = Node(
321+
package="fuse_optimizers",
322+
executable="fixed_lag_smoother_node",
323+
name="state_estimator",
324+
parameters=[
325+
PathJoinSubstitution([hangar_sim_pkg, "config", "fuse", "fuse.yaml"])
326+
],
327+
output="screen",
328+
)
329+
ld.add_action(fuse_state_estimator)
330+
320331
return ld

0 commit comments

Comments
 (0)