diff --git a/Dockerfile b/Dockerfile
index 24b065f..90fdee7 100644
--- a/Dockerfile
+++ b/Dockerfile
@@ -39,5 +39,18 @@ RUN $SRC/ros_from_src/build.sh
 COPY catkin.sh $SRC/ros_from_src
 RUN $SRC/ros_from_src/catkin.sh
 
+# WORKDIR $SRC/ros_from_src
+RUN mkdir -p base_ws/src
+COPY ubuntu_2404/base_repos.yaml base_ws/src
+COPY ubuntu_2404/base_git_clone.sh $SRC/ros_from_src
+# RUN ROS_CONSOLE=$ROSCONSOLE $SRC/ros_from_src/git_clone.sh
+RUN $SRC/ros_from_src/base_git_clone.sh
+
+COPY ubuntu_2404/dependencies.sh $SRC/ros_from_src/base_dependencies.sh
+RUN $SRC/ros_from_src/base_dependencies.sh
+
+COPY ubuntu_2404/base_catkin.sh $SRC/ros_from_src
+RUN $SRC/ros_from_src/base_catkin.sh
+
 WORKDIR $WS/..
 # TODO(lucasw) run tests
diff --git a/catkin.sh b/catkin.sh
index 44468d4..bbba7af 100755
--- a/catkin.sh
+++ b/catkin.sh
@@ -19,6 +19,6 @@ echo $LD_LIBRARY_PATH
 rospack list
 
 catkin build
-source devel/setup.bash
+source install/setup.bash
 rospack list
 # TODO(lucasw) run tests
diff --git a/ubuntu_2404/base_catkin.sh b/ubuntu_2404/base_catkin.sh
new file mode 100755
index 0000000..4d3256a
--- /dev/null
+++ b/ubuntu_2404/base_catkin.sh
@@ -0,0 +1,25 @@
+#!/bin/bash
+set -e
+set -x
+
+ls -l
+ls -l ros/bin
+ROS_DEST=`pwd`/ros source underlay_ws/env.sh
+
+WS=`pwd`/base_ws/src
+echo $WS
+
+cd $WS/..
+echo "#####################"
+pwd
+source ../underlay_ws/install/setup.bash
+catkin init
+catkin config --install --cmake-args -DCMAKE_BUILD_TYPE=Release -Wno-deprecated -DCATKIN_ENABLE_TESTING=False
+echo $PATH
+echo $LD_LIBRARY_PATH
+rospack list
+
+catkin build ros_comm
+source install/setup.bash
+rospack list
+# TODO(lucasw) run tests
diff --git a/ubuntu_2404/base_git_clone.sh b/ubuntu_2404/base_git_clone.sh
new file mode 100755
index 0000000..4daac20
--- /dev/null
+++ b/ubuntu_2404/base_git_clone.sh
@@ -0,0 +1,17 @@
+#!/bin/bash
+# TODO(lucasw) replace the below with submodules
+# export PATH=$PATH:/usr/local/bin
+set -e
+set -x
+
+WS=`pwd`/base_ws/src
+echo $WS
+mkdir $WS -p
+
+# TODO(lucasw) replace these git clones with vcs
+# packages that need to be cmake installed, and are ros packages in a catkin workspace
+cd $WS
+vcs import --input base_repos.yaml --retry 10
+
+# ROSCONSOLE1=${ROSCONSOLE:-https://github.com/ros-o/rosconsole}
+# git clone $ROSCONSOLE1
diff --git a/ubuntu_2404/base_repos.yaml b/ubuntu_2404/base_repos.yaml
index 5c8469e..a3a3c9a 100644
--- a/ubuntu_2404/base_repos.yaml
+++ b/ubuntu_2404/base_repos.yaml
@@ -1,678 +1,418 @@
 repositories:
-  clearpath/cpr_gazebo:
-    type: git
-    url: https://github.com/clearpathrobotics/cpr_gazebo.git
-    version: noetic-devel
-  clearpath/husky:
-    type: git
-    url: git@github.com:lucasw/husky
-    version: roslint_fixes
-  clearpath/moose:
-    type: git
-    url: git@github.com:lucasw/moose
-    version: pluginlib_hpp
-  clearpath/moose_simulator:
-    type: git
-    url: git@github.com:moose-cpr/moose_simulator.git
-    version: master
-  clearpath/warthog:
-    type: git
-    url: git@github.com:warthog-cpr/warthog
-    version: kinetic-devel
-  clearpath/warthog_simulator:
-    type: git
-    url: git@github.com:warthog-cpr/warthog_simulator.git
-    version: melodic-devel
   # extra/common_msgs:  # in underlay_ws
   #   type: git
-  #   url: git@github.com:ros/common_msgs.git
+  #   url: https://github.com/ros/common_msgs
   #   version: noetic-devel
   # extra/geometry:
   #   type: git
-  #   url: git@github.com:ros-o/geometry.git
+  #   url: https://github.com/ros-o/geometry
   #   version: obese-devel
   extra/laser_geometry:
     type: git
-    url: git@github.com:ros-o/laser_geometry.git
+    url: https://github.com/ros-o/laser_geometry
     version: obese-devel
   extra/navigation_msgs:
     type: git
-    url: git@github.com:ros-planning/navigation_msgs.git
+    url: https://github.com/ros-planning/navigation_msgs
     version: ros1
   extra/pcl_msgs:
     type: git
-    url: git@github.com:ros-perception/pcl_msgs.git
+    url: https://github.com/ros-perception/pcl_msgs
     version: noetic-devel
   extra/perception_pcl:
     type: git
-    url: git@github.com:ros-o/perception_pcl.git
+    url: https://github.com/ros-o/perception_pcl
     version: obese-devel
   extra/python_qt_binding:
     type: git
-    url: git@github.com:ros-o/python_qt_binding.git
+    url: https://github.com/ros-o/python_qt_binding
     version: obese-devel
   extra/vision_opencv:
     type: git
-    url: git@github.com:ros-perception/vision_opencv.git
+    url: https://github.com/ros-perception/vision_opencv
     version: noetic
-  greenzie/boustrophedon_planner:
-    type: git
-    url: git@github.com:lucasw/boustrophedon_planner
-    version: cpp17
-  lucasw/carbot:
-    type: git
-    url: git@github.com:lucasw/carbot
-    version: master
   lucasw/dynamic_reconfigure_tools:
     type: git
-    url: git@github.com:lucasw/dynamic_reconfigure_tools
-    version: master
-  lucasw/frei0r_image:
-    type: git
-    url: git@github.com:lucasw/frei0r_image
+    url: https://github.com/lucasw/dynamic_reconfigure_tools
     version: master
   lucasw/image_manip:
     type: git
-    url: git@github.com:lucasw/image_manip
+    url: https://github.com/lucasw/image_manip
     version: fix_zero_frame_rate
-  lucasw/joy_feedback_ros:
-    type: git
-    url: git@github.com:lucasw/joy_feedback_ros
-    version: master
   lucasw/nodelet_demo:
     type: git
-    url: git@github.com:lucasw/nodelet_demo
-    version: master
-  lucasw/popcanbot:
-    type: git
-    url: git@github.com:lucasw/popcanbot
+    url: https://github.com/lucasw/nodelet_demo
     version: master
   lucasw/ros1_lifecycle:
     type: git
-    url: git@github.com:lucasw/ros1_lifecycle
+    url: https://github.com/lucasw/ros1_lifecycle
     version: misc_fixes
   lucasw/ros_example:
     type: git
-    url: git@github.com:lucasw/ros_example
+    url: https://github.com/lucasw/ros_example
     version: main
   lucasw/ros_system_monitor:
     type: git
-    url: git@github.com:lucasw/ros_system_monitor
+    url: https://github.com/lucasw/ros_system_monitor
     version: chrony_monitor
-  lucasw/rqt_file_dialog:
-    type: git
-    url: git@github.com:lucasw/rqt_file_dialog
-    version: master
-  lucasw/rqt_tf_echo:
-    type: git
-    url: git@github.com:lucasw/rqt_tf_echo.git
-    version: master
-  lucasw/rqt_topic_display:
-    type: git
-    url: git@github.com:lucasw/rqt_topic_display.git
-    version: master
-  lucasw/rviz_camera_stream:
-    type: git
-    url: git@github.com:lucasw/rviz_camera_stream
-    version: noetic-devel
-  lucasw/rviz_interactive_tf:
-    type: git
-    url: git@github.com:lucasw/rviz_interactive_tf
-    version: master
-  lucasw/rviz_lighting:
-    type: git
-    url: git@github.com:lucasw/rviz_lighting
-    version: cpp17
-  lucasw/rviz_ortho_view_controller:
-    type: git
-    url: git@github.com:lucasw/rviz_ortho_view_controller.git
-    version: master
   lucasw/screengrab_ros:
     type: git
-    url: git@github.com:lucasw/screengrab_ros
+    url: https://github.com/lucasw/screengrab_ros
     version: master
   lucasw/signal_generator:
     type: git
