Skip to content

add lidar sensor and use obstacle_layer in costmap params#531

Open
bkanator wants to merge 1 commit intomainfrom
lidar-hangar-sim
Open

add lidar sensor and use obstacle_layer in costmap params#531
bkanator wants to merge 1 commit intomainfrom
lidar-hangar-sim

Conversation

@bkanator
Copy link

@bkanator bkanator commented Mar 13, 2026

summarized with claude: (I tested with confirming local costmap matches and running the click to navigate objective. It was also helpful to watch the mujoco viewer, rviz, and add temporary boxes. I increased to the 3 degree beam spacing after performance did not seem to be an issue )

Summary

This PR adds obstacle detection to the hangar_sim local and global costmaps, which previously had no
active sensors feeding Nav2. The nav2 config was referencing a non-existent /left_camera/points point
cloud, so obstacles were never detected during navigation.

Changes

Added dual 270° planar lidars to the Ridgeback MJCF (description/ur5e_ridgeback.xml)

  • Front lidar: mounted at front bumper (pos="0.45 0 0.15")
  • Rear lidar: mounted at rear bumper (pos="-0.45 0 0.15")
  • 91 beams × 3° spacing = 270° FOV per lidar, matching real SICK TIM571 spec
  • Range: 0.05m – 25.0m
  • Added <size nuser_sensor="6"/> required by the MuJoCo lidar plugin

Added script/scan_mirror_fix.py

  • The MuJoCo lidar plugin publishes the lidar_front_ROS / lidar_rear_ROS TF frames with RPY [180°, 0°,
    0°] relative to ridgeback_base_link, which flips the Y-axis and causes obstacles to appear mirrored
    left↔right in the costmap
  • This node reverses the ranges array in the /scan message and republishes as /scan_mirrored,
    mathematically cancelling the TF sign flip

Added params/laser_filter_params.yaml

  • LaserScanAngularBoundsFilter keeping only beams within ±93° (±1.6231 rad)
  • Removes beams at ±93°–135° that hit the Ridgeback chassis corners

Updated params/nav2_params.yaml

  • Replaced non-functional voxel_layer (3D point cloud plugin, wrong type for LaserScan) with
    obstacle_layer in both local and global costmaps
  • Observation source changed from /left_camera/points/scan_filtered
  • Local costmap: obstacle_layer + inflation_layer, rolling 10×10m window
  • Global costmap: static_layer + obstacle_layer + inflation_layer
  • All scan QoS set to best_effort to match MuJoCo's SensorDataQoS publisher

Updated launch/sim/robot_drivers_to_persist_sim.launch.py

  • Added scan_mirror_fix node (/scan/scan_mirrored)
  • Added laser_angular_filter node (/scan_mirrored/scan_filtered)

Updated CMakeLists.txt and package.xml

  • Installed scan_mirror_fix.py as an executable
  • Added laser_filters exec dependency

Updated description/hangar_scene.xml

  • Changed timestep from 0.02 to 0.01 for physics stability

Scan pipeline

/scan  →  scan_mirror_fix  →  /scan_mirrored  →  laser_angular_filter  →  /scan_filtered  →  Nav2
          (reverses ranges          (removes chassis
           to fix Y-flip)            self-hits ±93–135°)

Test plan

  • Launch sim: ros2 launch moveit_studio_agent agent_robot.launch.xml
  • Verify /scan is published at expected rate: ros2 topic hz /scan
  • Verify /scan_filtered is published: ros2 topic hz /scan_filtered
  • Drive robot toward an obstacle and confirm local costmap marks it correctly (no left↔right
    mirroring)
  • Confirm global costmap updates with static map layer visible
  • Run a Nav2 navigate-to-pose goal and confirm the robot avoids obstacles

@bkanator bkanator added this to the 9.1.0 milestone Mar 13, 2026
@bkanator bkanator force-pushed the lidar-hangar-sim branch 3 times, most recently from d03855f to 8ae9a4e Compare March 13, 2026 03:30
Copy link

@griswaldbrooks griswaldbrooks left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@bgill92 is the scan mirror fix a picknik_mujoco_ros limitation or should @bkanator just mount the lidar upside-down?

@bkanator
Copy link
Author

bkanator commented Mar 17, 2026

@bgill92 is the scan mirror fix a picknik_mujoco_ros limitation or should @bkanator just mount the lidar upside-down?

do you want me to try to flip the mount body orientation to see if I can get rid of the script? I know things can get weird when I tune the quaternion since it affects both TF and beam direction so it can sometimes get in a bad state, but happy to try since it is cleaner than using the relay node. Thoughts?

--WILL TRY THIS----

@bkanator bkanator force-pushed the lidar-hangar-sim branch 3 times, most recently from 8ae9a4e to b1ca37e Compare March 17, 2026 18:02
@bkanator bkanator marked this pull request as draft March 17, 2026 18:03
@bkanator bkanator closed this Mar 17, 2026
@bkanator bkanator reopened this Mar 17, 2026
@bkanator bkanator marked this pull request as ready for review March 17, 2026 20:37
@bkanator
Copy link
Author

bkanator commented Mar 17, 2026

fix was to update the mujoco plug-in https://github.com/PickNikRobotics/moveit_pro/pull/17551, and then I removed the relay script

@bkanator bkanator marked this pull request as draft March 19, 2026 01:14
@bkanator
Copy link
Author

bkanator commented Mar 19, 2026

ok, so finally fixed the quaternion, and stopped punting it to claude, so as now to not need the extra 180 degree. The main issue being knowing that there was a -90 degree rotation in the Y-axis in the plug-in which flips the world Z from up to the forward X direction. Since the beams point along the forward X-axis now it needed another rotation about the world Z to move the beams along the x-y plane to -135 degrees where the lidar was mounted. Then had to tune the filters again .

@bkanator bkanator marked this pull request as ready for review March 19, 2026 15:01
Copy link

@griswaldbrooks griswaldbrooks left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Some small things, and can you post a video?

@bkanator
Copy link
Author

First video shows going to the small boxes and the global path planning a path that the local costmap does not allow completion of.

lidarnav_toboxes.mp4

Second video just goes towards the plane.

lidarnav_toplane.mp4

third video i made the laser scan thicker to show the scanned points better:

lidarnav_tostart.mp4

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants