Skip to content

Commit 64728da

Browse files
authored
Merge pull request #108 from lbr-stack/fix/roboreg-100/robot_ros_dependency
Remove ROS dependency in Robot constructor
2 parents 3330220 + b0cede5 commit 64728da

39 files changed

+947
-615
lines changed

.github/workflows/tests.yaml

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,9 @@ jobs:
1818
steps:
1919
# Check out the repository.
2020
- name: Checkout code
21-
uses: actions/checkout@v3
21+
uses: actions/checkout@v6
22+
with:
23+
lfs: true
2224

2325
# Set up the specified Python version.
2426
- name: Set up Python ${{ matrix.python-version }}

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -183,7 +183,7 @@ rr-cam-swarm \
183183
--xacro-path urdf/med7/med7.xacro \
184184
--root-link-name lbr_link_0 \
185185
--end-link-name lbr_link_7 \
186-
--target-reduction 0.95 \
186+
--target-reduction 0.8 \
187187
--scale 0.1 \
188188
--n-samples 1 \
189189
--camera-info-file test/assets/lbr_med7/zed2i/left_camera_info.yaml \

cli/rr_cam_swarm.py

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,13 @@
11
import argparse
22
import os
3+
from typing import Union
34

45
import cv2
56
import numpy as np
67
import torch
78