-    url: git@github.com:lucasw/signal_generator
-    version: master
-  lucasw/simple_sim_ros:
-    type: git
-    url: git@github.com:lucasw/simple_sim_ros
+    url: https://github.com/lucasw/signal_generator
     version: master
   lucasw/tf_demo:
     type: git
-    url: git@github.com:lucasw/tf_demo
+    url: https://github.com/lucasw/tf_demo
     version: old_tf_to_new_tf
   lucasw/timer_test:
     type: git
-    url: git@github.com:lucasw/timer_test
+    url: https://github.com/lucasw/timer_test
     version: master
   lucasw/topic_state:
     type: git
-    url: git@github.com:lucasw/topic_state
+    url: https://github.com/lucasw/topic_state
     version: master
   lucasw/transform_point_cloud:
     type: git
-    url: git@github.com:lucasw/transform_point_cloud.git
+    url: https://github.com/lucasw/transform_point_cloud
     version: master
   lucasw/v4l2ucp:
     type: git
-    url: git@github.com:lucasw/v4l2ucp
+    url: https://github.com/lucasw/v4l2ucp
     version: master
   lucasw/vimjay:
     type: git
-    url: git@github.com:lucasw/vimjay
+    url: https://github.com/lucasw/vimjay
     version: eliminate_build_warnings
   opencv_apps:
     type: git
-    # url: git@github.com:ros-perception/opencv_apps.git
-    url: git@github.com:muellerbernd/opencv_apps
+    # url: https://github.com/ros-perception/opencv_apps
+    url: https://github.com/muellerbernd/opencv_apps
     version: indigo
   other/PlotJuggler:
     type: git
-    url: git@github.com:facontidavide/PlotJuggler.git
+    url: https://github.com/facontidavide/PlotJuggler
     version: main
-  other/anybotics/elevation_mapping:
-    type: git
-    url: git@github.com:ANYbotics/elevation_mapping.git
-    version: master
-  other/anybotics/kindr:
-    type: git
-    url: git@github.com:ANYbotics/kindr
-    version: master
-  other/anybotics/kindr_ros:
-    type: git
-    url: git@github.com:lucasw/kindr_ros
-    version: cpp17
-  other/anybotics/message_logger:
-    type: git
-    url: git@github.com:lucasw/message_logger
-    version: line_endings
-  other/anybotics/point_cloud_io:
-    type: git
-    url: git@github.com:ANYbotics/point_cloud_io
-    version: master
   other/apriltag_ros:
     type: git
-    url: git@github.com:AprilRobotics/apriltag_ros.git
+    url: https://github.com/AprilRobotics/apriltag_ros
     version: master
   other/camera_throttler_nodelets:
     type: git
-    url: git@github.com:lucasw/camera_throttler_nodelets.git
+    url: https://github.com/lucasw/camera_throttler_nodelets
     version: noetic_aggregated
   other/catkin_virtualenv:
     type: git
-    url: git@github.com:locusrobotics/catkin_virtualenv.git
+    url: https://github.com/locusrobotics/catkin_virtualenv
     version: master
   other/ddynamic_reconfigure:
     type: git
-    url: git@github.com:ros-o/ddynamic_reconfigure
+    url: https://github.com/ros-o/ddynamic_reconfigure
     version: obese-devel
-  other/depthai-ros-examples:
-    type: git
-    url: git@github.com:luxonis/depthai-ros-examples.git
-    version: main
   other/euslisp-release:
     type: git
-    url: git@github.com:tork-a/euslisp-release.git
+    url: https://github.com/tork-a/euslisp-release
     version: release/melodic/euslisp
-  other/ffmpeg_image_transport:
-    type: git
-    url: git@github.com:lucasw/ffmpeg_image_transport
-    version: noetic_aggregated
-  other/ffmpeg_image_transport_msgs:
-    type: git
-    url: git@github.com:daniilidis-group/ffmpeg_image_transport_msgs.git
-    version: master
   other/fiducials:
     type: git
-    url: git@github.com:lucasw/fiducials
+    url: https://github.com/lucasw/fiducials
     version: cmake_vision_msgs
-  other/find-object:
-    type: git
-    url: git@github.com:lucasw/find-object.git
-    version: master
-  other/fuse:
-    type: git
-    url: git@github.com:lucasw/fuse
-    version: cpp17
   # other/geneus:  # in underlay_ws
   #   type: git
-  #   url: git@github.com:jsk-ros-pkg/geneus.git
+  #   url: https://github.com/jsk-ros-pkg/geneus
   #   version: master
-  other/graph_rviz_plugin:
-    type: git
-    url: git@github.com:lucasw/graph_rviz_plugin
-    version: pluginlib_hpp
-  other/hector_slam:
-    type: git
-    url: git@github.com:lucasw/hector_slam
-    version: boost_placeholders
   other/jsk_common:
     type: git
-    url: git@github.com:lucasw/jsk_common
+    url: https://github.com/lucasw/jsk_common
     version: video_to_bag_features
   other/jsk_common_msgs:
     type: git
-    url: git@github.com:lucasw/jsk_common_msgs
+    url: https://github.com/lucasw/jsk_common_msgs
     version: master
   other/jsk_recognition:
     type: git
-    url: git@github.com:lucasw/jsk_recognition
+    url: https://github.com/lucasw/jsk_recognition
     version: pcl_vtk_isfinite
   other/jsk_roseus:
     type: git
-    url: git@github.com:jsk-ros-pkg/jsk_roseus.git
+    url: https://github.com/jsk-ros-pkg/jsk_roseus
     version: master
-  other/jsk_visualization:
-    type: git
-    url: git@github.com:lucasw/jsk_visualization
-    version: boost_placeholders
   other/libnabo:
     type: git
-    url: git@github.com:ethz-asl/libnabo
+    url: https://github.com/ethz-asl/libnabo
     version: master
   other/lvr2:
     type: git
-    url: git@github.com:uos/lvr2
+    url: https://github.com/uos/lvr2
     version: humble
   other/marti_messages:
     type: git
-    url: git@github.com:swri-robotics/marti_messages.git
+    url: https://github.com/swri-robotics/marti_messages
     version: master
-  other/mavros:
-    type: git
-    url: git@github.com:lucasw/mavros
-    version: master
-  other/mesh_tools:
-    type: git
-    url: git@github.com:lucasw/mesh_tools
-    version: generate_mesh_geometry
   other/message_filters:
     type: git
-    url: git@github.com:fkie/message_filters.git
+    url: https://github.com/fkie/message_filters
     version: master
   other/nmea_navsat_driver:
     type: git
-    url: git@github.com:ros-drivers/nmea_navsat_driver.git
+    url: https://github.com/ros-drivers/nmea_navsat_driver
     version: master
   other/nodelet_rosbag:
     type: git
-    url: git@github.com:lucasw/nodelet_rosbag
+    url: https://github.com/lucasw/nodelet_rosbag
     version: pluginlib_hpp
-  other/octomap_mapping:
-    type: git
-    url: git@github.com:octomap/octomap_mapping.git
-    version: kinetic-devel
-  other/octomap_ros:
-    type: git
-    url: git@github.com:octomap/octomap_ros
-    version: melodic-devel
-  other/openni2_camera:
-    type: git
-    url: git@github.com:lucasw/openni2_camera.git
-    version: subprocess_wtf_python3_7
   other/pal_statistics:
     type: git
-    url: git@github.com:pal-robotics/pal_statistics.git
+    url: https://github.com/pal-robotics/pal_statistics
     version: kinetic-devel
-  other/people:
-    type: git
-    url: git@github.com:wg-perception/people.git
-    version: melodic
   other/pid:
     type: git
-    url: git@github.com:lucasw/pid.git
+    url: https://github.com/lucasw/pid
     version: boost_placeholders
   other/plotjuggler-ros-plugins:
     type: git
-    url: git@github.com:PlotJuggler/plotjuggler-ros-plugins.git
+    url: https://github.com/PlotJuggler/plotjuggler-ros-plugins
     version: main
   other/plotjuggler_msgs:
     type: git
-    url: git@github.com:PlotJuggler/plotjuggler_msgs.git
+    url: https://github.com/PlotJuggler/plotjuggler_msgs
     version: main
   other/point_cloud_converter:
     type: git
-    url: git@github.com:pal-robotics-forks/point_cloud_converter.git
+    url: https://github.com/pal-robotics-forks/point_cloud_converter
     version: hydro-devel
   other/ros_control_boilerplate:
     type: git
-    url: git@github.com:lucasw/ros_control_boilerplate
+    url: https://github.com/lucasw/ros_control_boilerplate
     version: cpp17
   other/ros_numpy:
     type: git
-    url: git@github.com:lucasw/ros_numpy.git
+    url: https://github.com/lucasw/ros_numpy
     version: collections_abc
   other/ros_rtsp:
     type: git
-    url: git@github.com:lucasw/ros_rtsp
+    url: https://github.com/lucasw/ros_rtsp
     version: pluginlib_hpp
   other/ros_type_introspection:
     type: git
-    url: git@github.com:lucasw/ros_type_introspection.git
+    url: https://github.com/lucasw/ros_type_introspection
     version: build_2204
   other/rosbag_snapshot:
     type: git
