System Implementation

This page documents the progress made, broken down by subsystems:

Mechanical Design and Fabrication

Chassis v0 rendered mounted on the mobility platform
  • Updates from February 15th, 2023:
    • The sensor pod chassis v0 has been designed and is under fabrication, scheduled for completion before progress review 2 on March 1st, 2023.
    • This chassis co-locates the sensors, compute, and power backup, in order to provide a portable rig for sensor data capture.
    • Insights from this v0 chassis will be used to inform the design for the next iteration of the chassis, which will be set to the dimension agreed upon with the stakeholders to have appropriate payload-bearing surfaces.
  • Updates from March 1st, 2023:
    • Procured material for AMR Frame
    • Laser-cut Base sheet
    • Began sensor mounting
    • Coordinated with MFI personnel to assist us in the fabrication of AMR Frame
  • Updates from March 22nd, 2023:
    • Fabrication of Mechanical Frame completed
    • Sensor mounts and transformations mapping sensor_frame ←→ robot_frame calculated
    • Started trade study on planning algorithms.
  • Updates from April 5th, 2023:
    • Conducting rigorous testing of SLAM packages.
    • Built testing rig to validate fiducial marker accuracy
    • Started perception work with a new model architecture called TR3D
  • Updates from May 5th, 2023:
    • Prepared system demonstration for Sping Validation Demonstration.
    • Creating an integration plan for the fall semester.
  • Updates from November 15th, 2023:
    • The designed AMR frame has been deployed on the robot.
    • System successfully demonstrated in Fall Validation Demonstration.

Lidar Mapping and Localization

NSH B-level mapped using HDL-graphSLAM on VLP16 lidar data
  • Updates from February 15th, 2023:
    • Conducted trade study to evaluate mapping algorithms.
    • Tested multiple implementations of GraphSLAM algorithms on sample rosbag files.
    • Captured data using infra test bench on a cart, to generate map v0.
  • Updates from March 1st, 2023:
    • Devised a pure LIDAR mapping stack.
    • Mapped NSH B-level with different data modalities
      • .pcd → Most likely for global localization
      • .pgm → Global planning
    • .bt → Perception and local planning 
  • Updates from March 22nd, 2023:
    • Performed mapping validation exercise
      • Compared the floorplan of NSH B-level to our generated map
  • Updates from April 5th, 2023:
    • Shifted requirements from the 3D map to 2D map
    • Generated occupancy grid-based map
    • Devised a pure lidar-based odometry mapping stack
  • Updates from May 5th, 2023:
    • Tested out graph slam on NSH level 4
    • Tested out AMCL on NSH level 4
    • Prepared a cohesive demo for SVD
  • Updates from November 15th, 2023:
    • 3D localization had problems due to networking issues.
    • Added a 2D fallback with high weightage to odometry.

Camera-based Localization using Fiducial Markers

Link to demo

  • Updates from February 15th, 2023:
    • Trade study ongoing for fiducial marker selection, with the MVP to be demonstrated at progress review 3 on March 22nd, 2023.
  • Updates from March 22nd, 2023:
    • Selected marker type: ArUco3 based on analysis of:
      • Source code availability
      • ROS package availability
      • 6DOF pose estimation output
      • Sensitivity and specificity vs. range / viewing angle
      • Pose error vs. range/viewing angle
      • Jitter in pose estimates
      • Performance vs occlusion levels
      • Computing latency
      • (STags to be used as a backup option [easier codebase])
    • Prototyped standalone detection pipeline
      using Aruco3 markers
  • Updates from April 5th, 2023:
    • ROS2 integration of Aruco3 marker detection using Intel Realsense RGB stream
      • Runs real-time for 1920×1080 @ 15Hz (dev-pc)
      • Detection callback processing time: 10-20ms (100-50Hz)
      • Reliable detections even at 3m range, and up to 80o viewing angles w.r.t. optical axis
      • Empirical L2 pose error under 1cm at a range of 1.2m
      • Self-profiles compute usage
    • Calibrated camera intrinsics using aruco3 marker board
    • Helped build test rig and captured validation bag files (using factory camera calibration)
  • Updates from May 5th, 2023:
    • Created a GUI to validate the fiducial marker system performance
    • Demonstrated the system in SVD
  • Updates from November 15th, 2023:
    • Fiducial marker subsystem was finally integrated into the docking sub-system

Motion-Planning and Controls

  • Updates from February 15th, 2023:
    • Completed trade study to select algorithms for the global planner.
    • Demonstrated single-agent planner planning optimal paths on sample octomaps.
  • Updates from March 1st, 2023:
    • Trade study to select planning algorithm
      • Tested multiple planners for shortest near-optimal sample-based planners on the city-octomap.
    • Converted NSH B level pointcloud to octomap
  • Updates from April 5th, 2023:
    • Had a meeting with Prof. Jiaoyang Li to gain clarity on how to go about the implementation
    • Started implementation of a CostMap2D ROS2 map to an intermediate representation
    • Will write a ROS2 wrapper around CBSH2-RTC – which an optimal multi-robot planner
  • Updates from May 5th, 2023:
    • Created a ROS2 plugin to interpret costmap2D to custom map representation.
    • Integrated pure pursuit control as a local controller.
    • Integrated Model Predictive Path Integral control as an alternative local controller for the robots in simulation.
    • Tested planning and controls system performance in a multi-robot scenario (for 3 robots) in different test environments in simulation.
    • Demonstrated current progress in SVD
  • Updates from November 15th, 2023:
    • A new ROS2 multi-robot planner package was developed and deployed in the testbed domain.
    • Successfully demonstrated various cases for the planner in the FVD.

