Skip to content

Commit 42598c0

Browse files
authored
Merge pull request #54 from lbr-stack/rolling
default to visual meshes roboreg 0.4.5 (#53)
2 parents c61166f + 1cd04f4 commit 42598c0

File tree

3 files changed

+8
-8
lines changed

3 files changed

+8
-8
lines changed

roboreg_nodes/config/monocular_depth.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@
4848
device: cuda
4949
root_link_name: ""
5050
end_link_name: ""
51-
visual_meshes: False
51+
collision_meshes: False
5252

5353
renderer:
5454
enabled: False

roboreg_nodes/config/stereo_depth.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@
5858
device: cuda
5959
root_link_name: ""
6060
end_link_name: ""
61-
visual_meshes: False
61+
collision_meshes: False
6262

6363
renderer:
6464
enabled: False

roboreg_nodes/roboreg_nodes/reg/base.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ class _RobotModelParams:
4646
device: str
4747
root_link_name: str
4848
end_link_name: str
49-
visual_meshes: bool
49+
collision_meshes: bool
5050

5151
@dataclass
5252
class _RendererParams:
@@ -207,7 +207,7 @@ def _on_robot_description(self, msg: String) -> None:
207207
if self._robot_model_params.root_link_name == "":
208208
self._robot_model_params.root_link_name = (
209209
self._urdf_parser.link_names_with_meshes(
210-
self._robot_model_params.visual_meshes
210+
collision=self._robot_model_params.collision_meshes
211211
)[0]
212212
)
213213
self.get_logger().info(
@@ -216,7 +216,7 @@ def _on_robot_description(self, msg: String) -> None:
216216
if self._robot_model_params.end_link_name == "":
217217
self._robot_model_params.end_link_name = (
218218
self._urdf_parser.link_names_with_meshes(
219-
self._robot_model_params.visual_meshes
219+
collision=self._robot_model_params.collision_meshes
220220
)[-1]
221221
)
222222
self.get_logger().info(
@@ -257,7 +257,7 @@ def _meshes_factory(
257257
mesh_paths=self._urdf_parser.ros_package_mesh_paths(
258258
root_link_name=self._robot_model_params.root_link_name,
259259
end_link_name=self._robot_model_params.end_link_name,
260-
visual=self._robot_model_params.visual_meshes,
260+
collision=self._robot_model_params.collision_meshes,
261261
),
262262
batch_size=batch_size,
263263
device=self._robot_model_params.device,
@@ -297,7 +297,7 @@ def _declare_common_parameters(self) -> None:
297297
("robot_model.device", "cuda" if torch.cuda.is_available() else "cpu"),
298298
("robot_model.root_link_name", ""),
299299
("robot_model.end_link_name", ""),
300-
("robot_model.visual_meshes", False),
300+
("robot_model.collision_meshes", False),
301301
],
302302
)
303303
self.declare_parameters(
@@ -374,7 +374,7 @@ def _get_common_parameters(self) -> None:
374374
end_link_name=self.get_parameter("robot_model.end_link_name")
375375
.get_parameter_value()
376376
.string_value,
377-
visual_meshes=self.get_parameter("robot_model.visual_meshes")
377+
collision_meshes=self.get_parameter("robot_model.collision_meshes")
378378
.get_parameter_value()
379379
.bool_value,
380380
)

0 commit comments

Comments
 (0)