Skip to content

Commit bd792ce

Browse files
authored
Merge pull request #491 - Full Transforms Architecture in Python
### allows multiple modules to emit different parts of transform graph and do arbitrary instant lookups on this graph easy oneliners to ask questions like "how do I turn the body to face this person that I see with my camera" - Implemented generic collection for timestamped objects (sensor messages, transforms, poses) (required to support historical Transform tree lookups, and time bounded storage) - Time series collection allows to search for closest points, merge, calculate time distances etc. - Implemented generic transform interface - Implemented LCM transform transport on top of that - Unitree emitting simple world -> base_link transform (from odom) - next steps to check people follow, rendering detection boxes etc <img width="894" height="1201" alt="2025-07-25_05-55" src="https://github.com/user-attachments/assets/15a6fd0e-77f3-4cc1-b732-05c693c81979" /> Former-commit-id: 239ade3 [formerly f5658ea] Former-commit-id: a58d0a7
1 parent b7ab58d commit bd792ce

14 files changed

Lines changed: 1327 additions & 180 deletions

File tree

dimos/core/transport.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ def subscribe(self, selfstream: In[T], callback: Callable[[T], None]) -> None:
7272
if not self._started:
7373
self.lcm.start()
7474
self._started = True
75-
self.lcm.subscribe(self.topic, lambda msg, topic: callback(msg))
75+
return self.lcm.subscribe(self.topic, lambda msg, topic: callback(msg))
7676

7777

7878
class LCMTransport(PubSubTransport[T]):
@@ -96,7 +96,7 @@ def subscribe(self, selfstream: In[T], callback: Callable[[T], None]) -> None:
9696
if not self._started:
9797
self.lcm.start()
9898
self._started = True
99-
self.lcm.subscribe(self.topic, lambda msg, topic: callback(msg))
99+
return self.lcm.subscribe(self.topic, lambda msg, topic: callback(msg))
100100

101101

102102
class ZenohTransport(PubSubTransport[T]): ...

dimos/msgs/geometry_msgs/Transform.py

Lines changed: 68 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,14 +14,11 @@
1414

1515
from __future__ import annotations
1616

17-
import struct
1817
import time
19-
from io import BytesIO
2018
from typing import BinaryIO
2119

2220
from dimos_lcm.geometry_msgs import Transform as LCMTransform
2321
from dimos_lcm.geometry_msgs import TransformStamped as LCMTransformStamped
24-
from plum import dispatch
2522

2623
from dimos.msgs.geometry_msgs.Quaternion import Quaternion
2724
from dimos.msgs.geometry_msgs.Vector3 import Vector3
@@ -79,6 +76,74 @@ def lcm_transform(self) -> LCMTransformStamped:
7976
),
8077
)
8178

79+
def __add__(self, other: "Transform") -> "Transform":
80+
"""Compose two transforms (transform composition).
81+
82+
The operation self + other represents applying transformation 'other'
83+
in the coordinate frame defined by 'self'. This is equivalent to:
84+
- First apply transformation 'self' (from frame A to frame B)
85+
- Then apply transformation 'other' (from frame B to frame C)
86+
87+
Args:
88+
other: The transform to compose with this one
89+
90+
Returns:
91+
A new Transform representing the composed transformation
92+
93+
Example:
94+
t1 = Transform(Vector3(1, 0, 0), Quaternion(0, 0, 0, 1))
95+
t2 = Transform(Vector3(2, 0, 0), Quaternion(0, 0, 0, 1))
96+
t3 = t1 + t2 # Combined transform: translation (3, 0, 0)
97+
"""
98+
if not isinstance(other, Transform):
99+
raise TypeError(f"Cannot add Transform and {type(other).__name__}")
100+
101+
# Compose orientations: self.rotation * other.rotation
102+
new_rotation = self.rotation * other.rotation
103+
104+
# Transform other's translation by self's rotation, then add to self's translation
105+
rotated_translation = self.rotation.rotate_vector(other.translation)
106+
new_translation = self.translation + rotated_translation
107+
108+
return Transform(
109+
translation=new_translation,
110+
rotation=new_rotation,
111+
frame_id=self.frame_id,
112+
child_frame_id=other.child_frame_id,
113+
ts=self.ts,
114+
)
115+
116+
@classmethod
117+
def from_pose(cls, frame_id: str, pose: "Pose | PoseStamped") -> "Transform":
118+
"""Create a Transform from a Pose or PoseStamped.
119+
120+
Args:
121+
pose: A Pose or PoseStamped object to convert
122+
123+
Returns:
124+
A Transform with the same translation and rotation as the pose
125+
"""
126+
# Import locally to avoid circular imports
127+
from dimos.msgs.geometry_msgs.Pose import Pose
128+
from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped
129+
130+
# Handle both Pose and PoseStamped
131+
if isinstance(pose, PoseStamped):
132+
return cls(
133+
translation=pose.position,
134+
rotation=pose.orientation,
135+
frame_id=pose.frame_id,
136+
child_frame_id=frame_id,
137+
ts=pose.ts,
138+
)
139+
elif isinstance(pose, Pose):
140+
return cls(
141+
translation=pose.position,
142+
rotation=pose.orientation,
143+
)
144+
else:
145+
raise TypeError(f"Expected Pose or PoseStamped, got {type(pose).__name__}")
146+
82147
def lcm_encode(self) -> bytes:
83148
# we get a circular import otherwise
84149
from dimos.msgs.tf2_msgs.TFMessage import TFMessage

