Skip to content

Commit a28ed6a

Browse files
authored
Merge pull request #460 - Stream/type fixes and updates, Change default dev container to non-ROS build
Small stream/type fixes for unitree Former-commit-id: 54c87f0 [formerly a5c1eba] Former-commit-id: 3022569
1 parent 7fc185e commit a28ed6a

File tree

13 files changed

+448
-199
lines changed

13 files changed

+448
-199
lines changed

.devcontainer/devcontainer.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
{
22
"name": "dimos-dev",
3-
"image": "ghcr.io/dimensionalos/ros-dev:dev",
3+
"image": "ghcr.io/dimensionalos/dev:dev",
44
"customizations": {
55
"vscode": {
66
"extensions": [

dimos/msgs/geometry_msgs/PoseStamped.py

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -74,3 +74,9 @@ def lcm_decode(cls, data: bytes | BinaryIO) -> PoseStamped:
7474
lcm_msg.pose.orientation.w,
7575
], # noqa: E501,
7676
)
77+
78+
def __str__(self) -> str:
79+
return (
80+
f"PoseStamped(pos=[{self.x:.3f}, {self.y:.3f}, {self.z:.3f}], "
81+
f"euler=[{self.roll:.3f}, {self.pitch:.3f}, {self.yaw:.3f}])"
82+
)
Lines changed: 55 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
# Copyright 2025 Dimensional Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import pickle
16+
import time
17+
18+
from dimos.msgs.geometry_msgs import PoseStamped
19+
20+
21+
def test_lcm_encode_decode():
22+
"""Test encoding and decoding of Pose to/from binary LCM format."""
23+
24+
pose_source = PoseStamped(
25+
ts=time.time(),
26+
position=(1.0, 2.0, 3.0),
27+
orientation=(0.1, 0.2, 0.3, 0.9),
28+
)
29+
binary_msg = pose_source.lcm_encode()
30+
pose_dest = PoseStamped.lcm_decode(binary_msg)
31+
32+
assert isinstance(pose_dest, PoseStamped)
33+
assert pose_dest is not pose_source
34+
35+
print(pose_source.position)
36+
print(pose_source.orientation)
37+
38+
print(pose_dest.position)
39+
print(pose_dest.orientation)
40+
assert pose_dest == pose_source
41+
42+
43+
def test_pickle_encode_decode():
44+
"""Test encoding and decoding of PoseStamped to/from binary LCM format."""
45+
46+
pose_source = PoseStamped(
47+
ts=time.time(),
48+
position=(1.0, 2.0, 3.0),
49+
orientation=(0.1, 0.2, 0.3, 0.9),
50+
)
51+
binary_msg = pickle.dumps(pose_source)
52+
pose_dest = pickle.loads(binary_msg)
53+
assert isinstance(pose_dest, PoseStamped)
54+
assert pose_dest is not pose_source
55+
assert pose_dest == pose_source

dimos/robot/global_planner/algo.py

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,15 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
import math
1615
import heapq
17-
from typing import Optional, Tuple
16+
import math
1817
from collections import deque
19-
from dimos.types.path import Path
20-
from dimos.types.vector import VectorLike, Vector
18+
from typing import Optional, Tuple
19+
20+
from dimos.msgs.geometry_msgs import Vector3 as Vector
21+
from dimos.msgs.geometry_msgs.Vector3 import VectorLike
2122
from dimos.types.costmap import Costmap
23+
from dimos.types.path import Path
2224

2325

2426
def find_nearest_free_cell(

dimos/robot/local_planner/simple.py

Lines changed: 66 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -14,29 +14,27 @@
1414

1515
import math
1616
import time
17-
from dataclasses import dataclass
18-
from typing import Any, Callable, Optional
17+
import traceback
18+
from typing import Callable, Optional
1919

2020
import reactivex as rx
2121
from plum import dispatch
2222
from reactivex import operators as ops
2323

2424
from dimos.core import In, Module, Out, rpc
2525
from dimos.msgs.geometry_msgs import PoseStamped, Vector3
26-
from dimos.robot.unitree_webrtc.type.odometry import Odometry
2726

2827
# from dimos.robot.local_planner.local_planner import LocalPlanner
2928
from dimos.types.costmap import Costmap
3029
from dimos.types.path import Path
31-
from dimos.types.pose import Pose
3230
from dimos.types.vector import Vector, VectorLike, to_vector
3331
from dimos.utils.logging_config import setup_logger
3432
from dimos.utils.threadpool import get_scheduler
3533

36-
logger = setup_logger("dimos.robot.unitree.global_planner")
34+
logger = setup_logger("dimos.robot.unitree.local_planner")
3735

3836

39-
def transform_to_robot_frame(global_vector: Vector, robot_position: Pose) -> Vector:
37+
def transform_to_robot_frame(global_vector: Vector3, robot_position: PoseStamped) -> Vector:
4038
"""Transform a global coordinate vector to robot-relative coordinates.
4139
4240
Args:
@@ -47,21 +45,22 @@ def transform_to_robot_frame(global_vector: Vector, robot_position: Pose) -> Vec
4745
Vector in robot coordinates where X is forward/backward, Y is left/right
4846
"""
4947
# Get the robot's yaw angle (rotation around Z-axis)
50-
robot_yaw = robot_position.rot.z
48+
robot_yaw = robot_position.yaw
5149

5250
# Create rotation matrix to transform from global to robot frame
5351
# We need to rotate the coordinate system by -robot_yaw to get robot-relative coordinates
5452
cos_yaw = math.cos(-robot_yaw)
5553
sin_yaw = math.sin(-robot_yaw)
5654

55+
print(cos_yaw, sin_yaw, global_vector)
5756
# Apply 2D rotation transformation
5857
# This transforms a global direction vector into the robot's coordinate frame
5958
# In robot frame: X=forward/backward, Y=left/right
6059
# In global frame: X=east/west, Y=north/south
6160
robot_x = global_vector.x * cos_yaw - global_vector.y * sin_yaw # Forward/backward
6261
robot_y = global_vector.x * sin_yaw + global_vector.y * cos_yaw # Left/right
6362

64-
return Vector(-robot_x, robot_y, 0)
63+
return Vector3(-robot_x, robot_y, 0)
6564

6665

6766
class SimplePlanner(Module):
@@ -71,7 +70,7 @@ class SimplePlanner(Module):
7170

7271
get_costmap: Callable[[], Costmap]
7372

74-
latest_odom: PoseStamped = None
73+
latest_odom: Optional[PoseStamped] = None
7574

7675
goal: Optional[Vector] = None
7776
speed: float = 0.3
@@ -83,24 +82,59 @@ def __init__(
8382
Module.__init__(self)
8483
self.get_costmap = get_costmap
8584

86-
def get_move_stream(self, frequency: float = 40.0) -> rx.Observable:
85+
def get_move_stream(self, frequency: float = 20.0) -> rx.Observable:
8786
return rx.interval(1.0 / frequency, scheduler=get_scheduler()).pipe(
8887
# do we have a goal?
8988
ops.filter(lambda _: self.goal is not None),
90-
# For testing: make robot move left/right instead of rotating
91-
ops.map(lambda _: self._test_translational_movement()),
92-
self.frequency_spy("movement_test"),
89+
# do we have odometry data?
90+
ops.filter(lambda _: self.latest_odom is not None),
91+
# transform goal to robot frame with error handling
92+
ops.map(lambda _: self._safe_transform_goal()),
93+
# filter out None results (errors)
94+
ops.filter(lambda result: result is not None),
95+
ops.map(self._calculate_rotation_to_target),
96+
# filter out None results from calc_move
97+
ops.filter(lambda result: result is not None),
9398
)
9499

100+
def _safe_transform_goal(self) -> Optional[Vector]:
101+
"""Safely transform goal to robot frame with error handling."""
102+
try:
103+
if self.goal is None or self.latest_odom is None:
104+
return None
105+
106+
# Convert PoseStamped to Pose for transform function
107+
# Pose constructor takes (pos, rot) where pos and rot are VectorLike
108+
109+
return transform_to_robot_frame(self.goal, self.latest_odom)
110+
except Exception as e:
111+
logger.error(f"Error transforming goal to robot frame: {e}")
112+
print(traceback.format_exc())
113+
return None
114+
95115
@rpc
96116
def start(self):
117+
print(self.path.connection, self.path.transport)
97118
self.path.subscribe(self.set_goal)
119+
self.movecmd.publish(Vector3(1, 2, 3))
120+
self.movecmd.publish(Vector3(1, 2, 3))
121+
self.movecmd.publish(Vector3(1, 2, 3))
122+
self.movecmd.publish(Vector3(1, 2, 3))
98123

99-
def setodom(odom: Odometry):
124+
def setodom(odom: PoseStamped):
100125
self.latest_odom = odom
101126

127+
def pubmove(move: Vector3):
128+
print("PUBMOVE", move, "\n\n")
129+
# print(self.movecmd)
130+
try:
131+
self.movecmd.publish(move)
132+
except Exception as e:
133+
print(traceback.format_exc())
134+
print(e)
135+
102136
self.odom.subscribe(setodom)
103-
self.get_move_stream(frequency=20.0).subscribe(self.movecmd.publish)
137+
self.get_move_stream(frequency=20.0).subscribe(pubmove)
104138

105139
@dispatch
106140
def set_goal(self, goal: Path, stop_event=None, goal_theta=None) -> bool:
@@ -114,14 +148,14 @@ def set_goal(self, goal: VectorLike, stop_event=None, goal_theta=None) -> bool:
114148
logger.info(f"Setting goal: {self.goal}")
115149
return True
116150

117-
def calc_move(self, direction: Vector) -> Vector:
151+
def calc_move(self, direction: Vector) -> Optional[Vector]:
118152
"""Calculate the movement vector based on the direction to the goal.
119153
120154
Args:
121155
direction: Direction vector towards the goal
122156
123157
Returns:
124-
Movement vector scaled by speed
158+
Movement vector scaled by speed, or None if error occurs
125159
"""
126160
try:
127161
# Normalize the direction vector and scale by speed
@@ -130,7 +164,8 @@ def calc_move(self, direction: Vector) -> Vector:
130164
print("CALC MOVE", direction, normalized_direction, move_vector)
131165
return move_vector
132166
except Exception as e:
133-
print("Error calculating move vector:", e)
167+
logger.error(f"Error calculating move vector: {e}")
168+
return None
134169

135170
def spy(self, name: str):
136171
def spyfun(x):
@@ -184,11 +219,11 @@ def _test_translational_movement(self) -> Vector:
184219

185220
if phase < 0.5:
186221
# First half: move LEFT (positive X according to our documentation)
187-
movement = Vector3(0.2, 0, 0) # Move left at 0.2 m/s
222+
movement = Vector(0.2, 0, 0) # Move left at 0.2 m/s
188223
direction = "LEFT (positive X)"
189224
else:
190225
# Second half: move RIGHT (negative X according to our documentation)
191-
movement = Vector3(-0.2, 0, 0) # Move right at 0.2 m/s
226+
movement = Vector(-0.2, 0, 0) # Move right at 0.2 m/s
192227
direction = "RIGHT (negative X)"
193228

194229
print("=== LEFT-RIGHT MOVEMENT TEST ===")
@@ -207,11 +242,15 @@ def _calculate_rotation_to_target(self, direction_to_goal: Vector) -> Vector:
207242
Returns:
208243
Vector with (x=0, y=0, z=angular_velocity) for rotation only
209244
"""
245+
if self.latest_odom is None:
246+
logger.warning("No odometry data available for rotation calculation")
247+
return Vector(0, 0, 0)
248+
210249
# Calculate the desired yaw angle to face the target
211250
desired_yaw = math.atan2(direction_to_goal.y, direction_to_goal.x)
212251

213252
# Get current robot yaw
214-
current_yaw = self.latest_odom.orientation.z
253+
current_yaw = self.latest_odom.yaw
215254

216255
# Calculate the yaw error using a more robust method to avoid oscillation
217256
yaw_error = math.atan2(
@@ -247,13 +286,17 @@ def _calculate_rotation_to_target(self, direction_to_goal: Vector) -> Vector:
247286

248287
# Return movement command: no translation (x=0, y=0), only rotation (z=angular_velocity)
249288
# Try flipping the sign in case the rotation convention is opposite
250-
return Vector(0, 0, -angular_velocity)
289+
return Vector3(0, 0, -angular_velocity)
251290

252291
def _debug_direction(self, name: str, direction: Vector) -> Vector:
253292
"""Debug helper to log direction information"""
254293
robot_pos = self.latest_odom
294+
if robot_pos is None:
295+
print(f"DEBUG {name}: direction={direction}, robot_pos=None, goal={self.goal}")
296+
return direction
297+
255298
print(
256-
f"DEBUG {name}: direction={direction}, robot_pos={robot_pos.position.to_2d()}, robot_yaw={math.degrees(robot_pos.rot.z):.1f}°, goal={self.goal}"
299+
f"DEBUG {name}: direction={direction}, robot_pos={robot_pos.position.to_2d()}, robot_yaw={math.degrees(robot_pos.orientation.z):.1f}°, goal={self.goal}"
257300
)
258301
return direction
259302

dimos/robot/unitree_webrtc/multiprocess/unitree_go2.py

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -146,7 +146,6 @@ async def run(ip):
146146

147147
# This enables LCM transport
148148
# Ensures system multicast, udp sizes are auto-adjusted if needed
149-
# TODO: this doesn't seem to work atm and LCMTransport instantiation can fail
150149
pubsub.lcm.autoconf()
151150

152151
connection.lidar.transport = core.LCMTransport("/lidar", LidarMessage)
@@ -171,11 +170,10 @@ async def run(ip):
171170
global_planner.path.transport = core.pLCMTransport("/global_path")
172171

173172
local_planner.path.connect(global_planner.path)
174-
175173
local_planner.odom.connect(connection.odom)
176174

177175
local_planner.movecmd.transport = core.LCMTransport("/move", Vector3)
178-
local_planner.movecmd.connect(connection.movecmd)
176+
connection.movecmd.connect(local_planner.movecmd)
179177

180178
ctrl = dimos.deploy(ControlModule)
181179

@@ -207,13 +205,12 @@ async def run(ip):
207205
print(colors.green("starting foxglove bridge"))
208206
foxglove_bridge.start()
209207

210-
# uncomment to move the bot
211208
print(colors.green("starting ctrl"))
212209
ctrl.start()
213210

214211
print(colors.red("READY"))
215212

216-
await asyncio.sleep(10)
213+
await asyncio.sleep(2)
217214
print("querying system")
218215
print(mapper.costmap())
219216
while True:

dimos/robot/unitree_webrtc/type/lidar.py

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -86,14 +86,6 @@ def from_msg(cls: "LidarMessage", raw_message: RawLidarMsg) -> "LidarMessage":
8686
raw_msg=raw_message,
8787
)
8888

89-
def to_pointcloud2(self) -> PointCloud2:
90-
"""Convert to PointCloud2 message format."""
91-
return PointCloud2(
92-
pointcloud=self.pointcloud,
93-
frame_id=self.frame_id,
94-
ts=self.ts,
95-
)
96-
9789
def __repr__(self):
9890
return f"LidarMessage(ts={to_human_readable(self.ts)}, origin={self.origin}, resolution={self.resolution}, {self.pointcloud})"
9991

dimos/robot/unitree_webrtc/type/test_lidar.py

Lines changed: 0 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -31,21 +31,3 @@ def test_init():
3131
assert isinstance(raw_frame, dict)
3232
frame = LidarMessage.from_msg(raw_frame)
3333
assert isinstance(frame, LidarMessage)
34-
data = frame.to_pointcloud2().lcm_encode()
35-
assert len(data) > 0
36-
assert isinstance(data, bytes)
37-
38-
39-
@pytest.mark.tool
40-
def test_publish():
41-
lcm = LCM()
42-
lcm.start()
43-
44-
topic = Topic(topic="/lidar", lcm_type=PointCloud2)
45-
lidar = SensorReplay("office_lidar", autocast=LidarMessage.from_msg)
46-
47-
while True:
48-
for frame in lidar.iterate():
49-
print(frame)
50-
lcm.publish(topic, frame.to_pointcloud2())
51-
time.sleep(0.1)

0 commit comments

Comments
 (0)