diff --git a/src/hangar_sim/description/picknik_ur_mujoco_ros2_control.xacro b/src/hangar_sim/description/picknik_ur_mujoco_ros2_control.xacro
index a072f8aa..b43913f8 100644
--- a/src/hangar_sim/description/picknik_ur_mujoco_ros2_control.xacro
+++ b/src/hangar_sim/description/picknik_ur_mujoco_ros2_control.xacro
@@ -22,7 +22,10 @@
10
true
ridgeback_base_link
+ 150
true
+ odom
+ false
${mujoco_viewer}
default
diff --git a/src/hangar_sim/launch/sim/robot_drivers_to_persist_sim.launch.py b/src/hangar_sim/launch/sim/robot_drivers_to_persist_sim.launch.py
index 60461b22..04a797f8 100644
--- a/src/hangar_sim/launch/sim/robot_drivers_to_persist_sim.launch.py
+++ b/src/hangar_sim/launch/sim/robot_drivers_to_persist_sim.launch.py
@@ -256,22 +256,27 @@ def generate_launch_description():
}.items(),
)
- # Static TF between mjWorld and map frame
+ # Static TF between mj_world and map frame — anchors the nav2 map frame to the MuJoCo
+ # simulation world.
static_tf_world_to_map = Node(
package="tf2_ros",
executable="static_transform_publisher",
- name="static_transform_publisher",
+ name="static_tf_world_to_map",
output="log",
arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "mj_world", "map"],
)
- # Static TF between map and odom frame
- static_tf_map_to_odom = Node(
+ # Static TF connecting MoveIt's planning root ('world') to the simulation root ('mj_world').
+ # The UI (pose-utils.ts) hardcodes 'world' as the reference frame for all user-clicked poses,
+ # so this link is required for nav2 goals to be transformable to 'map', and lets MoveIt
+ # locate the base link via 'world → mj_world → base_platform → ridgeback_base_link'
+ # instead of relying on virtual joint states (which are not published in sim).
+ static_tf_mj_world_to_world = Node(
package="tf2_ros",
executable="static_transform_publisher",
- name="static_transform_publisher",
+ name="static_tf_mj_world_to_world",
output="log",
- arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "map", "odom"],
+ arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "mj_world", "world"],
)
# QoS relay to bridge BEST_EFFORT odom and IMU to RELIABLE for fuse
@@ -364,7 +369,7 @@ def generate_launch_description():
# ld.add_action(rviz_cmd)
ld.add_action(static_tf_world_to_map)
- ld.add_action(static_tf_map_to_odom)
+ ld.add_action(static_tf_mj_world_to_world)
ld.add_action(sensor_qos_relay)
ld.add_action(laser_filter_front_node)
ld.add_action(laser_filter_rear_node)
diff --git a/src/hangar_sim/package.xml b/src/hangar_sim/package.xml
index 7563389f..91578728 100644
--- a/src/hangar_sim/package.xml
+++ b/src/hangar_sim/package.xml
@@ -26,6 +26,7 @@
picknik_ur_base_config
realsense2_camera
realsense2_description
+ slam_toolbox
ur_description
velocity_force_controller
moveit_pro_sam2
diff --git a/src/hangar_sim/params/nav2_params.yaml b/src/hangar_sim/params/nav2_params.yaml
index 0ee8d6af..4cdfa9c5 100644
--- a/src/hangar_sim/params/nav2_params.yaml
+++ b/src/hangar_sim/params/nav2_params.yaml
@@ -428,3 +428,69 @@ velocity_smoother:
odom_duration: 0.1
deadband_velocity: [0.0, 0.0, 0.0]
velocity_timeout: 1.0
+
+slam_toolbox:
+ ros__parameters:
+ use_sim_time: True
+
+ # Plugin params
+ solver_plugin: solver_plugins::CeresSolver
+ ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
+ ceres_preconditioner: SCHUR_JACOBI
+ ceres_trust_strategy: LEVENBERG_MARQUARDT
+ ceres_dogleg_type: TRADITIONAL_DOGLEG
+ ceres_loss_function: None
+
+ # ROS Parameters
+ odom_frame: odom
+ map_frame: map
+ base_frame: ridgeback_base_link
+ scan_topic: /scan_front_filtered
+ mode: mapping
+
+ debug_logging: false
+ throttle_scans: 1
+ transform_publish_period: 0.02
+ map_update_interval: 5.0
+ resolution: 0.05
+ max_laser_range: 20.0
+ minimum_time_interval: 0.5
+ tf_buffer_duration: 30.0
+ stack_size_to_use: 40000000
+ enable_interactive_mode: true
+
+ # General Parameters
+ use_scan_matching: true
+ use_scan_barycenter: true
+ minimum_travel_distance: 0.5
+ minimum_travel_heading: 0.5
+ scan_buffer_size: 10
+ scan_buffer_maximum_scan_distance: 10.0
+ link_match_minimum_response_fine: 0.1
+ link_scan_maximum_distance: 1.5
+ loop_search_maximum_distance: 3.0
+ do_loop_closing: true
+ loop_match_minimum_chain_size: 10
+ loop_match_maximum_variance_coarse: 3.0
+ loop_match_minimum_response_coarse: 0.35
+ loop_match_minimum_response_fine: 0.45
+
+ # Correlation Parameters
+ correlation_search_space_dimension: 0.5
+ correlation_search_space_resolution: 0.01
+ correlation_search_space_smear_deviation: 0.1
+
+ # Loop Closure Parameters
+ loop_search_space_dimension: 8.0
+ loop_search_space_resolution: 0.05
+ loop_search_space_smear_deviation: 0.03
+
+ # Scan Matcher Parameters
+ distance_variance_penalty: 0.5
+ angle_variance_penalty: 1.0
+ fine_search_angle_offset: 0.00349
+ coarse_search_angle_offset: 0.349
+ coarse_angle_resolution: 0.0349
+ minimum_angle_penalty: 0.9
+ minimum_distance_penalty: 0.5
+ use_response_expansion: true