Skip to content

Commit d810d3b

Browse files
tracking more tightly
1 parent 870d582 commit d810d3b

2 files changed

Lines changed: 5 additions & 16 deletions

File tree

src/hangar_sim/config/fuse/fuse.yaml

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,8 @@ state_estimator:
1717
# Order: x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az
1818
# Ground robot: z, roll, pitch (and their velocities) should be small
1919
# since the robot stays on the ground plane and level.
20-
process_noise_diagonal: [0.25, 0.25, 0.001, 0.001, 0.001, 0.25, 0.1, 0.1, 0.001, 0.001, 0.001, 0.1, 0.001, 0.001, 0.001]
20+
#process_noise_diagonal: [0.25, 0.25, 0.001, 0.001, 0.001, 0.25, 0.1, 0.1, 0.001, 0.001, 0.001, 0.1, 0.001, 0.001, 0.001]
21+
process_noise_diagonal: [2.0, 2.0, 0.1, 0.1, 0.1, 2.0, 2.0, 1.0, 0.1, 0.1, 0.1, 0.001, 0.01, 0.01, 0.001]
2122

2223
sensor_models:
2324
initial_localization_sensor:
@@ -47,10 +48,7 @@ state_estimator:
4748
linear_velocity_dimensions: ['x']
4849
angular_velocity_dimensions: ['yaw']
4950
differential: false
50-
# Order: x, y, z, roll, pitch, yaw
51-
pose_covariance_diagonal: [0.5, 0.5, 0.01, 1e9, 1e9, 0.05]
52-
# Order: vx, vy, vz, vroll, vpitch, vyaw
53-
twist_covariance_diagonal: [0.05, 1e9, 1e9, 1e9, 1e9, 0.05]
51+
# Uses covariance from the odom message directly (no override)
5452

5553
# IMU sensor
5654
# - Roll/pitch orientation from gravity vector (absolute, keeps robot level)
@@ -72,8 +70,8 @@ state_estimator:
7270

7371
filtered_publisher:
7472
topic: 'odom_filtered'
75-
base_link_frame_id: 'base_footprint'
76-
base_link_output_frame_id: 'base_footprint'
73+
base_link_frame_id: 'ridgeback_base_link'
74+
base_link_output_frame_id: 'ridgeback_base_link'
7775
odom_frame_id: 'odom'
7876
map_frame_id: 'map'
7977
world_frame_id: 'odom'

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

Lines changed: 0 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -268,14 +268,6 @@ def generate_launch_description():
268268
arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "map", "odom"],
269269
)
270270

271-
# Publish odometry as joint state messages
272-
odom_to_joint_state_repub = Node(
273-
package="hangar_sim",
274-
executable="odometry_joint_state_publisher.py",
275-
name="odometry_joint_state_publisher",
276-
output="log",
277-
)
278-
279271
# QoS relay to bridge BEST_EFFORT odom to RELIABLE for fuse
280272
odom_qos_relay = Node(
281273
package="hangar_sim",
@@ -312,7 +304,6 @@ def generate_launch_description():
312304

313305
ld.add_action(static_tf_world_to_map)
314306
ld.add_action(static_tf_map_to_odom)
315-
ld.add_action(odom_to_joint_state_repub)
316307
ld.add_action(odom_qos_relay)
317308

318309
# Fuse state estimator for mobile base localization

0 commit comments

Comments
 (0)