Skip to content

Commit 2f7b7ca

Browse files
committed
added ROS-free URDF parsing to CLI (#110)
1 parent 1b79b73 commit 2f7b7ca

File tree

9 files changed

+226
-71
lines changed

9 files changed

+226
-71
lines changed

README.md

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -128,8 +128,13 @@ Next:
128128
```
129129

130130
## Command Line Interface
131-
> [!NOTE]
132-
> In these examples, the [lbr_fri_ros2_stack](https://github.com/lbr-stack/lbr_fri_ros2_stack/) is used. Make sure to follow [Quick Start](https://github.com/lbr-stack/lbr_fri_ros2_stack/#quick-start) first. However, you can also use your own robot description files.
131+
> [!TIP]
132+
> Examples use sample data under [test/assets/lbr_med7_r800](test/assets/lbr_med7_r800). Data is stored via Git Large File Storage (LFS). Data is cloned automatically when `git-lfs` is installed. To clone in retrospect:
133+
> ```shell
134+
> sudo apt install git-lfs
135+
> git lfs fetch --all
136+
> git lfs checkout
137+
> ```
133138

134139
### Segment
135140
This is a required step to generate robot masks.
@@ -153,8 +158,7 @@ rr-hydra \
153158
--mask-pattern mask_sam2_left_image_*.png \
154159
--depth-pattern depth_*.npy \
155160
--joint-states-pattern joint_states_*.npy \
156-
--ros-package lbr_description \
157-
--xacro-path urdf/med7/med7.xacro \
161+
--urdf-path test/assets/lbr_med7_r800/description/lbr_med7_r800.urdf \
158162
--root-link-name lbr_link_0 \
159163
--end-link-name lbr_link_7 \
160164
--number-of-points 5000 \
@@ -181,8 +185,7 @@ rr-cam-swarm \
181185
--c2 1.5 \
182186
--max-iterations 100 \
183187
--display-progress \
184-
--ros-package lbr_description \
185-
--xacro-path urdf/med7/med7.xacro \
188+
--urdf-path test/assets/lbr_med7_r800/description/lbr_med7_r800.urdf \
186189
--root-link-name lbr_link_0 \
187190
--end-link-name lbr_link_7 \
188191
--target-reduction 0.8 \
@@ -210,8 +213,7 @@ rr-mono-dr \
210213
--lr 0.01 \
211214
--max-iterations 100 \
212215
--display-progress \
213-
--ros-package lbr_description \
214-
--xacro-path urdf/med7/med7.xacro \
216+
--urdf-path test/assets/lbr_med7_r800/description/lbr_med7_r800.urdf \
215217
--root-link-name lbr_link_0 \
216218
--end-link-name lbr_link_7 \
217219
--camera-info-file test/assets/lbr_med7_r800/samples/left_camera_info.yaml \
@@ -237,8 +239,7 @@ rr-stereo-dr \
237239
--lr 0.01 \
238240
--max-iterations 100 \
239241
--display-progress \
240-
--ros-package lbr_description \
241-
--xacro-path urdf/med7/med7.xacro \
242+
--urdf-path test/assets/lbr_med7_r800/description/lbr_med7_r800.urdf \
242243
--root-link-name lbr_link_0 \
243244
--end-link-name lbr_link_7 \
244245
--left-camera-info-file test/assets/lbr_med7_r800/samples/left_camera_info.yaml \
@@ -267,8 +268,7 @@ Generate renders using the obtained extrinsics:
267268
rr-render \
268269
--batch-size 1 \
269270
--num-workers 0 \
270-
--ros-package lbr_description \
271-
--xacro-path urdf/med7/med7.xacro \
271+
--urdf-path test/assets/lbr_med7_r800/description/lbr_med7_r800.urdf \
272272
--root-link-name lbr_link_0 \
273273
--end-link-name lbr_link_7 \
274274
--camera-info-file test/assets/lbr_med7_r800/samples/left_camera_info.yaml \

cli/rr_cam_swarm.py

Lines changed: 34 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
from roboreg.io import (
1818
find_files,
1919
load_robot_data_from_ros_xacro,
20+
load_robot_data_from_urdf_file,
2021
parse_camera_info,
2122
parse_mono_data,
2223
)
@@ -29,6 +30,8 @@
2930
random_fov_eye_space_coordinates,
3031
)
3132

33+
from .util.validate import validate_urdf_source
34+
3235

3336
def args_factory() -> argparse.Namespace:
3437
parser = argparse.ArgumentParser(
@@ -96,17 +99,26 @@ def args_factory() -> argparse.Namespace:
9699
action="store_true",
97100
help="Display optimization progress.",
98101
)
102+
parser.add_argument(
103+
"--urdf-path",
104+
type=str,
105+
default="test/assets/lbr_med7_r800/description/lbr_med7_r800.urdf",
106+
help="Path to URDF file. Meshes resolved relative to this file. "
107+
"Mutually exclusive with --ros-package/--xacro-path.",
108+
)
99109
parser.add_argument(
100110
"--ros-package",
101111
type=str,
102-
default="lbr_description",
103-
help="Package where the URDF is located.",
112+
default=None,
113+
help="ROS package containing robot description. "
114+
"Requires --xacro-path. Mutually exclusive with --urdf-path.",
104115
)
105116
parser.add_argument(
106117
"--xacro-path",
107118
type=str,
108-
default="urdf/med7/med7.xacro",
109-
help="Path to the xacro file, relative to --ros-package.",
119+
default=None,
120+
help="Path to xacro file relative to --ros-package. "
121+
"Requires --ros-package. Mutually exclusive with --urdf-path.",
110122
)
111123
parser.add_argument(
112124
"--root-link-name",
@@ -180,6 +192,7 @@ def args_factory() -> argparse.Namespace:
180192
default=2,
181193
help="Number of concurrent compilation jobs for nvdiffrast. Only relevant on first run.",
182194
)
195+
validate_urdf_source(parser, parser.parse_args())
183196
return parser.parse_args()
184197

185198

@@ -315,14 +328,23 @@ def main() -> None:
315328
)
316329

317330
# instantiate robot
318-
robot_data = load_robot_data_from_ros_xacro(
319-
ros_package=args.ros_package,
320-
xacro_path=args.xacro_path,
321-
root_link_name=args.root_link_name,
322-
end_link_name=args.end_link_name,
323-
collision=args.collision_meshes,
324-
target_reduction=args.target_reduction,
325-
)
331+
if args.urdf_path is not None:
332+
robot_data = load_robot_data_from_urdf_file(
333+
urdf_path=args.urdf_path,
334+
root_link_name=args.root_link_name,
335+
end_link_name=args.end_link_name,
336+
collision=args.collision_meshes,
337+
target_reduction=args.target_reduction,
338+
)
339+
else:
340+
robot_data = load_robot_data_from_ros_xacro(
341+
ros_package=args.ros_package,
342+
xacro_path=args.xacro_path,
343+
root_link_name=args.root_link_name,
344+
end_link_name=args.end_link_name,
345+
collision=args.collision_meshes,
346+
target_reduction=args.target_reduction,
347+
)
326348
mesh_container = TorchMeshContainer(
327349
meshes=robot_data.meshes,
328350
batch_size=batch_size,

cli/rr_hydra.py

Lines changed: 32 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
from roboreg.io import (
1010
find_files,
1111
load_robot_data_from_ros_xacro,
12+
load_robot_data_from_urdf_file,
1213
parse_camera_info,
1314
parse_hydra_data,
1415
)
@@ -23,6 +24,8 @@
2324
to_homogeneous,
2425
)
2526

27+
from .util.validate import validate_urdf_source
28+
2629

2730
def args_factory() -> argparse.Namespace:
2831
parser = argparse.ArgumentParser(
@@ -53,17 +56,26 @@ def args_factory() -> argparse.Namespace:
5356
default="joint_states_*.npy",
5457
help="Joint state file pattern.",
5558
)
59+
parser.add_argument(
60+
"--urdf-path",
61+
type=str,
62+
default="test/assets/lbr_med7_r800/description/lbr_med7_r800.urdf",
63+
help="Path to URDF file. Meshes resolved relative to this file. "
64+
"Mutually exclusive with --ros-package/--xacro-path.",
65+
)
5666
parser.add_argument(
5767
"--ros-package",
5868
type=str,
59-
default="lbr_description",
60-
help="Package where the URDF is located.",
69+
default=None,
70+
help="ROS package containing robot description. "
71+
"Requires --xacro-path. Mutually exclusive with --urdf-path.",
6172
)
6273
parser.add_argument(
6374
"--xacro-path",
6475
type=str,
65-
default="urdf/med7/med7.xacro",
66-
help="Path to the xacro file, relative to --ros-package.",
76+
default=None,
77+
help="Path to xacro file relative to --ros-package. "
78+
"Requires --ros-package. Mutually exclusive with --urdf-path.",
6779
)
6880
parser.add_argument(
6981
"--root-link-name",
@@ -147,6 +159,7 @@ def args_factory() -> argparse.Namespace:
147159
default=10,
148160
help="Erosion kernel size for mask boundary. Larger value will result in larger boundary. The closer the robot, the larger the recommended kernel size.",
149161
)
162+
validate_urdf_source(parser, parser.parse_args())
150163
return parser.parse_args()
151164

152165

@@ -167,13 +180,21 @@ def main():
167180

168181
# instantiate robot
169182
batch_size = len(joint_states)
170-
robot_data = load_robot_data_from_ros_xacro(
171-
ros_package=args.ros_package,
172-
xacro_path=args.xacro_path,
173-
root_link_name=args.root_link_name,
174-
end_link_name=args.end_link_name,
175-
collision=args.collision_meshes,
176-
)
183+
if args.urdf_path is not None:
184+
robot_data = load_robot_data_from_urdf_file(
185+
urdf_path=args.urdf_path,
186+
root_link_name=args.root_link_name,
187+
end_link_name=args.end_link_name,
188+
collision=args.collision_meshes,
189+
)
190+
else:
191+
robot_data = load_robot_data_from_ros_xacro(
192+
ros_package=args.ros_package,
193+
xacro_path=args.xacro_path,
194+
root_link_name=args.root_link_name,
195+
end_link_name=args.end_link_name,
196+
collision=args.collision_meshes,
197+
)
177198
mesh_container = TorchMeshContainer(
178199
meshes=robot_data.meshes,
179200
batch_size=len(joint_states),

cli/rr_mono_dr.py

Lines changed: 37 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -18,10 +18,17 @@
1818
TorchMeshContainer,
1919
VirtualCamera,
2020
)
21-
from roboreg.io import find_files, load_robot_data_from_ros_xacro, parse_mono_data
21+
from roboreg.io import (
22+
find_files,
23+
load_robot_data_from_ros_xacro,
24+
load_robot_data_from_urdf_file,
25+
parse_mono_data,
26+
)
2227
from roboreg.losses import soft_dice_loss
2328
from roboreg.util import mask_distance_transform, mask_exponential_decay, overlay_mask
2429

30+
from .util.validate import validate_urdf_source
31+
2532

2633
class REGISTRATION_MODE(Enum):
2734
DISTANCE_FUNCTION = "distance-function"
@@ -74,17 +81,26 @@ def args_factory() -> argparse.Namespace:
7481
action="store_true",
7582
help="Display optimization progress.",
7683
)
84+
parser.add_argument(
85+
"--urdf-path",
86+
type=str,
87+
default="test/assets/lbr_med7_r800/description/lbr_med7_r800.urdf",
88+
help="Path to URDF file. Meshes resolved relative to this file. "
89+
"Mutually exclusive with --ros-package/--xacro-path.",
90+
)
7791
parser.add_argument(
7892
"--ros-package",
7993
type=str,
80-
default="lbr_description",
81-
help="Package where the URDF is located.",
94+
default=None,
95+
help="ROS package containing robot description. "
96+
"Requires --xacro-path. Mutually exclusive with --urdf-path.",
8297
)
8398
parser.add_argument(
8499
"--xacro-path",
85100
type=str,
86-
default="urdf/med7/med7.xacro",
87-
help="Path to the xacro file, relative to --ros-package.",
101+
default=None,
102+
help="Path to xacro file relative to --ros-package. "
103+
"Requires --ros-package. Mutually exclusive with --urdf-path.",
88104
)
89105
parser.add_argument(
90106
"--root-link-name",
@@ -146,6 +162,7 @@ def args_factory() -> argparse.Namespace:
146162
default=2,
147163
help="Number of concurrent compilation jobs for nvdiffrast. Only relevant on first run.",
148164
)
165+
validate_urdf_source(parser, parser.parse_args())
149166
return parser.parse_args()
150167

151168

@@ -188,13 +205,21 @@ def main() -> None:
188205
}
189206

190207
# instantiate robot
191-
robot_data = load_robot_data_from_ros_xacro(
192-
ros_package=args.ros_package,
193-
xacro_path=args.xacro_path,
194-
root_link_name=args.root_link_name,
195-
end_link_name=args.end_link_name,
196-
collision=args.collision_meshes,
197-
)
208+
if args.urdf_path is not None:
209+
robot_data = load_robot_data_from_urdf_file(
210+
urdf_path=args.urdf_path,
211+
root_link_name=args.root_link_name,
212+
end_link_name=args.end_link_name,
213+
collision=args.collision_meshes,
214+
)
215+
else:
216+
robot_data = load_robot_data_from_ros_xacro(
217+
ros_package=args.ros_package,
218+
xacro_path=args.xacro_path,
219+
root_link_name=args.root_link_name,
220+
end_link_name=args.end_link_name,
221+
collision=args.collision_meshes,
222+
)
198223
mesh_container = TorchMeshContainer(
199224
meshes=robot_data.meshes,
200225
batch_size=joint_states.shape[0],

0 commit comments

Comments
 (0)