Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
41 commits
Select commit Hold shift + click to select a range
0e155c6
fix quat
paul-nechifor Oct 25, 2025
c1cd372
add ros docker integration
paul-nechifor Oct 25, 2025
264779f
new path
paul-nechifor Oct 25, 2025
6d3c7a9
improve names
paul-nechifor Oct 25, 2025
da2c87f
fix it
paul-nechifor Oct 25, 2025
6cc7cf5
Add initial environment.
paul-nechifor Oct 25, 2025
ee8fcf0
CI code cleanup
paul-nechifor Oct 25, 2025
2d65c97
remove more unnecessary stuff
paul-nechifor Oct 25, 2025
47bb9cc
more cleanup
paul-nechifor Oct 26, 2025
e1d5b45
Merge branch 'dev' into dimos-rosnav-docker
paul-nechifor Oct 29, 2025
c09c70b
move to docker/navigation
paul-nechifor Oct 29, 2025
e28779a
fix import
paul-nechifor Oct 29, 2025
ef988dc
fix log
paul-nechifor Oct 29, 2025
91bfe37
fix nvidia runtime error with GPU auto-detection and CPU fallback
naveenkul Oct 29, 2025
f6e6983
switch to ros-navigation-autonomy-stack
paul-nechifor Oct 30, 2025
377cfa0
add trap to shut down x access
paul-nechifor Oct 30, 2025
c6217cf
Merge branch 'dev' into dimos-rosnav-docker
paul-nechifor Oct 30, 2025
483b6c4
use demo_ros_navigation
paul-nechifor Oct 30, 2025
5758f7a
spacing
paul-nechifor Oct 30, 2025
f0ffa1c
fix navigation
paul-nechifor Oct 30, 2025
5d5bc0f
use ROS_DOMAIN_ID=42
paul-nechifor Oct 30, 2025
65e72e1
add setup script for new os installation for easy deployments
naveenkul Nov 4, 2025
fb9ea0f
use main branch for public use
naveenkul Nov 4, 2025
2e2b65a
include hardware in docker
paul-nechifor Nov 4, 2025
c762ac6
describe how to configure lidar and wifi
paul-nechifor Nov 6, 2025
34879ca
CI code cleanup
paul-nechifor Nov 6, 2025
0f69734
Added livox config for G1 edu
spomichter Nov 6, 2025
311f69a
CI code cleanup
spomichter Nov 6, 2025
8284ccb
generate MID360_config.json
paul-nechifor Nov 6, 2025
00f65c6
remove CAMERA_DEVICE and update ROBOT_CONFIG_PATH comment
paul-nechifor Nov 7, 2025
2f7acbc
add LIDAR_GATEWAY
paul-nechifor Nov 7, 2025
90d2b8d
continue even without nvidia runtime
paul-nechifor Nov 7, 2025
b8dd34d
use runc for hardware
paul-nechifor Nov 7, 2025
4ae131f
add turbojpeg
paul-nechifor Nov 7, 2025
4e01815
describe what ./build.sh does in the readme.
paul-nechifor Nov 7, 2025
8a247a4
mark directory as safe
paul-nechifor Nov 7, 2025
5f73b3c
Merge branch 'dev' into dimos-rosnav-docker
paul-nechifor Nov 7, 2025
7a6d493
install git-lfs
paul-nechifor Nov 7, 2025
66d41b0
increase timeout
paul-nechifor Nov 7, 2025
b269556
activate automatically
paul-nechifor Nov 7, 2025
c42252b
Added Unitree g1 EDU lidar IP addresses to the .env
spomichter Nov 9, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions data/.lfs/office_building_1.tar.gz
Git LFS file not shown
72 changes: 72 additions & 0 deletions dimos/navigation/demo_ros_navigation.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
# Copyright 2025 Dimensional Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import time

import rclpy

from dimos import core
from dimos.msgs.geometry_msgs import PoseStamped, Quaternion, Twist, Vector3
from dimos.msgs.nav_msgs import Path
from dimos.msgs.sensor_msgs import PointCloud2
from dimos.navigation.rosnav import ROSNav
from dimos.protocol import pubsub
from dimos.utils.logging_config import setup_logger

logger = setup_logger(__file__)


def main() -> None:
pubsub.lcm.autoconf()
dimos = core.start(2)

ros_nav = dimos.deploy(ROSNav)

ros_nav.goal_req.transport = core.LCMTransport("/goal", PoseStamped)
ros_nav.pointcloud.transport = core.LCMTransport("/pointcloud_map", PointCloud2)
ros_nav.global_pointcloud.transport = core.LCMTransport("/global_pointcloud", PointCloud2)
ros_nav.goal_active.transport = core.LCMTransport("/goal_active", PoseStamped)
ros_nav.path_active.transport = core.LCMTransport("/path_active", Path)
ros_nav.cmd_vel.transport = core.LCMTransport("/cmd_vel", Twist)