89
from roboreg import differentiable as rrd
9-
from roboreg.io import find_files, parse_camera_info, parse_mono_data
10+
from roboreg.io import URDFParser, find_files, parse_camera_info, parse_mono_data
1011
from roboreg.losses import soft_dice_loss
1112
from roboreg.optim import LinearParticleSwarm, ParticleSwarmOptimizer
1213
from roboreg.util import (
@@ -179,7 +180,7 @@ def instantiate_particles(
179180
eye_min_dist: float,
180181
eye_max_dist: float,
181182
angle_interval: float,
182-
device: torch.device = torch.device("cuda"),
183+
device: Union[torch.device, str] = "cuda",
183184
) -> torch.Tensor:
184185
r"""Instantiate the particles for the optimization randomly under field of view constraints.
185186
Particles (camera poses) are represented using eye space coordinates (eye, center, angle).
@@ -193,7 +194,7 @@ def instantiate_particles(
193194
eye_min_dist (float): The minimum distance of the eye from the origin.
194195
eye_max_dist (float): The maximum distance of the eye from the origin.
195196
angle_interval (float): The angle interval in which to sample the rotation angle.
196-
device (torch.device): The device to instantiate the particles on.
197+
device (Union[torch.device, str]): The device to instantiate the particles on.
197198
198199
Returns:
199200
torch.Tensor: The particles of shape (n_particles, 7).
@@ -249,7 +250,6 @@ def main() -> None:
249250
mask_files = np.array(mask_files)[random_indices].tolist()
250251
joint_states_files = np.array(joint_states_files)[random_indices].tolist()
251252
images, joint_states, masks = parse_mono_data(
252-
path=args.path,
253253
image_files=image_files,
254254
mask_files=mask_files,
255255
joint_states_files=joint_states_files,
@@ -302,9 +302,10 @@ def main() -> None:
302302
device=device,
303303
)
304304

305-
urdf_parser = rrd.URDFParser()
306-
urdf_parser.from_ros_xacro(ros_package=args.ros_package, xacro_path=args.xacro_path)
307-
robot = rrd.Robot(
305+
urdf_parser = URDFParser.from_ros_xacro(
306+
ros_package=args.ros_package, xacro_path=args.xacro_path
307+
)
308+
robot = rrd.Robot.from_urdf_parser(
308309
urdf_parser=urdf_parser,
309310
root_link_name=args.root_link_name,
310311
end_link_name=args.end_link_name,

cli/rr_hydra.py

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -155,16 +155,16 @@ def main():
155155
mask_files = find_files(args.path, args.mask_pattern)
156156
depth_files = find_files(args.path, args.depth_pattern)
157157
joint_states, masks, depths = parse_hydra_data(
158-
path=args.path,
159158
joint_states_files=joint_states_files,
160159
mask_files=mask_files,
161160
depth_files=depth_files,
162161
)
163162
height, width, intrinsics = parse_camera_info(args.camera_info_file)
164163

165164
# instantiate kinematics
166-
urdf_parser = URDFParser()
167-
urdf_parser.from_ros_xacro(ros_package=args.ros_package, xacro_path=args.xacro_path)
165+
urdf_parser = URDFParser.from_ros_xacro(
166+
ros_package=args.ros_package, xacro_path=args.xacro_path
167+
)
168168
root_link_name = args.root_link_name
169169
end_link_name = args.end_link_name
170170
if root_link_name == "":
@@ -184,7 +184,7 @@ def main():
184184

185185
# instantiate robot
186186
batch_size = len(joint_states)
187-
robot = Robot(
187+
robot = Robot.from_urdf_parser(
188188
urdf_parser=urdf_parser,
189189
root_link_name=root_link_name,
190190
end_link_name=end_link_name,
@@ -226,7 +226,9 @@ def main():
226226
mesh_normals = []
227227
for i in range(batch_size):
228228
mesh_normals.append(
229-
compute_vertex_normals(vertices=mesh_vertices[i], faces=robot.faces)
229+
compute_vertex_normals(
230+
vertices=mesh_vertices[i], faces=robot.mesh_container.faces
231+
)
230232
)
231233

232234
# clean observed vertices and turn into tensor

cli/rr_mono_dr.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -153,7 +153,6 @@ def main() -> None:
153153
joint_states_files = find_files(args.path, args.joint_states_pattern)
154154
mask_files = find_files(args.path, args.mask_pattern)
155155
images, joint_states, masks = parse_mono_data(
156-
path=args.path,
157156
image_files=image_files,
158157
joint_states_files=joint_states_files,
159158
mask_files=mask_files,

cli/rr_render.py

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
import argparse
22
import os
3-
import pathlib
3+
from pathlib import Path
44

55
import cv2
66
import numpy as np
@@ -142,7 +142,7 @@ def main():
142142
num_workers=args.num_workers,
143143
)
144144

145-
output_path = pathlib.Path(args.output_path)
145+
output_path = Path(args.output_path)
146146
if not output_path.exists():
147147
output_path.mkdir(parents=True)
148148

@@ -162,13 +162,12 @@ def main():
162162
images = images.numpy()
163163
renders = (renders * 255.0).squeeze(-1).cpu().numpy().astype(np.uint8)
164164
for render, image, image_file in zip(renders, images, image_files):
165-
image_stem = pathlib.Path(image_file).stem
166-
image_suffix = pathlib.Path(image_file).suffix
165+
image_file = Path(image_file)
166+
output_file = (
167+
output_path / f"overlay_render_{image_file.stem + image_file.suffix}"
168+
)
167169
cv2.imwrite(
168-
os.path.join(
169-
str(output_path.absolute()),
170-
f"overlay_render_{image_stem + image_suffix}",
171-
),
170+
output_file,
172171
overlay_mask(image, render, args.color, scale=1.0),
173172
)
174173

cli/rr_sam2.py

Lines changed: 8 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,4 @@
11
import argparse
2-
import os
3-
import pathlib
42

53
import cv2
64
import numpy as np
@@ -48,8 +46,7 @@ def args_factory() -> argparse.Namespace:
4846

4947
def main():
5048
args = args_factory()
51-
path = pathlib.Path(args.path)
52-
image_names = find_files(path.absolute(), args.pattern)
49+
image_files = find_files(args.path, args.pattern)
5350

5451
# detect
5552
detector = OpenCVDetector(
@@ -60,23 +57,21 @@ def main():
6057
# segment
6158
segmentor = Sam2Segmentor(model_id=args.model_id, device=args.device)
6259

63-
for image_name in progress.track(image_names, description="Generating masks..."):
64-
image_stem = pathlib.Path(image_name).stem
65-
image_suffix = pathlib.Path(image_name).suffix
66-
img = cv2.imread(os.path.join(path.absolute(), image_name))
60+
for image_file in progress.track(image_files, description="Generating masks..."):
61+
img = cv2.imread(image_file)
6762
annotations = False
6863
if args.pre_annotated:
6964
try:
7065
samples, labels = detector.read(
71-
path=os.path.join(path.absolute(), f"{image_stem}_samples.csv")
66+
path=image_file.parent / f"{image_file.stem}_samples.csv"
7267
)
7368
annotations = True
7469
except FileNotFoundError:
7570
pass
7671
if not annotations:
7772
samples, labels = detector.detect(img)
7873
detector.write(
79-
path=os.path.join(path.absolute(), f"{image_stem}_samples.csv"),
74+
path=image_file.parent / f"{image_file.stem}_samples.csv",
8075
samples=samples,
8176
labels=labels,
8277
)
@@ -86,15 +81,9 @@ def main():
8681
overlay = overlay_mask(img, mask, mode="g", scale=1.0)
8782

8883
# write probability and mask
89-
probability_path = os.path.join(
90-
path.absolute(), f"probability_sam2_{image_stem + image_suffix}"
91-
)
92-
mask_path = os.path.join(
93-
path.absolute(), f"mask_sam2_{image_stem + image_suffix}"
94-
)
95-
overlay_path = os.path.join(
96-
path.absolute(), f"overlay_sam2_{image_stem + image_suffix}"
97-
)
84+
probability_path = image_file.parent / f"probability_sam2_{image_file.name}"
85+
mask_path = image_file.parent / f"mask_sam2_{image_file.name}"
86+
overlay_path = image_file.parent / f"overlay_sam2_{image_file.name}"
9887
cv2.imwrite(probability_path, (probability * 255.0).astype(np.uint8))
9988
cv2.imwrite(mask_path, mask)
10089
cv2.imwrite(overlay_path, overlay)

cli/rr_stereo_dr.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -186,7 +186,6 @@ def main() -> None:
186186
right_mask_files = find_files(args.path, args.right_mask_pattern)
187187
left_images, right_images, joint_states, left_masks, right_masks = (
188188
parse_stereo_data(
189-
path=args.path,
190189
left_image_files=left_image_files,
191190
right_image_files=right_image_files,
192191
joint_states_files=joint_states_files,

pyproject.toml

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,6 @@ dependencies = [
3232
"torch",
3333
"transformations",
3434
"trimesh",
35-
"xacro",
3635
]
3736
classifiers = [
3837
"Programming Language :: Python :: 3",

roboreg/differentiable/kinematics.py

Lines changed: 10 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -1,45 +1,33 @@
1-
from typing import Dict
1+
from typing import Dict, Union
22

33
import pytorch_kinematics as pk
44
import torch
55

6-
from roboreg.io import URDFParser
7-
86

97
class TorchKinematics:
108
__slots__ = [
119
"_root_link_name",
1210
"_end_link_name",
1311
"_chain",
14-
"_mesh_origins_lookup",
1512
"_device",
1613
]
1714

1815
def __init__(
1916
self,
20-
urdf_parser: URDFParser,
17+
urdf: str,
2118
root_link_name: str,
2219
end_link_name: str,
23-
device: torch.device = "cuda",
20+
device: Union[torch.device, str] = "cuda",
2421
) -> None:
2522
self._root_link_name = root_link_name
2623
self._end_link_name = end_link_name
2724
self._chain = self._build_serial_chain_from_urdf(
28-
urdf_parser.urdf,
25+
urdf=urdf,
2926
root_link_name=self._root_link_name,
3027
end_link_name=self._end_link_name,
3128
)
32-
33-
self._mesh_origins_lookup = urdf_parser.mesh_origins(
34-
root_link_name=root_link_name, end_link_name=end_link_name
35-
)
36-
self._mesh_origins_lookup = {
37-
key: torch.from_numpy(value).to(device=device, dtype=torch.float32)
38-
for key, value in self._mesh_origins_lookup.items()
39-
}
40-
41-
# default move to device
42-
self.to(device=device)
29+
self._device = torch.device(device) if isinstance(device, str) else device
30+
self.to(device=self._device)
4331

4432
def _build_serial_chain_from_urdf(
4533
self, urdf: str, root_link_name: str, end_link_name: str
@@ -48,20 +36,13 @@ def _build_serial_chain_from_urdf(
4836
urdf, end_link_name=end_link_name, root_link_name=root_link_name
4937
)
5038

51-
def to(self, device: torch.device) -> None:
39+
def to(self, device: Union[torch.device, str]) -> None:
5240
self._chain.to(device=device)
53-
for link_name in self._mesh_origins_lookup:
54-
self._mesh_origins_lookup[link_name] = self._mesh_origins_lookup[
55-
link_name
56-
].to(device=device)
57-
self._device = device
41+
self._device = torch.device(device) if isinstance(device, str) else device
5842

59-
def mesh_forward_kinematics(self, q: torch.Tensor) -> Dict[str, torch.Tensor]:
60-
r"""Computes forward kinematics and returns corresponding homogeneous transformations.
61-
Corrects for mesh offsets. Meshes that are tranformed by the returned transformation appear physically correct.
62-
"""
43+
def forward_kinematics(self, q: torch.Tensor) -> Dict[str, torch.Tensor]:
6344
ht_lookup = {
64-
key: value.get_matrix() @ self._mesh_origins_lookup[key]
45+
key: value.get_matrix()
6546
for key, value in self._chain.forward_kinematics(q, end_only=False).items()
6647
}
6748
return ht_lookup

0 commit comments

Comments
 (0)