-    url: git@github.com:ros/rosbag_snapshot.git
+    url: https://github.com/ros/rosbag_snapshot
     version: main
-  other/rosboard:
-    type: git
-    url: git@github.com:lucasw/rosboard.git
-    version: patch-1
-  other/rosfmt:
-    type: git
-    url: git@github.com:lucasw/rosfmt
-    version: build_2204
-  other/rosmon:
-    type: git
-    url: git@github.com:lucasw/rosmon
-    version: build_2204
-  other/rosshow:
-    type: git
-    url: git@github.com:dheera/rosshow
-    version: main
-  other/rqt_ez_publisher:
-    type: git
-    url: git@github.com:lucasw/rqt_ez_publisher
-    version: ubuntu2210
-  other/rtabmap:
-    type: git
-    url: git@github.com:introlab/rtabmap.git
-    version: master
-  other/rtabmap_ros:
-    type: git
-    url: git@github.com:introlab/rtabmap_ros
-    version: master
   other/static_transform_mux:
     type: git
-    url: git@github.com:tradr-project/static_transform_mux.git
+    url: https://github.com/tradr-project/static_transform_mux
     version: master
   other/tf2_2d:
     type: git
-    url: git@github.com:locusrobotics/tf2_2d.git
+    url: https://github.com/locusrobotics/tf2_2d
     version: devel
-  other/turtlebot:
-    type: git
-    url: git@github.com:turtlebot/turtlebot
-    version: melodic
-  other/vdb/openvdb:
-    type: git
-    url: git@github.com:AcademySoftwareFoundation/openvdb.git
-    version: master
-  other/vdb/vdb_mapping:
-    type: git
-    url: git@github.com:lucasw/vdb_mapping
-    version: ubuntu_2404
-  other/vdb/vdb_mapping_ros:
-    type: git
-    url: git@github.com:lucasw/vdb_mapping_ros
-    version: rolling_window
   other/wu_ros_tools:
     type: git
-    url: git@github.com:lucasw/wu_ros_tools
+    url: https://github.com/lucasw/wu_ros_tools
     version: noetic
-  ros/async_web_server_cpp:
-    type: git
-    url: git@github.com:lucasw/async_web_server_cpp.git
-    version: ros1-develop
   ros/audio_common:
     type: git
-    url: git@github.com:ros-drivers/audio_common.git
+    url: https://github.com/ros-drivers/audio_common
     version: master
   ros/camera_info_manager_py:
     type: git
-    url: git@github.com:lucasw/camera_info_manager_py
+    url: https://github.com/lucasw/camera_info_manager_py
     version: noetic-devel
   ros/common_tutorials:
     type: git
-    url: git@github.com:lucasw/common_tutorials.git
+    url: https://github.com/lucasw/common_tutorials
     version: boost_placeholders
   ros/control_msgs:
     type: git
-    url: git@github.com:ros-controls/control_msgs.git
+    url: https://github.com/ros-controls/control_msgs
     version: kinetic-devel
   ros/ddynamic_reconfigure_python:
     type: git
-    url: git@github.com:pal-robotics/ddynamic_reconfigure_python
+    url: https://github.com/pal-robotics/ddynamic_reconfigure_python
     version: master
   ros/diagnostics:
     type: git
-    url: git@github.com:ros/diagnostics.git
+    url: https://github.com/ros/diagnostics
     version: noetic-devel
   ros/dynamic_reconfigure:
     type: git
-    url: git@github.com:lucasw/dynamic_reconfigure
+    url: https://github.com/lucasw/dynamic_reconfigure
     version: init_default_values
   ros/filters:
     type: git
-    url: git@github.com:ros/filters.git
+    url: https://github.com/ros/filters
     version: noetic-devel
   ros/four_wheel_steering_msgs:
     type: git
-    url: git@github.com:ros-drivers/four_wheel_steering_msgs.git
+    url: https://github.com/ros-drivers/four_wheel_steering_msgs
     version: master
-  ros/gazebo_ros_demos:
-    type: git
-    url: git@github.com:lucasw/gazebo_ros_demos
-    version: noetic-devel
-  ros/gazebo_ros_pkgs:
-    type: git
-    url: git@github.com:lucasw/gazebo_ros_pkgs
-    version: noetic_debug_plugins
   ros/geographic_info:
     type: git
-    url: git@github.com:ros-geographic-info/geographic_info.git
+    url: https://github.com/ros-geographic-info/geographic_info
     version: master
   # ros/geometry2:  # in underlay_ws
   #   type: git
-  #   url: git@github.com:lucasw/geometry2
+  #   url: https://github.com/lucasw/geometry2
   #   version: noetic_aggregated
   ros/grid_map:
     type: git
-    url: git@github.com:lucasw/grid_map
+    url: https://github.com/lucasw/grid_map
     version: tbb_2021
   ros/image_common:
     type: git
-    url: git@github.com:lucasw/image_common
+    url: https://github.com/lucasw/image_common
     version: ubuntu_2210
   ros/image_pipeline:
     type: git
-    url: git@github.com:lucasw/image_pipeline
+    url: https://github.com/lucasw/image_pipeline
     version: rgb_in_depth_range
   ros/image_transport_plugins:
     type: git
-    url: git@github.com:lucasw/image_transport_plugins
+    url: https://github.com/lucasw/image_transport_plugins
     version: enable_pub
-  ros/interactive_markers:
-    type: git
-    url: git@github.com:ros-visualization/interactive_markers.git
-    version: noetic-devel
   ros/joint_state_publisher:
     type: git
-    url: git@github.com:lucasw/joint_state_publisher
+    url: https://github.com/lucasw/joint_state_publisher
     version: noetic_aggregated
   ros/joystick_drivers:
     type: git
-    url: git@github.com:lucasw/joystick_drivers
+    url: https://github.com/lucasw/joystick_drivers
     version: warn_not_error_if_no_joy
   ros/laser_assembler:
     type: git
-    url: git@github.com:lucasw/laser_assembler
+    url: https://github.com/lucasw/laser_assembler
     version: noetic-devel
   ros/libuvc_ros:
     type: git
-    url: git@github.com:lucasw/libuvc_ros.git
+    url: https://github.com/lucasw/libuvc_ros
     version: libuvc_0_0_7
   ros/media_export:
     type: git
-    url: git@github.com:ros/media_export.git
+    url: https://github.com/ros/media_export
     version: kinetic-devel
   ros/navigation:
     type: git
-    url: git@github.com:lucasw/navigation
+    url: https://github.com/lucasw/navigation
     version: lucasw_debug
   ros/nmea_msgs:
     type: git
-    url: git@github.com:ros-drivers/nmea_msgs
+    url: https://github.com/ros-drivers/nmea_msgs
     version: master
   ros/nodelet_core:
     type: git
-    url: git@github.com:lucasw/nodelet_core.git
+    url: https://github.com/lucasw/nodelet_core
     version: throttle_looping_time
   ros/octomap_msgs:
     type: git
-    url: git@github.com:OctoMap/octomap_msgs.git
+    url: https://github.com/OctoMap/octomap_msgs
     version: melodic-devel
   ros/realtime_tools:
     type: git
-    url: git@github.com:ros-controls/realtime_tools.git
+    url: https://github.com/ros-controls/realtime_tools
     version: noetic-devel
-  ros/robot_localization:
-    type: git
-    url: git@github.com:lucasw/robot_localization
-    version: boost_placeholders_cpp17
   ros/robot_state_publisher:
     type: git
-    url: git@github.com:lucasw/robot_state_publisher
+    url: https://github.com/lucasw/robot_state_publisher
     version: robot_state_function
   ros/ros_comm:  # custom overlay with logging mods
     type: git
-    url: git@github.com:lucasw/ros_comm
+    url: https://github.com/lucasw/ros_comm
     version: salsa_noetic_aggregated
   ros/ros_control:
     type: git
-    url: git@github.com:lucasw/ros_control
+    url: https://github.com/lucasw/ros_control
     version: acceleration_limits
   ros/ros_controllers:
     type: git
-    url: git@github.com:lucasw/ros_controllers
+    url: https://github.com/lucasw/ros_controllers
     version: avoid_no_trajectory_defined
   ros/ros_tutorials:
     type: git
-    url: git@github.com:lucasw/ros_tutorials.git
+    url: https://github.com/lucasw/ros_tutorials
     version: boost_placeholders
   ros/rosconsole:  # lucasw logging mods
     type: git
-    url: git@github.com:lucasw/rosconsole
+    url: https://github.com/lucasw/rosconsole
     version: ubuntu_2210
   ros/roscpp_core:  # lucasw fixes
     type: git
-    url: git@github.com:lucasw/roscpp_core
+    url: https://github.com/lucasw/roscpp_core
     version: duration_out_of_dual_range
   ros/rospack:  # debian patches
     type: git
-    url: git@github.com:lucasw/rospack
+    url: https://github.com/lucasw/rospack
     version: salsa
   ros/rqt:
     type: git
-    url: git@github.com:lucasw/rqt
+    url: https://github.com/lucasw/rqt
     version: ubuntu_2210