Robot Infrastructure

  • Updates from February 15th, 2023:
    • Test Bench bring-up: OS, ROS, Sensor Drivers tested
    • Evaluated the available choices for running different ROS versions on both the onboard computer and the MP400 computer
    • Conducted experiments to test cross-distribution communication between ROS Humble and Foxy, and discovered that the resulting latency is close to 15ms
    • Established Developer Workflow: Documented and demonstrated the steps required to set up a development environment on both the Jetson AGX and personal devices.
  • Updates from March 1st, 2023:
    • Switched to Foxy from Humble
    • Completed robot test bench setup
      • ROS2 Foxy docker for Jetson and x86 machines
      • GPU & Display access inside docker environment
      • Sensor health monitor package
  • Updates from March 22nd, 2023:
    • Worked with Sergi to set up the UM7 IMU
    • Tested the ROS2 package for UM7
    • Calibrated the magnetometer
  • Updates from April 5th, 2023:
    • Improved the current v0 chassis.
  • Updates from May 5th, 2023:
    • Working on optimizing packages for Jetson. 
  • Updates from November 15th, 2023:
    • Fixed networking issues for ROS2 nodes on the robot by limiting them to the localhost network interface and exposing only a certain topic on wlan0 interface.

Perception

  • Updates from March 1st, 2023:
    • Conducted literature review for 3d object detection –
      • Models/Architectures:
        • Frustum PointNets / VoxelNet / PointRCNN / PointNet++
      • Datasets:
        • SUN RGB-D / ScanNet V2 / KITTI
    • Finalized Frustum PointNets with SUN RGB-D based on performance for indoor environments and computational efficiency
  • Updates from March 22nd, 2023:
    • Established pipeline for feeding data in TR3D and implemented ROS2 package for inferencing
    • Tried running different pre-trained models (Frustum P-Nets, VoteNet, TR3D) and different sensor modalities – VLP-16 and RealSense
  • Updates from April 5th, 2023:
    • Fine-tuned and ran different experiments on TR3D to reduce domain gap and improve performance
    • Worked on speed up of TR3D inference from 2 Hz to 5 Hz
    • Evaluated performance of TR3D on test dataset 
  • Updates from May 5th, 2023:
    • Conducted various real-time tests on NSH B level and 4th level.
    • Demonstrated the working perception system in SVD.
  • Updates from November 15th, 2023:
    • Integrated Velodyne lidar-based obstacle perception with the robot and the planner.
    • Successfully demonstrated in FVD.

Gazebo simulation environment

  • Updates from March 1st, 2023:
    • Built first version of Gazebo environment utilizing Testbed floor plan for scale
  • Updates from March 22nd, 2023:
    • Added robot to custom gazebo world file
    • Performed mapping using ROS SLAM Toolbox and simulated lidar
    • Generated .pgm files for simulated world
  • Updates from April 5th, 2023:
    • Building Test Workspaces
      • To test multi-agent planning a more complex environment was necessary
      • Objects can be added to constrain the environment further
  • Updates from May 5th, 2023:
    • Added 4 new simulation environments:
    • Warehouse environment
    • Race Track
    • Open Space
    • MFI Testbed environment
    • All of these environment were demonstrated in SVD
  • Updates from November 15th, 2023:
    • Upgraded and debugged simulation to spawn up to 20 robots reliably with the entire navigation stack as it would in the actual deployment.

Power distribution Board

  • Updates from March 22nd, 2023:
    • PCB Board and Schematic design done and submitted.
    • Sent email to Christine to source the required components.
  • Updates from April 5th, 2023:
    • Received the PCB
    • Have received the required components
  • Updates from May 5th, 2023:
    • Component assembled on the PCB and thoroughly tested the functionality of the PCB
  • Updates from November 15th, 2023:
    • 2 New PCBs were manufactured for the new robots.
    • In the final iteration, the PCBs were skipped and the compute and sensors were directly powered from the ports provided by the manufacturer.

Project Management

Screenshot of JIRA product backlog
  • Updates from February 15th, 2023:
    • Project management processes and tools established. Following agile methodology. See full details on protocols being followed at this link.
    • Working with MFI sponsors, testbed customer team and lego manipulation design team to finalize software and hardware interfaces.
  • Updates from March 1st, 2023:
    • Team has started effectively using JIRA to track tasks
    • Coordinated with MFI to place orders for the Neobotix MP400 robots 
    • Coordinated with Sushant and MFI to place orders for mechanical components
    • Connected the GitHub organization to JIRA
  • Updates from May 5th, 2023:
    • Working on task breakdown for the fall semester.
  • Updates from November 15th, 2023:
    • Final Integration and timeline updates.
    • Risk mitigation to ensure success.

High-level system design

System diagram of the system that was finnaly deployed can be found here