dimos/msgs/geometry_msgs/test_Transform.py

Lines changed: 154 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919
from dimos_lcm.geometry_msgs import Transform as LCMTransform
2020
from dimos_lcm.geometry_msgs import TransformStamped as LCMTransformStamped
2121

22-
from dimos.msgs.geometry_msgs import Pose, Quaternion, Transform, Vector3
22+
from dimos.msgs.geometry_msgs import Pose, PoseStamped, Quaternion, Transform, Vector3
2323

2424

2525
def test_transform_initialization():
@@ -228,3 +228,156 @@ def test_lcm_encode_decode():
228228
decoded_transform = Transform.lcm_decode(data)
229229

230230
assert decoded_transform == transform
231+
232+
233+
def test_transform_addition():
234+
# Test 1: Simple translation addition (no rotation)
235+
t1 = Transform(
236+
translation=Vector3(1, 0, 0),
237+
rotation=Quaternion(0, 0, 0, 1), # identity rotation
238+
)
239+
t2 = Transform(
240+
translation=Vector3(2, 0, 0),
241+
rotation=Quaternion(0, 0, 0, 1), # identity rotation
242+
)
243+
t3 = t1 + t2
244+
assert t3.translation == Vector3(3, 0, 0)
245+
assert t3.rotation == Quaternion(0, 0, 0, 1)
246+
247+
# Test 2: 90-degree rotation composition
248+
# First transform: move 1 unit in X
249+
t1 = Transform(
250+
translation=Vector3(1, 0, 0),
251+
rotation=Quaternion(0, 0, 0, 1), # identity
252+
)
253+
# Second transform: move 1 unit in X with 90-degree rotation around Z
254+
angle = np.pi / 2
255+
t2 = Transform(
256+
translation=Vector3(1, 0, 0),
257+
rotation=Quaternion(0, 0, np.sin(angle / 2), np.cos(angle / 2)),
258+
)
259+
t3 = t1 + t2
260+
assert t3.translation == Vector3(2, 0, 0)
261+
# Rotation should be 90 degrees around Z
262+
assert np.isclose(t3.rotation.x, 0.0, atol=1e-10)
263+
assert np.isclose(t3.rotation.y, 0.0, atol=1e-10)
264+
assert np.isclose(t3.rotation.z, np.sin(angle / 2), atol=1e-10)
265+
assert np.isclose(t3.rotation.w, np.cos(angle / 2), atol=1e-10)
266+
267+
# Test 3: Rotation affects translation
268+
# First transform: 90-degree rotation around Z
269+
t1 = Transform(
270+
translation=Vector3(0, 0, 0),
271+
rotation=Quaternion(0, 0, np.sin(angle / 2), np.cos(angle / 2)), # 90° around Z
272+
)
273+
# Second transform: move 1 unit in X
274+
t2 = Transform(
275+
translation=Vector3(1, 0, 0),
276+
rotation=Quaternion(0, 0, 0, 1), # identity
277+
)
278+
t3 = t1 + t2
279+
# X direction rotated 90° becomes Y direction
280+
assert np.isclose(t3.translation.x, 0.0, atol=1e-10)
281+
assert np.isclose(t3.translation.y, 1.0, atol=1e-10)
282+
assert np.isclose(t3.translation.z, 0.0, atol=1e-10)
283+
# Rotation remains 90° around Z
284+
assert np.isclose(t3.rotation.z, np.sin(angle / 2), atol=1e-10)
285+
assert np.isclose(t3.rotation.w, np.cos(angle / 2), atol=1e-10)
286+
287+
# Test 4: Frame tracking
288+
t1 = Transform(
289+
translation=Vector3(1, 0, 0),
290+
rotation=Quaternion(0, 0, 0, 1),
291+
frame_id="world",
292+
child_frame_id="robot",
293+
)
294+
t2 = Transform(
295+
translation=Vector3(2, 0, 0),
296+
rotation=Quaternion(0, 0, 0, 1),
297+
frame_id="robot",
298+
child_frame_id="sensor",
299+
)
300+
t3 = t1 + t2
301+
assert t3.frame_id == "world"
302+
assert t3.child_frame_id == "sensor"
303+
304+
# Test 5: Type error
305+
with pytest.raises(TypeError):
306+
t1 + "not a transform"
307+
308+
309+
def test_transform_from_pose():
310+
"""Test converting Pose to Transform"""
311+
# Create a Pose with position and orientation
312+
pose = Pose(
313+
position=Vector3(1.0, 2.0, 3.0),
314+
orientation=Quaternion(0.0, 0.0, 0.707, 0.707), # 90 degrees around Z
315+
)
316+
317+
# Convert to Transform
318+
transform = Transform.from_pose("base_link", pose)
319+
320+
# Check that translation and rotation match
321+
assert transform.translation == pose.position
322+
assert transform.rotation == pose.orientation
323+
assert transform.frame_id == "world" # default frame_id
324+
assert transform.child_frame_id == "base_link" # passed as first argument
325+
326+
327+
def test_transform_from_pose_stamped():
328+
"""Test converting PoseStamped to Transform"""
329+
# Create a PoseStamped with position, orientation, timestamp and frame
330+
test_time = time.time()
331+
pose_stamped = PoseStamped(
332+
ts=test_time,
333+
frame_id="map",
334+
position=Vector3(4.0, 5.0, 6.0),
335+
orientation=Quaternion(0.0, 0.707, 0.0, 0.707), # 90 degrees around Y
336+
)
337+
338+
# Convert to Transform
339+
transform = Transform.from_pose("robot_base", pose_stamped)
340+
341+
# Check that all fields match
342+
assert transform.translation == pose_stamped.position
343+
assert transform.rotation == pose_stamped.orientation
344+
assert transform.frame_id == pose_stamped.frame_id
345+
assert transform.ts == pose_stamped.ts
346+
assert transform.child_frame_id == "robot_base" # passed as first argument
347+
348+
349+
def test_transform_from_pose_variants():
350+
"""Test from_pose with different Pose initialization methods"""
351+
# Test with Pose created from x,y,z
352+
pose1 = Pose(1.0, 2.0, 3.0)
353+
transform1 = Transform.from_pose("base_link", pose1)
354+
assert transform1.translation.x == 1.0
355+
assert transform1.translation.y == 2.0
356+
assert transform1.translation.z == 3.0
357+
assert transform1.rotation.w == 1.0 # Identity quaternion
358+
359+
# Test with Pose created from tuple
360+
pose2 = Pose(([7.0, 8.0, 9.0], [0.0, 0.0, 0.0, 1.0]))
361+
transform2 = Transform.from_pose("base_link", pose2)
362+
assert transform2.translation.x == 7.0
363+
assert transform2.translation.y == 8.0
364+
assert transform2.translation.z == 9.0
365+
366+
# Test with Pose created from dict
367+
pose3 = Pose({"position": [10.0, 11.0, 12.0], "orientation": [0.0, 0.0, 0.0, 1.0]})
368+
transform3 = Transform.from_pose("base_link", pose3)
369+
assert transform3.translation.x == 10.0
370+
assert transform3.translation.y == 11.0
371+
assert transform3.translation.z == 12.0
372+
373+
374+
def test_transform_from_pose_invalid_type():
375+
"""Test that from_pose raises TypeError for invalid types"""
376+
with pytest.raises(TypeError):
377+
Transform.from_pose("not a pose")
378+
379+
with pytest.raises(TypeError):
380+
Transform.from_pose(42)
381+
382+
with pytest.raises(TypeError):
383+
Transform.from_pose(None)

dimos/msgs/tf2_msgs/TFMessage.py

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -60,11 +60,8 @@ def lcm_encode(self) -> bytes:
6060
If not provided, defaults to "base_link" for all.
6161
"""
6262

63-
print("WILL MAP", self.transforms)
6463
res = list(map(lambda t: t.lcm_transform(), self.transforms))
65-
print("RES IS", res)
6664

67-
print("HEADER", res[0].header)
6865
lcm_msg = LCMTFMessage(
6966
transforms_length=len(self.transforms),
7067
transforms=res,

dimos/protocol/service/lcmservice.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
from typing import Any, Callable, Optional, Protocol, runtime_checkable
2525

2626
import lcm
27+
2728
from dimos.protocol.service.spec import Service
2829

2930

@@ -161,7 +162,7 @@ class Topic:
161162
def __str__(self) -> str:
162163
if self.lcm_type is None:
163164
return self.topic
164-
return f"{self.topic}#{self.lcm_type.name}"
165+
return f"{self.topic}#{self.lcm_type.msg_name}"
165166

166167

167168
class LCMService(Service[LCMConfig]):

0 commit comments

Comments
 (0)