-  ros/rqt_bag:
-    type: git
-    url: git@github.com:lucasw/rqt_bag
-    version: build_2204
-  ros/rqt_console:
-    type: git
-    url: git@github.com:ros-visualization/rqt_console.git
-    version: master
-  ros/rqt_graph:
-    type: git
-    url: git@github.com:ros-visualization/rqt_graph.git
-    version: master
-  ros/rqt_logger_level:
-    type: git
-    url: git@github.com:ros-visualization/rqt_logger_level.git
-    version: master
-  ros/rqt_plot:
-    type: git
-    url: git@github.com:ros-visualization/rqt_plot.git
-    version: master
-  ros/rqt_reconfigure:
-    type: git
-    url: https://github.com/ros-visualization/rqt_reconfigure
-    version: master
-  ros/rqt_robot_monitor:
-    type: git
-    url: git@github.com:ros-visualization/rqt_robot_monitor.git
-    version: ros1
-  ros/rqt_robot_steering:
-    type: git
-    url: git@github.com:lucasw/rqt_robot_steering.git
-    version: python310
-  ros/rqt_tf_tree:
-    type: git
-    url: git@github.com:ros-visualization/rqt_tf_tree.git
-    version: master
-  ros/rviz:
-    type: git
-    url: git@github.com:lucasw/rviz.git
-    version: misc_fixes
   ros/teleop_twist_joy:
     type: git
-    url: git@github.com:lucasw/teleop_twist_joy
+    url: https://github.com/lucasw/teleop_twist_joy
     version: cmp0115_cpp_extension
   ros/teleop_twist_keyboard:
     type: git
-    url: git@github.com:ros-teleop/teleop_twist_keyboard.git
+    url: https://github.com/ros-teleop/teleop_twist_keyboard
     version: master
   ros/twist_mux:
     type: git
-    url: git@github.com:lucasw/twist_mux
+    url: https://github.com/lucasw/twist_mux
     version: ubuntu2210
   ros/twist_mux_msgs:
     type: git
-    url: git@github.com:ros-teleop/twist_mux_msgs
+    url: https://github.com/ros-teleop/twist_mux_msgs
     version: melodic-devel
   ros/unique_identifier:
     type: git
-    url: git@github.com:ros-geographic-info/unique_identifier.git
+    url: https://github.com/ros-geographic-info/unique_identifier
     version: master
   ros/urdf_geometry_parser:
     type: git
-    url: git@github.com:ros-controls/urdf_geometry_parser.git
+    url: https://github.com/ros-controls/urdf_geometry_parser
     version: kinetic-devel
   ros/urdf_parser_py:
     type: git
-    url: git@github.com:ros/urdf_parser_py.git
+    url: https://github.com/ros/urdf_parser_py
     version: melodic-devel
   ros/usb_cam:
     type: git
-    url: git@github.com:ros-drivers/usb_cam.git
+    url: https://github.com/ros-drivers/usb_cam
     version: develop
   ros/video_stream_opencv:
     type: git
-    url: git@github.com:lucasw/video_stream_opencv
+    url: https://github.com/lucasw/video_stream_opencv
     version: build_2204
   ros/view_controller_msgs:
     type: git
-    url: git@github.com:ros-visualization/view_controller_msgs.git
+    url: https://github.com/ros-visualization/view_controller_msgs
     version: lunar-devel
   ros/vision_msgs:
     type: git
-    url: git@github.com:ros-perception/vision_msgs.git
+    url: https://github.com/ros-perception/vision_msgs
     version: noetic-devel
   ros/web_video_server:
     type: git
-    url: git@github.com:lucasw/web_video_server
+    url: https://github.com/lucasw/web_video_server
     version: boost_placeholders
   ros/xacro:
     type: git
-    url: git@github.com:lucasw/xacro.git
+    url: https://github.com/lucasw/xacro
     version: cleanup_roslint
   roso/control_toolbox:
     type: git
-    url: git@github.com:ros-o/control_toolbox
+    url: https://github.com/ros-o/control_toolbox
     version: obese-devel
   roso/qt_gui_core:
     type: git
-    url: git@github.com:lucasw/qt_gui_core
+    url: https://github.com/lucasw/qt_gui_core
     version: ubuntu_2210
   roso/rosparam_shortcuts:
     type: git
-    url: git@github.com:lucasw/rosparam_shortcuts
+    url: https://github.com/lucasw/rosparam_shortcuts
     version: cleanup_lint