ros_nav.start()

logger.info("\nTesting navigation in 2 seconds...")
time.sleep(2)

test_pose = PoseStamped(
ts=time.time(),
frame_id="map",
position=Vector3(2.0, 2.0, 0.0),
orientation=Quaternion(0.0, 0.0, 0.0, 1.0),
)

logger.info("Sending navigation goal to: (2.0, 2.0, 0.0)")
success = ros_nav.navigate_to(test_pose, timeout=30.0)
logger.info(f"Navigated successfully: {success}")

try:
logger.info("\nNavBot running. Press Ctrl+C to stop.")
while True:
time.sleep(1)
except KeyboardInterrupt:
logger.info("\nShutting down...")
ros_nav.stop()

if rclpy.ok():
rclpy.shutdown()


if __name__ == "__main__":
main()
6 changes: 3 additions & 3 deletions dimos/navigation/rosnav.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
"""

from collections.abc import Generator
from dataclasses import dataclass
from dataclasses import dataclass, field
import logging
import threading
import time
Expand Down Expand Up @@ -64,8 +64,8 @@
class Config(ModuleConfig):
local_pointcloud_freq: float = 2.0
global_pointcloud_freq: float = 1.0
sensor_to_base_link_transform: Transform = Transform(
frame_id="sensor", child_frame_id="base_link"
sensor_to_base_link_transform: Transform = field(
default_factory=lambda: Transform(frame_id="sensor", child_frame_id="base_link")
)


Expand Down
2 changes: 1 addition & 1 deletion dimos/protocol/rpc/spec.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ def call(self, name: str, arguments: Args, cb: Callable | None) -> Callable[[],
# we expect to crash if we don't get a return value after 10 seconds
# but callers can override this timeout for extra long functions
def call_sync(
self, name: str, arguments: Args, rpc_timeout: float | None = 30.0
self, name: str, arguments: Args, rpc_timeout: float | None = 120.0
) -> tuple[Any, Callable[[], None]]:
event = threading.Event()

Expand Down
59 changes: 59 additions & 0 deletions docker/navigation/.env.hardware
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
# Hardware Configuration Environment Variables
# Copy this file to .env and customize for your hardware setup

# ============================================
# NVIDIA GPU Support
# ============================================
# Set the Docker runtime to nvidia for GPU support (it's runc by default)
#DOCKER_RUNTIME=nvidia

# ============================================
# ROS Configuration
# ============================================
# ROS domain ID for multi-robot setups
ROS_DOMAIN_ID=42

# Robot configuration ('mechanum_drive', 'unitree/unitree_g1', 'unitree/unitree_g1', etc)
ROBOT_CONFIG_PATH=mechanum_drive

# ============================================
# Mid-360 Lidar Configuration
# ============================================
# Network interface connected to the lidar (e.g., eth0, enp0s3)
# Find with: ip addr show
LIDAR_INTERFACE=eth0

# Processing computer IP address on the lidar subnet
# Must be on the same subnet as the lidar (e.g., 192.168.1.5)
# LIDAR_COMPUTER_IP=192.168.123.5 # FOR UNITREE G1 EDU
LIDAR_COMPUTER_IP=192.168.1.5

# Gateway IP address for the lidar subnet
# LIDAR_GATEWAY=192.168.123.1 # FOR UNITREE G1 EDU
LIDAR_GATEWAY=192.168.1.1

# Full IP address of your Mid-360 lidar
# This should match the IP configured on your lidar device
# Common patterns: 192.168.1.1XX or 192.168.123.1XX
# LIDAR_IP=192.168.123.120 # FOR UNITREE G1 EDU
LIDAR_IP=192.168.1.116

# ============================================
# Motor Controller Configuration
# ============================================
# Serial device for motor controller
# Check with: ls /dev/ttyACM* or ls /dev/ttyUSB*
MOTOR_SERIAL_DEVICE=/dev/ttyACM0

# ============================================
# Network Communication (for base station)
# ============================================
# Enable WiFi buffer optimization for data transmission
# Set to true if using wireless base station
ENABLE_WIFI_BUFFER=false

# ============================================
# Display Configuration
# ============================================
# X11 display (usually auto-detected)
# DISPLAY=:0
20 changes: 20 additions & 0 deletions docker/navigation/.gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
# Cloned repository
ros-navigation-autonomy-stack/

# Unity models (large binary files)
unity_models/

# ROS bag files
bagfiles/

# Config files (may contain local settings)
config/

# Docker volumes
.docker/

# Temporary files
*.tmp
*.log
*.swp
*~
Loading
Loading