-  roso/rqt_image_view:
-    type: git
-    url: git@github.com:lucasw/rqt_image_view
-    version: detection2d_image_view
diff --git a/ubuntu_2404/dependencies.sh b/ubuntu_2404/dependencies.sh
new file mode 100755
index 0000000..11eb683
--- /dev/null
+++ b/ubuntu_2404/dependencies.sh
@@ -0,0 +1,3 @@
+#!/bin/bash
+
+apt-get install -yq libb64-dev libboost-iostreams-dev libboost-test-dev libboost-timer-dev libcgal-dev libgdal-dev libopencv-dev liboctomap-dev libpcl-dev libvtk9-dev sip-dev
diff --git a/ubuntu_2404/extra_repos.yaml b/ubuntu_2404/extra_repos.yaml
new file mode 100644
index 0000000..5c8469e
--- /dev/null
+++ b/ubuntu_2404/extra_repos.yaml
@@ -0,0 +1,678 @@
+repositories:
+  clearpath/cpr_gazebo:
+    type: git
+    url: https://github.com/clearpathrobotics/cpr_gazebo.git
+    version: noetic-devel
+  clearpath/husky:
+    type: git
+    url: git@github.com:lucasw/husky
+    version: roslint_fixes
+  clearpath/moose:
+    type: git
+    url: git@github.com:lucasw/moose
+    version: pluginlib_hpp
+  clearpath/moose_simulator:
+    type: git
+    url: git@github.com:moose-cpr/moose_simulator.git
+    version: master
+  clearpath/warthog:
+    type: git
+    url: git@github.com:warthog-cpr/warthog
+    version: kinetic-devel
+  clearpath/warthog_simulator:
+    type: git
+    url: git@github.com:warthog-cpr/warthog_simulator.git
+    version: melodic-devel
+  # extra/common_msgs:  # in underlay_ws
+  #   type: git
+  #   url: git@github.com:ros/common_msgs.git
+  #   version: noetic-devel
+  # extra/geometry:
+  #   type: git
+  #   url: git@github.com:ros-o/geometry.git
+  #   version: obese-devel
+  extra/laser_geometry:
+    type: git
+    url: git@github.com:ros-o/laser_geometry.git
+    version: obese-devel
+  extra/navigation_msgs:
+    type: git
+    url: git@github.com:ros-planning/navigation_msgs.git
+    version: ros1
+  extra/pcl_msgs:
+    type: git
+    url: git@github.com:ros-perception/pcl_msgs.git
+    version: noetic-devel
+  extra/perception_pcl:
+    type: git
+    url: git@github.com:ros-o/perception_pcl.git
+    version: obese-devel
+  extra/python_qt_binding:
+    type: git
+    url: git@github.com:ros-o/python_qt_binding.git
+    version: obese-devel
+  extra/vision_opencv:
+    type: git
+    url: git@github.com:ros-perception/vision_opencv.git
+    version: noetic
+  greenzie/boustrophedon_planner:
+    type: git
+    url: git@github.com:lucasw/boustrophedon_planner
+    version: cpp17
+  lucasw/carbot:
+    type: git
+    url: git@github.com:lucasw/carbot
+    version: master
+  lucasw/dynamic_reconfigure_tools:
+    type: git
+    url: git@github.com:lucasw/dynamic_reconfigure_tools
+    version: master
+  lucasw/frei0r_image:
+    type: git
+    url: git@github.com:lucasw/frei0r_image
+    version: master
+  lucasw/image_manip:
+    type: git
+    url: git@github.com:lucasw/image_manip
+    version: fix_zero_frame_rate
+  lucasw/joy_feedback_ros:
+    type: git
+    url: git@github.com:lucasw/joy_feedback_ros
+    version: master
+  lucasw/nodelet_demo:
+    type: git
+    url: git@github.com:lucasw/nodelet_demo
+    version: master
+  lucasw/popcanbot:
+    type: git
+    url: git@github.com:lucasw/popcanbot
+    version: master
+  lucasw/ros1_lifecycle:
+    type: git
+    url: git@github.com:lucasw/ros1_lifecycle
+    version: misc_fixes
+  lucasw/ros_example:
+    type: git
+    url: git@github.com:lucasw/ros_example
+    version: main
+  lucasw/ros_system_monitor:
+    type: git
+    url: git@github.com:lucasw/ros_system_monitor
+    version: chrony_monitor
+  lucasw/rqt_file_dialog:
+    type: git
+    url: git@github.com:lucasw/rqt_file_dialog
+    version: master
+  lucasw/rqt_tf_echo:
+    type: git
+    url: git@github.com:lucasw/rqt_tf_echo.git
+    version: master
+  lucasw/rqt_topic_display:
+    type: git
+    url: git@github.com:lucasw/rqt_topic_display.git
+    version: master
+  lucasw/rviz_camera_stream:
+    type: git
+    url: git@github.com:lucasw/rviz_camera_stream
+    version: noetic-devel
+  lucasw/rviz_interactive_tf:
+    type: git
+    url: git@github.com:lucasw/rviz_interactive_tf
+    version: master
+  lucasw/rviz_lighting:
+    type: git
+    url: git@github.com:lucasw/rviz_lighting
+    version: cpp17
+  lucasw/rviz_ortho_view_controller:
+    type: git
+    url: git@github.com:lucasw/rviz_ortho_view_controller.git
+    version: master
+  lucasw/screengrab_ros:
+    type: git
+    url: git@github.com:lucasw/screengrab_ros
+    version: master
+  lucasw/signal_generator:
+    type: git
+    url: git@github.com:lucasw/signal_generator
+    version: master
+  lucasw/simple_sim_ros:
+    type: git
+    url: git@github.com:lucasw/simple_sim_ros
+    version: master
+  lucasw/tf_demo:
+    type: git
+    url: git@github.com:lucasw/tf_demo
+    version: old_tf_to_new_tf
+  lucasw/timer_test:
+    type: git
+    url: git@github.com:lucasw/timer_test
+    version: master
+  lucasw/topic_state:
+    type: git
+    url: git@github.com:lucasw/topic_state
+    version: master
+  lucasw/transform_point_cloud:
+    type: git
+    url: git@github.com:lucasw/transform_point_cloud.git
+    version: master
+  lucasw/v4l2ucp:
+    type: git
+    url: git@github.com:lucasw/v4l2ucp
+    version: master
+  lucasw/vimjay:
+    type: git
+    url: git@github.com:lucasw/vimjay
+    version: eliminate_build_warnings
+  opencv_apps:
+    type: git
+    # url: git@github.com:ros-perception/opencv_apps.git
+    url: git@github.com:muellerbernd/opencv_apps
+    version: indigo
+  other/PlotJuggler:
+    type: git
+    url: git@github.com:facontidavide/PlotJuggler.git
+    version: main
+  other/anybotics/elevation_mapping:
+    type: git
+    url: git@github.com:ANYbotics/elevation_mapping.git
+    version: master
+  other/anybotics/kindr:
+    type: git
+    url: git@github.com:ANYbotics/kindr
+    version: master
+  other/anybotics/kindr_ros:
+    type: git
+    url: git@github.com:lucasw/kindr_ros
+    version: cpp17
+  other/anybotics/message_logger:
+    type: git
+    url: git@github.com:lucasw/message_logger
+    version: line_endings
+  other/anybotics/point_cloud_io:
+    type: git
+    url: git@github.com:ANYbotics/point_cloud_io
+    version: master
+  other/apriltag_ros:
+    type: git
+    url: git@github.com:AprilRobotics/apriltag_ros.git
+    version: master
+  other/camera_throttler_nodelets:
+    type: git
+    url: git@github.com:lucasw/camera_throttler_nodelets.git
+    version: noetic_aggregated
+  other/catkin_virtualenv:
+    type: git
+    url: git@github.com:locusrobotics/catkin_virtualenv.git
+    version: master
+  other/ddynamic_reconfigure:
+    type: git
+    url: git@github.com:ros-o/ddynamic_reconfigure
+    version: obese-devel
+  other/depthai-ros-examples:
+    type: git
+    url: git@github.com:luxonis/depthai-ros-examples.git
+    version: main
+  other/euslisp-release:
+    type: git
+    url: git@github.com:tork-a/euslisp-release.git
+    version: release/melodic/euslisp
+  other/ffmpeg_image_transport:
+    type: git
+    url: git@github.com:lucasw/ffmpeg_image_transport
+    version: noetic_aggregated
+  other/ffmpeg_image_transport_msgs:
+    type: git
+    url: git@github.com:daniilidis-group/ffmpeg_image_transport_msgs.git
+    version: master
+  other/fiducials:
+    type: git
+    url: git@github.com:lucasw/fiducials
+    version: cmake_vision_msgs
+  other/find-object:
+    type: git
+    url: git@github.com:lucasw/find-object.git
+    version: master
+  other/fuse:
+    type: git
+    url: git@github.com:lucasw/fuse
+    version: cpp17
+  # other/geneus:  # in underlay_ws
+  #   type: git
+  #   url: git@github.com:jsk-ros-pkg/geneus.git
+  #   version: master
+  other/graph_rviz_plugin:
+    type: git
+    url: git@github.com:lucasw/graph_rviz_plugin
+    version: pluginlib_hpp
+  other/hector_slam:
+    type: git
+    url: git@github.com:lucasw/hector_slam
+    version: boost_placeholders
+  other/jsk_common:
+    type: git
+    url: git@github.com:lucasw/jsk_common
+    version: video_to_bag_features
+  other/jsk_common_msgs:
+    type: git
+    url: git@github.com:lucasw/jsk_common_msgs
+    version: master
+  other/jsk_recognition:
+    type: git
+    url: git@github.com:lucasw/jsk_recognition
+    version: pcl_vtk_isfinite
+  other/jsk_roseus:
+    type: git
+    url: git@github.com:jsk-ros-pkg/jsk_roseus.git
+    version: master
+  other/jsk_visualization:
+    type: git
+    url: git@github.com:lucasw/jsk_visualization
+    version: boost_placeholders
+  other/libnabo:
+    type: git
+    url: git@github.com:ethz-asl/libnabo
+    version: master
+  other/lvr2:
+    type: git
+    url: git@github.com:uos/lvr2
+    version: humble
+  other/marti_messages:
+    type: git
+    url: git@github.com:swri-robotics/marti_messages.git
+    version: master
+  other/mavros:
+    type: git
+    url: git@github.com:lucasw/mavros
+    version: master
+  other/mesh_tools:
+    type: git
+    url: git@github.com:lucasw/mesh_tools
+    version: generate_mesh_geometry
+  other/message_filters:
+    type: git
+    url: git@github.com:fkie/message_filters.git
+    version: master
+  other/nmea_navsat_driver:
+    type: git
+    url: git@github.com:ros-drivers/nmea_navsat_driver.git
+    version: master
+  other/nodelet_rosbag:
+    type: git
+    url: git@github.com:lucasw/nodelet_rosbag
+    version: pluginlib_hpp
+  other/octomap_mapping:
+    type: git
+    url: git@github.com:octomap/octomap_mapping.git
+    version: kinetic-devel
+  other/octomap_ros:
+    type: git
+    url: git@github.com:octomap/octomap_ros
+    version: melodic-devel
+  other/openni2_camera:
+    type: git
+    url: git@github.com:lucasw/openni2_camera.git
+    version: subprocess_wtf_python3_7
+  other/pal_statistics:
+    type: git
+    url: git@github.com:pal-robotics/pal_statistics.git
+    version: kinetic-devel
+  other/people:
+    type: git
+    url: git@github.com:wg-perception/people.git
+    version: melodic
+  other/pid:
+    type: git
+    url: git@github.com:lucasw/pid.git
+    version: boost_placeholders
+  other/plotjuggler-ros-plugins:
+    type: git
+    url: git@github.com:PlotJuggler/plotjuggler-ros-plugins.git
+    version: main
+  other/plotjuggler_msgs:
+    type: git
+    url: git@github.com:PlotJuggler/plotjuggler_msgs.git
+    version: main
+  other/point_cloud_converter:
+    type: git
+    url: git@github.com:pal-robotics-forks/point_cloud_converter.git
+    version: hydro-devel
+  other/ros_control_boilerplate:
+    type: git
+    url: git@github.com:lucasw/ros_control_boilerplate
+    version: cpp17
+  other/ros_numpy:
+    type: git
+    url: git@github.com:lucasw/ros_numpy.git
+    version: collections_abc
+  other/ros_rtsp:
+    type: git
+    url: git@github.com:lucasw/ros_rtsp
+    version: pluginlib_hpp
+  other/ros_type_introspection:
+    type: git
+    url: git@github.com:lucasw/ros_type_introspection.git
+    version: build_2204
+  other/rosbag_snapshot:
+    type: git
+    url: git@github.com:ros/rosbag_snapshot.git
+    version: main
+  other/rosboard:
+    type: git
+    url: git@github.com:lucasw/rosboard.git
+    version: patch-1
+  other/rosfmt:
+    type: git
+    url: git@github.com:lucasw/rosfmt
+    version: build_2204
+  other/rosmon:
+    type: git
+    url: git@github.com:lucasw/rosmon
+    version: build_2204
+  other/rosshow:
+    type: git
+    url: git@github.com:dheera/rosshow
+    version: main
+  other/rqt_ez_publisher:
+    type: git
+    url: git@github.com:lucasw/rqt_ez_publisher
+    version: ubuntu2210
+  other/rtabmap:
+    type: git
+    url: git@github.com:introlab/rtabmap.git
+    version: master
+  other/rtabmap_ros:
+    type: git
+    url: git@github.com:introlab/rtabmap_ros
+    version: master
+  other/static_transform_mux:
+    type: git
+    url: git@github.com:tradr-project/static_transform_mux.git
+    version: master
+  other/tf2_2d:
+    type: git
+    url: git@github.com:locusrobotics/tf2_2d.git
+    version: devel
+  other/turtlebot:
+    type: git
+    url: git@github.com:turtlebot/turtlebot
+    version: melodic
+  other/vdb/openvdb:
+    type: git
+    url: git@github.com:AcademySoftwareFoundation/openvdb.git
+    version: master
+  other/vdb/vdb_mapping:
+    type: git
+    url: git@github.com:lucasw/vdb_mapping
+    version: ubuntu_2404
+  other/vdb/vdb_mapping_ros:
+    type: git
+    url: git@github.com:lucasw/vdb_mapping_ros
+    version: rolling_window
+  other/wu_ros_tools:
+    type: git
+    url: git@github.com:lucasw/wu_ros_tools
+    version: noetic
+  ros/async_web_server_cpp:
+    type: git
+    url: git@github.com:lucasw/async_web_server_cpp.git
+    version: ros1-develop
+  ros/audio_common:
+    type: git
+    url: git@github.com:ros-drivers/audio_common.git
+    version: master
+  ros/camera_info_manager_py:
+    type: git
+    url: git@github.com:lucasw/camera_info_manager_py
+    version: noetic-devel
+  ros/common_tutorials:
+    type: git
+    url: git@github.com:lucasw/common_tutorials.git
+    version: boost_placeholders
+  ros/control_msgs:
+    type: git
+    url: git@github.com:ros-controls/control_msgs.git
+    version: kinetic-devel
+  ros/ddynamic_reconfigure_python:
+    type: git
+    url: git@github.com:pal-robotics/ddynamic_reconfigure_python
+    version: master
+  ros/diagnostics:
+    type: git
+    url: git@github.com:ros/diagnostics.git
+    version: noetic-devel
+  ros/dynamic_reconfigure:
+    type: git
+    url: git@github.com:lucasw/dynamic_reconfigure
+    version: init_default_values
+  ros/filters:
+    type: git
+    url: git@github.com:ros/filters.git
+    version: noetic-devel
+  ros/four_wheel_steering_msgs:
+    type: git
+    url: git@github.com:ros-drivers/four_wheel_steering_msgs.git
+    version: master
+  ros/gazebo_ros_demos:
+    type: git
+    url: git@github.com:lucasw/gazebo_ros_demos
+    version: noetic-devel
+  ros/gazebo_ros_pkgs:
+    type: git
+    url: git@github.com:lucasw/gazebo_ros_pkgs
+    version: noetic_debug_plugins
+  ros/geographic_info:
+    type: git
+    url: git@github.com:ros-geographic-info/geographic_info.git
+    version: master
+  # ros/geometry2:  # in underlay_ws
+  #   type: git
+  #   url: git@github.com:lucasw/geometry2
+  #   version: noetic_aggregated
+  ros/grid_map:
+    type: git
+    url: git@github.com:lucasw/grid_map
+    version: tbb_2021
+  ros/image_common:
+    type: git
+    url: git@github.com:lucasw/image_common
+    version: ubuntu_2210
+  ros/image_pipeline:
+    type: git
+    url: git@github.com:lucasw/image_pipeline
+    version: rgb_in_depth_range
+  ros/image_transport_plugins:
+    type: git
+    url: git@github.com:lucasw/image_transport_plugins
+    version: enable_pub
+  ros/interactive_markers:
+    type: git
+    url: git@github.com:ros-visualization/interactive_markers.git
+    version: noetic-devel
+  ros/joint_state_publisher:
+    type: git
+    url: git@github.com:lucasw/joint_state_publisher
+    version: noetic_aggregated
+  ros/joystick_drivers:
+    type: git
+    url: git@github.com:lucasw/joystick_drivers
+    version: warn_not_error_if_no_joy
+  ros/laser_assembler:
+    type: git
+    url: git@github.com:lucasw/laser_assembler
+    version: noetic-devel
+  ros/libuvc_ros:
+    type: git
+    url: git@github.com:lucasw/libuvc_ros.git
+    version: libuvc_0_0_7
+  ros/media_export:
+    type: git
+    url: git@github.com:ros/media_export.git
+    version: kinetic-devel
+  ros/navigation:
+    type: git
+    url: git@github.com:lucasw/navigation
+    version: lucasw_debug
+  ros/nmea_msgs:
+    type: git
+    url: git@github.com:ros-drivers/nmea_msgs
+    version: master
+  ros/nodelet_core:
+    type: git
+    url: git@github.com:lucasw/nodelet_core.git
+    version: throttle_looping_time
+  ros/octomap_msgs:
+    type: git
+    url: git@github.com:OctoMap/octomap_msgs.git
+    version: melodic-devel
+  ros/realtime_tools:
+    type: git
+    url: git@github.com:ros-controls/realtime_tools.git
+    version: noetic-devel
+  ros/robot_localization:
+    type: git
+    url: git@github.com:lucasw/robot_localization
+    version: boost_placeholders_cpp17
+  ros/robot_state_publisher:
+    type: git
+    url: git@github.com:lucasw/robot_state_publisher
+    version: robot_state_function
+  ros/ros_comm:  # custom overlay with logging mods
+    type: git
+    url: git@github.com:lucasw/ros_comm
+    version: salsa_noetic_aggregated
+  ros/ros_control:
+    type: git
+    url: git@github.com:lucasw/ros_control
+    version: acceleration_limits
+  ros/ros_controllers:
+    type: git
+    url: git@github.com:lucasw/ros_controllers
+    version: avoid_no_trajectory_defined
+  ros/ros_tutorials:
+    type: git
+    url: git@github.com:lucasw/ros_tutorials.git
+    version: boost_placeholders
+  ros/rosconsole:  # lucasw logging mods
+    type: git
+    url: git@github.com:lucasw/rosconsole
+    version: ubuntu_2210
+  ros/roscpp_core:  # lucasw fixes
+    type: git
+    url: git@github.com:lucasw/roscpp_core
+    version: duration_out_of_dual_range
+  ros/rospack:  # debian patches
+    type: git
+    url: git@github.com:lucasw/rospack
+    version: salsa
+  ros/rqt:
+    type: git
+    url: git@github.com:lucasw/rqt
+    version: ubuntu_2210
+  ros/rqt_bag:
+    type: git
+    url: git@github.com:lucasw/rqt_bag
+    version: build_2204
+  ros/rqt_console:
+    type: git
+    url: git@github.com:ros-visualization/rqt_console.git
+    version: master
+  ros/rqt_graph:
+    type: git
+    url: git@github.com:ros-visualization/rqt_graph.git
+    version: master
+  ros/rqt_logger_level:
+    type: git
+    url: git@github.com:ros-visualization/rqt_logger_level.git
+    version: master
+  ros/rqt_plot:
+    type: git
+    url: git@github.com:ros-visualization/rqt_plot.git
+    version: master
+  ros/rqt_reconfigure:
+    type: git
+    url: https://github.com/ros-visualization/rqt_reconfigure
+    version: master
+  ros/rqt_robot_monitor:
+    type: git
+    url: git@github.com:ros-visualization/rqt_robot_monitor.git
+    version: ros1
+  ros/rqt_robot_steering:
+    type: git
+    url: git@github.com:lucasw/rqt_robot_steering.git
+    version: python310
+  ros/rqt_tf_tree:
+    type: git
+    url: git@github.com:ros-visualization/rqt_tf_tree.git
+    version: master
+  ros/rviz:
+    type: git
+    url: git@github.com:lucasw/rviz.git
+    version: misc_fixes
+  ros/teleop_twist_joy:
+    type: git
+    url: git@github.com:lucasw/teleop_twist_joy
+    version: cmp0115_cpp_extension
+  ros/teleop_twist_keyboard:
+    type: git
+    url: git@github.com:ros-teleop/teleop_twist_keyboard.git
+    version: master
+  ros/twist_mux:
+    type: git
+    url: git@github.com:lucasw/twist_mux
+    version: ubuntu2210
+  ros/twist_mux_msgs:
+    type: git
+    url: git@github.com:ros-teleop/twist_mux_msgs
+    version: melodic-devel
+  ros/unique_identifier:
+    type: git
+    url: git@github.com:ros-geographic-info/unique_identifier.git
+    version: master
+  ros/urdf_geometry_parser:
+    type: git
+    url: git@github.com:ros-controls/urdf_geometry_parser.git
+    version: kinetic-devel
+  ros/urdf_parser_py:
+    type: git
+    url: git@github.com:ros/urdf_parser_py.git
+    version: melodic-devel
+  ros/usb_cam:
+    type: git
+    url: git@github.com:ros-drivers/usb_cam.git
+    version: develop
+  ros/video_stream_opencv:
+    type: git
+    url: git@github.com:lucasw/video_stream_opencv
+    version: build_2204
+  ros/view_controller_msgs:
+    type: git
+    url: git@github.com:ros-visualization/view_controller_msgs.git
+    version: lunar-devel
+  ros/vision_msgs:
+    type: git
+    url: git@github.com:ros-perception/vision_msgs.git
+    version: noetic-devel
+  ros/web_video_server:
+    type: git
+    url: git@github.com:lucasw/web_video_server
+    version: boost_placeholders
+  ros/xacro:
+    type: git
+    url: git@github.com:lucasw/xacro.git
+    version: cleanup_roslint
+  roso/control_toolbox:
+    type: git
+    url: git@github.com:ros-o/control_toolbox
+    version: obese-devel
+  roso/qt_gui_core:
+    type: git
+    url: git@github.com:lucasw/qt_gui_core
+    version: ubuntu_2210
+  roso/rosparam_shortcuts:
+    type: git
+    url: git@github.com:lucasw/rosparam_shortcuts
+    version: cleanup_lint
+  roso/rqt_image_view:
+    type: git
+    url: git@github.com:lucasw/rqt_image_view
+    version: detection2d_image_view
diff --git a/ubuntu_2404/rqt_rviz_repos.yaml b/ubuntu_2404/rqt_rviz_repos.yaml
new file mode 100644
index 0000000..265eeb6
--- /dev/null
+++ b/ubuntu_2404/rqt_rviz_repos.yaml
@@ -0,0 +1,506 @@
+repositories:
+  # extra/common_msgs:  # in underlay_ws
+  #   type: git
+  #   url: https://github.com/ros/common_msgs
+  #   version: noetic-devel
+  # extra/geometry:
+  #   type: git
+  #   url: https://github.com/ros-o/geometry
+  #   version: obese-devel
+  extra/laser_geometry:
+    type: git
+    url: https://github.com/ros-o/laser_geometry
+    version: obese-devel
+  extra/navigation_msgs:
+    type: git
+    url: https://github.com/ros-planning/navigation_msgs
+    version: ros1
+  extra/pcl_msgs:
+    type: git
+    url: https://github.com/ros-perception/pcl_msgs
+    version: noetic-devel
+  extra/perception_pcl:
+    type: git
+    url: https://github.com/ros-o/perception_pcl
+    version: obese-devel
+  extra/python_qt_binding:
+    type: git
+    url: https://github.com/ros-o/python_qt_binding
+    version: obese-devel
+  extra/vision_opencv:
+    type: git
+    url: https://github.com/ros-perception/vision_opencv
+    version: noetic
+  lucasw/dynamic_reconfigure_tools:
+    type: git
+    url: https://github.com/lucasw/dynamic_reconfigure_tools
+    version: master
+  lucasw/image_manip:
+    type: git
+    url: https://github.com/lucasw/image_manip
+    version: fix_zero_frame_rate
+  lucasw/nodelet_demo:
+    type: git
+    url: https://github.com/lucasw/nodelet_demo
+    version: master
+  lucasw/ros1_lifecycle:
+    type: git
+    url: https://github.com/lucasw/ros1_lifecycle
+    version: misc_fixes
+  lucasw/ros_example:
+    type: git
+    url: https://github.com/lucasw/ros_example
+    version: main
+  lucasw/ros_system_monitor:
+    type: git
+    url: https://github.com/lucasw/ros_system_monitor
+    version: chrony_monitor
+  lucasw/rqt_file_dialog:
+    type: git
+    url: https://github.com/lucasw/rqt_file_dialog
+    version: master
+  lucasw/rqt_tf_echo:
+    type: git
+    url: https://github.com/lucasw/rqt_tf_echo
+    version: master
+  lucasw/rqt_topic_display:
+    type: git
+    url: https://github.com/lucasw/rqt_topic_display
+    version: master
+  lucasw/rviz_camera_stream:
+    type: git
+    url: https://github.com/lucasw/rviz_camera_stream
+    version: noetic-devel
+  lucasw/rviz_interactive_tf:
+    type: git
+    url: https://github.com/lucasw/rviz_interactive_tf
+    version: master
+  lucasw/rviz_lighting:
+    type: git
+    url: https://github.com/lucasw/rviz_lighting
+    version: cpp17
+  lucasw/rviz_ortho_view_controller:
+    type: git
+    url: https://github.com/lucasw/rviz_ortho_view_controller
+    version: master
+  lucasw/screengrab_ros:
+    type: git
+    url: https://github.com/lucasw/screengrab_ros
+    version: master
+  lucasw/signal_generator:
+    type: git
+    url: https://github.com/lucasw/signal_generator
+    version: master
+  lucasw/tf_demo:
+    type: git
+    url: https://github.com/lucasw/tf_demo
+    version: old_tf_to_new_tf
+  lucasw/timer_test:
+    type: git
+    url: https://github.com/lucasw/timer_test
+    version: master
+  lucasw/topic_state:
+    type: git
+    url: https://github.com/lucasw/topic_state
+    version: master
+  lucasw/transform_point_cloud:
+    type: git
+    url: https://github.com/lucasw/transform_point_cloud
+    version: master
+  lucasw/v4l2ucp:
+    type: git
+    url: https://github.com/lucasw/v4l2ucp
+    version: master
+  lucasw/vimjay:
+    type: git
+    url: https://github.com/lucasw/vimjay
+    version: eliminate_build_warnings
+  opencv_apps:
+    type: git
+    # url: https://github.com/ros-perception/opencv_apps
+    url: https://github.com/muellerbernd/opencv_apps
+    version: indigo
+  other/PlotJuggler:
+    type: git
+    url: https://github.com/facontidavide/PlotJuggler
+    version: main
+  other/apriltag_ros:
+    type: git
+    url: https://github.com/AprilRobotics/apriltag_ros
+    version: master
+  other/camera_throttler_nodelets:
+    type: git
+    url: https://github.com/lucasw/camera_throttler_nodelets
+    version: noetic_aggregated
+  other/catkin_virtualenv:
+    type: git
+    url: https://github.com/locusrobotics/catkin_virtualenv
+    version: master
+  other/ddynamic_reconfigure:
+    type: git
+    url: https://github.com/ros-o/ddynamic_reconfigure
+    version: obese-devel
+  other/euslisp-release:
+    type: git
+    url: https://github.com/tork-a/euslisp-release
+    version: release/melodic/euslisp
+  other/fiducials:
+    type: git
+    url: https://github.com/lucasw/fiducials
+    version: cmake_vision_msgs
+  # other/geneus:  # in underlay_ws
+  #   type: git
+  #   url: https://github.com/jsk-ros-pkg/geneus
+  #   version: master
+  other/graph_rviz_plugin:
+    type: git
+    url: https://github.com/lucasw/graph_rviz_plugin
+    version: pluginlib_hpp
+  other/jsk_common:
+    type: git
+    url: https://github.com/lucasw/jsk_common
+    version: video_to_bag_features
+  other/jsk_common_msgs:
+    type: git
+    url: https://github.com/lucasw/jsk_common_msgs
+    version: master
+  other/jsk_recognition:
+    type: git
+    url: https://github.com/lucasw/jsk_recognition
+    version: pcl_vtk_isfinite
+  other/jsk_roseus:
+    type: git
+    url: https://github.com/jsk-ros-pkg/jsk_roseus
+    version: master
+  other/jsk_visualization:
+    type: git
+    url: https://github.com/lucasw/jsk_visualization
+    version: boost_placeholders
+  other/libnabo:
+    type: git
+    url: https://github.com/ethz-asl/libnabo
+    version: master
+  other/lvr2:
+    type: git
+    url: https://github.com/uos/lvr2
+    version: humble
+  other/marti_messages:
+    type: git
+    url: https://github.com/swri-robotics/marti_messages
+    version: master
+  other/message_filters:
+    type: git
+    url: https://github.com/fkie/message_filters
+    version: master
+  other/nmea_navsat_driver:
+    type: git
+    url: https://github.com/ros-drivers/nmea_navsat_driver
+    version: master
+  other/nodelet_rosbag:
+    type: git
+    url: https://github.com/lucasw/nodelet_rosbag
+    version: pluginlib_hpp
+  other/pal_statistics:
+    type: git
+    url: https://github.com/pal-robotics/pal_statistics
+    version: kinetic-devel
+  other/pid:
+    type: git
+    url: https://github.com/lucasw/pid
+    version: boost_placeholders
+  other/plotjuggler-ros-plugins:
+    type: git
+    url: https://github.com/PlotJuggler/plotjuggler-ros-plugins
+    version: main
+  other/plotjuggler_msgs:
+    type: git
+    url: https://github.com/PlotJuggler/plotjuggler_msgs
+    version: main
+  other/point_cloud_converter:
+    type: git
+    url: https://github.com/pal-robotics-forks/point_cloud_converter
+    version: hydro-devel
+  other/ros_control_boilerplate:
+    type: git
+    url: https://github.com/lucasw/ros_control_boilerplate
+    version: cpp17
+  other/ros_numpy:
+    type: git
+    url: https://github.com/lucasw/ros_numpy
+    version: collections_abc
+  other/ros_rtsp:
+    type: git
+    url: https://github.com/lucasw/ros_rtsp
+    version: pluginlib_hpp
+  other/ros_type_introspection:
+    type: git
+    url: https://github.com/lucasw/ros_type_introspection
+    version: build_2204
+  other/rosbag_snapshot:
+    type: git
+    url: https://github.com/ros/rosbag_snapshot
+    version: main
+  other/rqt_ez_publisher:
+    type: git
+    url: https://github.com/lucasw/rqt_ez_publisher
+    version: ubuntu2210
+  other/static_transform_mux:
+    type: git
+    url: https://github.com/tradr-project/static_transform_mux
+    version: master
+  other/tf2_2d:
+    type: git
+    url: https://github.com/locusrobotics/tf2_2d
+    version: devel
+  other/wu_ros_tools:
+    type: git
+    url: https://github.com/lucasw/wu_ros_tools
+    version: noetic
+  ros/audio_common:
+    type: git
+    url: https://github.com/ros-drivers/audio_common
+    version: master
+  ros/camera_info_manager_py:
+    type: git
+    url: https://github.com/lucasw/camera_info_manager_py
+    version: noetic-devel
+  ros/common_tutorials:
+    type: git
+    url: https://github.com/lucasw/common_tutorials
+    version: boost_placeholders
+  ros/control_msgs:
+    type: git
+    url: https://github.com/ros-controls/control_msgs
+    version: kinetic-devel
+  ros/ddynamic_reconfigure_python:
+    type: git
+    url: https://github.com/pal-robotics/ddynamic_reconfigure_python
+    version: master
+  ros/diagnostics:
+    type: git
+    url: https://github.com/ros/diagnostics
+    version: noetic-devel
+  ros/dynamic_reconfigure:
+    type: git
+    url: https://github.com/lucasw/dynamic_reconfigure
+    version: init_default_values
+  ros/filters:
+    type: git
+    url: https://github.com/ros/filters
+    version: noetic-devel
+  ros/four_wheel_steering_msgs:
+    type: git
+    url: https://github.com/ros-drivers/four_wheel_steering_msgs
+    version: master
+  ros/geographic_info:
+    type: git
+    url: https://github.com/ros-geographic-info/geographic_info
+    version: master
+  # ros/geometry2:  # in underlay_ws
+  #   type: git
+  #   url: https://github.com/lucasw/geometry2
+  #   version: noetic_aggregated
+  ros/grid_map:
+    type: git
+    url: https://github.com/lucasw/grid_map
+    version: tbb_2021
+  ros/image_common:
+    type: git
+    url: https://github.com/lucasw/image_common
+    version: ubuntu_2210
+  ros/image_pipeline:
+    type: git
+    url: https://github.com/lucasw/image_pipeline
+    version: rgb_in_depth_range
+  ros/image_transport_plugins:
+    type: git
+    url: https://github.com/lucasw/image_transport_plugins
+    version: enable_pub
+  ros/interactive_markers:
+    type: git
+    url: https://github.com/ros-visualization/interactive_markers
+    version: noetic-devel
+  ros/joint_state_publisher:
+    type: git
+    url: https://github.com/lucasw/joint_state_publisher
+    version: noetic_aggregated
+  ros/joystick_drivers:
+    type: git
+    url: https://github.com/lucasw/joystick_drivers
+    version: warn_not_error_if_no_joy
+  ros/laser_assembler:
+    type: git
+    url: https://github.com/lucasw/laser_assembler
+    version: noetic-devel
+  ros/libuvc_ros:
+    type: git
+    url: https://github.com/lucasw/libuvc_ros
+    version: libuvc_0_0_7
+  ros/media_export:
+    type: git
+    url: https://github.com/ros/media_export
+    version: kinetic-devel
+  ros/navigation:
+    type: git
+    url: https://github.com/lucasw/navigation
+    version: lucasw_debug
+  ros/nmea_msgs:
+    type: git
+    url: https://github.com/ros-drivers/nmea_msgs
+    version: master
+  ros/nodelet_core:
+    type: git
+    url: https://github.com/lucasw/nodelet_core
+    version: throttle_looping_time
+  ros/octomap_msgs:
+    type: git
+    url: https://github.com/OctoMap/octomap_msgs
+    version: melodic-devel
+  ros/realtime_tools:
+    type: git
+    url: https://github.com/ros-controls/realtime_tools
+    version: noetic-devel
+  ros/robot_state_publisher:
+    type: git
+    url: https://github.com/lucasw/robot_state_publisher
+    version: robot_state_function
+  ros/ros_comm:  # custom overlay with logging mods
+    type: git
+    url: https://github.com/lucasw/ros_comm
+    version: salsa_noetic_aggregated
+  ros/ros_control:
+    type: git
+    url: https://github.com/lucasw/ros_control
+    version: acceleration_limits
+  ros/ros_controllers:
+    type: git
+    url: https://github.com/lucasw/ros_controllers
+    version: avoid_no_trajectory_defined
+  ros/ros_tutorials:
+    type: git
+    url: https://github.com/lucasw/ros_tutorials
+    version: boost_placeholders
+  ros/rosconsole:  # lucasw logging mods
+    type: git
+    url: https://github.com/lucasw/rosconsole
+    version: ubuntu_2210
+  ros/roscpp_core:  # lucasw fixes
+    type: git
+    url: https://github.com/lucasw/roscpp_core
+    version: duration_out_of_dual_range
+  ros/rospack:  # debian patches
+    type: git
+    url: https://github.com/lucasw/rospack
+    version: salsa
+  ros/rqt:
+    type: git
+    url: https://github.com/lucasw/rqt
+    version: ubuntu_2210
+  ros/rqt_bag:
+    type: git
+    url: https://github.com/lucasw/rqt_bag
+    version: build_2204
+  ros/rqt_console:
+    type: git
+    url: https://github.com/ros-visualization/rqt_console
+    version: master
+  ros/rqt_graph:
+    type: git
+    url: https://github.com/ros-visualization/rqt_graph
+    version: master
+  ros/rqt_logger_level:
+    type: git
+    url: https://github.com/ros-visualization/rqt_logger_level
+    version: master
+  ros/rqt_plot:
+    type: git
+    url: https://github.com/ros-visualization/rqt_plot
+    version: master
+  ros/rqt_reconfigure:
+    type: git
+    url: https://github.com/ros-visualization/rqt_reconfigure
+    version: master
+  ros/rqt_robot_monitor:
+    type: git
+    url: https://github.com/ros-visualization/rqt_robot_monitor
+    version: ros1
+  ros/rqt_robot_steering:
+    type: git
+    url: https://github.com/lucasw/rqt_robot_steering
+    version: python310
+  ros/rqt_tf_tree:
+    type: git
+    url: https://github.com/ros-visualization/rqt_tf_tree
+    version: master
+  ros/rviz:
+    type: git
+    url: https://github.com/lucasw/rviz
+    version: misc_fixes
+  ros/teleop_twist_joy:
+    type: git
+    url: https://github.com/lucasw/teleop_twist_joy
+    version: cmp0115_cpp_extension
+  ros/teleop_twist_keyboard:
+    type: git
+    url: https://github.com/ros-teleop/teleop_twist_keyboard
+    version: master
+  ros/twist_mux:
+    type: git
+    url: https://github.com/lucasw/twist_mux
+    version: ubuntu2210
+  ros/twist_mux_msgs:
+    type: git
+    url: https://github.com/ros-teleop/twist_mux_msgs
+    version: melodic-devel
+  ros/unique_identifier:
+    type: git
+    url: https://ros-geographic-info/unique_identifier
+    version: master
+  ros/urdf_geometry_parser:
+    type: git
+    url: https://ros-controls/urdf_geometry_parser
+    version: kinetic-devel
+  ros/urdf_parser_py:
+    type: git
+    url: https://github.com/ros/urdf_parser_py
+    version: melodic-devel
+  ros/usb_cam:
+    type: git
+    url: https://github.com/ros-drivers/usb_cam
+    version: develop
+  ros/video_stream_opencv:
+    type: git
+    url: https://github.com/lucasw/video_stream_opencv
+    version: build_2204
+  ros/view_controller_msgs:
+    type: git
+    url: https://github.com/ros-visualization/view_controller_msgs
+    version: lunar-devel
+  ros/vision_msgs:
+    type: git
+    url: https://github.com/ros-perception/vision_msgs
+    version: noetic-devel
+  ros/web_video_server:
+    type: git
+    url: https://github.com/lucasw/web_video_server
+    version: boost_placeholders
+  ros/xacro:
+    type: git
+    url: https://github.com/lucasw/xacro
+    version: cleanup_roslint
+  roso/control_toolbox:
+    type: git
+    url: https://github.com/ros-o/control_toolbox
+    version: obese-devel
+  roso/qt_gui_core:
+    type: git
+    url: https://github.com/lucasw/qt_gui_core
+    version: ubuntu_2210
+  roso/rosparam_shortcuts:
+    type: git
+    url: https://github.com/lucasw/rosparam_shortcuts
+    version: cleanup_lint
+  roso/rqt_image_view:
+    type: git
+    url: https://github.com/lucasw/rqt_image_view
+    version: detection2d_image_view