diff --git a/src/pycram/cache_manager.py b/src/pycram/cache_manager.py index 3e6a9889d..29bc5c2ba 100644 --- a/src/pycram/cache_manager.py +++ b/src/pycram/cache_manager.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import glob import os import pathlib @@ -5,8 +7,11 @@ from typing_extensions import List, TYPE_CHECKING, Optional +from .ros.logging import loginfo + if TYPE_CHECKING: from .description import ObjectDescription + from .datastructures.pose import Transform class CacheManager: @@ -49,8 +54,9 @@ def delete_cache_dir(self): shutil.rmtree(self.cache_dir) def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, - object_description: 'ObjectDescription', object_name: str, - scale_mesh: Optional[float] = None) -> str: + object_description: ObjectDescription, object_name: str, + scale_mesh: Optional[float] = None, + mesh_transform: Optional[Transform] = None) -> str: """ Check if the file is already in the cache directory, if not preprocess and save in the cache. @@ -60,6 +66,7 @@ def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, :param object_description: The object description of the file. :param object_name: The name of the object. :param scale_mesh: The scale of the mesh. + :param mesh_transform: The transformation matrix to apply to the mesh. :return: The path of the cached file. """ path_object = pathlib.Path(path) @@ -73,7 +80,9 @@ def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, if not self.is_cached(path, object_description) or ignore_cached_files: # if file is not yet cached preprocess the description file and save it in the cache directory. path = self.look_for_file_in_data_dir(path_object) - object_description.generate_description_from_file(path, object_name, extension, cache_path, scale_mesh) + object_description.original_path = path + object_description.generate_description_from_file(path, object_name, extension, cache_path, + scale_mesh, mesh_transform) return cache_path @@ -90,7 +99,7 @@ def look_for_file_in_data_dir(self, path_object: pathlib.Path) -> str: for file in glob.glob(str(data_path), recursive=True): file_path = pathlib.Path(file) if file_path.name == name: - print(f"Found file {name} in {file_path}") + loginfo(f"Found file {name} in {file_path}") return str(file_path) raise FileNotFoundError( @@ -103,7 +112,7 @@ def create_cache_dir_if_not_exists(self): if not pathlib.Path(self.cache_dir).exists(): os.mkdir(self.cache_dir) - def is_cached(self, path: str, object_description: 'ObjectDescription') -> bool: + def is_cached(self, path: str, object_description: ObjectDescription) -> bool: """ Check if the file in the given path is already cached or if there is already a cached file with the given name, this is the case if a .stl, .obj file or a description from @@ -125,7 +134,7 @@ def check_with_extension(self, path: str) -> bool: full_path = pathlib.Path(os.path.join(self.cache_dir, file_name)) return full_path.exists() - def check_without_extension(self, path: str, object_description: 'ObjectDescription') -> bool: + def check_without_extension(self, path: str, object_description: ObjectDescription) -> bool: """ Check if the file in the given path exists in the cache directory the given file extension. Instead, replace the given extension with the extension of the used ObjectDescription and check for that one. diff --git a/src/pycram/datastructures/dataclasses.py b/src/pycram/datastructures/dataclasses.py index f20fb4714..c6f55bf52 100644 --- a/src/pycram/datastructures/dataclasses.py +++ b/src/pycram/datastructures/dataclasses.py @@ -4,10 +4,12 @@ from copy import deepcopy, copy from dataclasses import dataclass, field -from typing_extensions import List, Optional, Tuple, Callable, Dict, Any, Union, TYPE_CHECKING +import numpy as np +import trimesh +from typing_extensions import List, Optional, Tuple, Callable, Dict, Any, Union, TYPE_CHECKING, Sequence from .enums import JointType, Shape, VirtualMobileBaseJointName -from .pose import Pose, Point +from .pose import Pose, Point, Transform from ..validation.error_checkers import calculate_joint_position_error, is_error_acceptable if TYPE_CHECKING: @@ -88,7 +90,7 @@ def get_rgb(self) -> List[float]: @dataclass -class AxisAlignedBoundingBox: +class BoundingBox: """ Dataclass for storing an axis-aligned bounding box. """ @@ -99,15 +101,24 @@ class AxisAlignedBoundingBox: max_y: float max_z: float - @classmethod - def from_min_max(cls, min_point: List[float], max_point: List[float]): + def get_points_list(self) -> List[List[float]]: """ - Set the axis-aligned bounding box from a minimum and maximum point. + :return: The points of the bounding box as a list of lists of floats. + """ + return list(filter(get_point_as_list, self.get_points())) - :param min_point: The minimum point - :param max_point: The maximum point + def get_points(self) -> List[Point]: """ - return cls(min_point[0], min_point[1], min_point[2], max_point[0], max_point[1], max_point[2]) + :return: The points of the bounding box as a list of Point instances. + """ + return [Point(self.min_x, self.min_y, self.min_z), + Point(self.min_x, self.min_y, self.max_z), + Point(self.min_x, self.max_y, self.min_z), + Point(self.min_x, self.max_y, self.max_z), + Point(self.max_x, self.min_y, self.min_z), + Point(self.max_x, self.min_y, self.max_z), + Point(self.max_x, self.max_y, self.min_z), + Point(self.max_x, self.max_y, self.max_z)] def get_min_max_points(self) -> Tuple[Point, Point]: """ @@ -158,6 +169,111 @@ def depth(self) -> float: return self.max_y - self.min_y +@dataclass +class AxisAlignedBoundingBox(BoundingBox): + + @classmethod + def from_multiple_bounding_boxes(cls, bounding_boxes: List[AxisAlignedBoundingBox]) -> 'AxisAlignedBoundingBox': + """ + Set the axis-aligned bounding box from multiple axis-aligned bounding boxes. + + :param bounding_boxes: The list of axis-aligned bounding boxes. + """ + min_x = min([box.min_x for box in bounding_boxes]) + min_y = min([box.min_y for box in bounding_boxes]) + min_z = min([box.min_z for box in bounding_boxes]) + max_x = max([box.max_x for box in bounding_boxes]) + max_y = max([box.max_y for box in bounding_boxes]) + max_z = max([box.max_z for box in bounding_boxes]) + return cls(min_x, min_y, min_z, max_x, max_y, max_z) + + def get_transformed_box(self, transform: Transform) -> 'AxisAlignedBoundingBox': + """ + Apply a transformation to the axis-aligned bounding box and return the transformed axis-aligned bounding box. + + :param transform: The transformation to apply + :return: The transformed axis-aligned bounding box + """ + transformed_points = transform.apply_transform_to_array_of_points(np.array(self.get_min_max())) + min_p = [min(transformed_points[:, i]) for i in range(3)] + max_p = [max(transformed_points[:, i]) for i in range(3)] + return AxisAlignedBoundingBox.from_min_max(min_p, max_p) + + @classmethod + def from_min_max(cls, min_point: Sequence[float], max_point: Sequence[float]): + """ + Set the axis-aligned bounding box from a minimum and maximum point. + + :param min_point: The minimum point + :param max_point: The maximum point + """ + return cls(min_point[0], min_point[1], min_point[2], max_point[0], max_point[1], max_point[2]) + + +@dataclass +class RotatedBoundingBox(BoundingBox): + """ + Dataclass for storing a rotated bounding box. + """ + + def __init__(self, min_x: float, min_y: float, min_z: float, max_x: float, max_y: float, max_z: float, + transform: Transform, points: Optional[List[Point]] = None): + self.min_x, self.min_y, self.min_z = min_x, min_y, min_z + self.max_x, self.max_y, self.max_z = max_x, max_y, max_z + self.transform: Transform = transform + self._points: Optional[List[Point]] = points + + @classmethod + def from_min_max(cls, min_point: Sequence[float], max_point: Sequence[float], transform: Transform): + """ + Set the rotated bounding box from a minimum, maximum point, and a transformation. + + :param min_point: The minimum point + :param max_point: The maximum point + :param transform: The transformation + """ + return cls(min_point[0], min_point[1], min_point[2], max_point[0], max_point[1], max_point[2], transform) + + @classmethod + def from_axis_aligned_bounding_box(cls, axis_aligned_bounding_box: AxisAlignedBoundingBox, + transform: Transform) -> 'RotatedBoundingBox': + """ + Set the rotated bounding box from an axis-aligned bounding box and a transformation. + + :param axis_aligned_bounding_box: The axis-aligned bounding box. + :param transform: The transformation. + """ + return cls(axis_aligned_bounding_box.min_x, axis_aligned_bounding_box.min_y, axis_aligned_bounding_box.min_z, + axis_aligned_bounding_box.max_x, axis_aligned_bounding_box.max_y, axis_aligned_bounding_box.max_z, + transform) + + def get_points_list(self) -> List[List[float]]: + """ + :return: The points of the rotated bounding box as a list of lists of floats. + """ + return [[point.x, point.y, point.z] for point in self.get_points()] + + def get_points(self, transform: Optional[Transform] = None) -> List[Point]: + """ + :param transform: The transformation to apply to the points, if None the stored transformation is used. + :return: The points of the rotated bounding box. + """ + if (self._points is None) or (transform is not None): + if transform is not None: + self.transform = transform + points_array = np.array([[self.min_x, self.min_y, self.min_z], + [self.min_x, self.min_y, self.max_z], + [self.min_x, self.max_y, self.min_z], + [self.min_x, self.max_y, self.max_z], + [self.max_x, self.min_y, self.min_z], + [self.max_x, self.min_y, self.max_z], + [self.max_x, self.max_y, self.min_z], + [self.max_x, self.max_y, self.max_z]]) + transformed_points = self.transform.apply_transform_to_array_of_points(points_array).tolist() + self._points = [Point(*point) for point in transformed_points] + return self._points + + @dataclass class CollisionCallbacks: """ @@ -208,6 +324,12 @@ def visual_geometry_type(self) -> Shape: """ pass + def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: + """ + :return: The axis-aligned bounding box of the visual shape. + """ + raise NotImplementedError + @dataclass class BoxVisualShape(VisualShape): @@ -227,6 +349,13 @@ def visual_geometry_type(self) -> Shape: def size(self) -> List[float]: return self.half_extents + def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: + """ + :return: The axis-aligned bounding box of the box visual shape. + """ + return AxisAlignedBoundingBox(-self.half_extents[0], -self.half_extents[1], -self.half_extents[2], + self.half_extents[0], self.half_extents[1], self.half_extents[2]) + @dataclass class SphereVisualShape(VisualShape): @@ -242,6 +371,12 @@ def shape_data(self) -> Dict[str, float]: def visual_geometry_type(self) -> Shape: return Shape.SPHERE + def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: + """ + :return: The axis-aligned bounding box of the sphere visual shape. + """ + return AxisAlignedBoundingBox(-self.radius, -self.radius, -self.radius, self.radius, self.radius, self.radius) + @dataclass class CapsuleVisualShape(VisualShape): @@ -258,6 +393,13 @@ def shape_data(self) -> Dict[str, float]: def visual_geometry_type(self) -> Shape: return Shape.CAPSULE + def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: + """ + :return: The axis-aligned bounding box of the capsule visual shape. + """ + return AxisAlignedBoundingBox(-self.radius, -self.radius, -self.length / 2, + self.radius, self.radius, self.length / 2) + @dataclass class CylinderVisualShape(CapsuleVisualShape): @@ -285,6 +427,16 @@ def shape_data(self) -> Dict[str, Union[List[float], str]]: def visual_geometry_type(self) -> Shape: return Shape.MESH + def get_axis_aligned_bounding_box(self, file_path: Optional[str] = None) -> AxisAlignedBoundingBox: + """ + :param file_path: An alternative file path. + :return: The axis-aligned bounding box of the mesh visual shape. + """ + mesh_file_path = file_path if file_path is not None else self.file_name + mesh = trimesh.load(mesh_file_path) + min_bound, max_bound = mesh.bounds + return AxisAlignedBoundingBox.from_min_max(min_bound, max_bound) + @dataclass class PlaneVisualShape(VisualShape): @@ -301,6 +453,10 @@ def visual_geometry_type(self) -> Shape: return Shape.PLANE +VisualShapeUnion = Union[BoxVisualShape, SphereVisualShape, CapsuleVisualShape, + CylinderVisualShape, MeshVisualShape, PlaneVisualShape] + + @dataclass class State(ABC): """ @@ -503,6 +659,7 @@ class ContactPointsList(list): """ A list of contact points. """ + def get_links_that_got_removed(self, previous_points: 'ContactPointsList') -> List[Link]: """ Return the links that are not in the current points list but were in the initial points list. @@ -718,4 +875,4 @@ class ReasoningResult: Result of a reasoning result of knowledge source """ success: bool - reasoned_parameter: Dict[str, Any] = field(default_factory=dict) \ No newline at end of file + reasoned_parameter: Dict[str, Any] = field(default_factory=dict) diff --git a/src/pycram/datastructures/pose.py b/src/pycram/datastructures/pose.py index e5e226861..b5c634fc7 100644 --- a/src/pycram/datastructures/pose.py +++ b/src/pycram/datastructures/pose.py @@ -380,8 +380,8 @@ def apply_transform_to_array_of_points(self, points: np.ndarray) -> np.ndarray: homogeneous_transform = self.get_homogeneous_matrix() # add the homogeneous coordinate, by adding a column of ones to the position vectors, becoming 4xN matrix homogenous_points = np.concatenate((points, np.ones((points.shape[0], 1))), axis=1).T - rays_end_positions = homogeneous_transform @ homogenous_points - return rays_end_positions[:3, :].T + transformed_points = homogeneous_transform @ homogenous_points + return transformed_points[:3, :].T def get_homogeneous_matrix(self) -> np.ndarray: """ diff --git a/src/pycram/datastructures/world.py b/src/pycram/datastructures/world.py index c69c704bf..74d55945d 100644 --- a/src/pycram/datastructures/world.py +++ b/src/pycram/datastructures/world.py @@ -9,6 +9,7 @@ import numpy as np from geometry_msgs.msg import Point +from trimesh.parent import Geometry3D from typing_extensions import List, Optional, Dict, Tuple, Callable, TYPE_CHECKING, Union, Type import pycrap @@ -20,7 +21,7 @@ SphereVisualShape, CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, ObjectState, WorldState, ClosestPointsList, - ContactPointsList, VirtualMobileBaseJoints) + ContactPointsList, VirtualMobileBaseJoints, RotatedBoundingBox) from ..datastructures.enums import JointType, ObjectType, WorldMode, Arms from ..datastructures.pose import Pose, Transform from ..datastructures.world_entity import StateEntity @@ -133,6 +134,42 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool = False, clear_ca self.original_state_id = self.save_state() + self.on_add_object_callbacks: List[Callable[[Object], None]] = [] + + def get_object_convex_hull(self, obj: Object) -> Geometry3D: + """ + Get the convex hull of an object. + + :param obj: The pycram object. + :return: The convex hull of the object as a list of Points. + """ + raise NotImplementedError + + def get_link_convex_hull(self, link: Link) -> Geometry3D: + """ + Get the convex hull of a link of an articulated object. + + :param link: The link as a AbstractLink object. + :return: The convex hull of the link as a list of Points. + """ + raise NotImplementedError + + def add_callback_on_add_object(self, callback: Callable[[Object], None]) -> None: + """ + Add a callback that is called when an object is added to the world. + + :param callback: The callback. + """ + self.on_add_object_callbacks.append(callback) + + def remove_callback_on_add_object(self, callback: Callable[[Object], None]) -> None: + """ + Remove a callback that is called when an object is added to the world. + + :param callback: The callback. + """ + self.on_add_object_callbacks.remove(callback) + @classmethod def get_cache_dir(cls) -> str: """ @@ -150,6 +187,16 @@ def add_object(self, obj: Object) -> None: self.objects.append(obj) self.add_object_to_original_state(obj) self.object_lock.release() + self.invoke_on_add_object_callbacks(obj) + + def invoke_on_add_object_callbacks(self, obj: Object) -> None: + """ + Invoke the object added callbacks. + + :param obj: The object. + """ + for callback in self.on_add_object_callbacks: + callback(obj) @property def robot_description(self) -> RobotDescription: @@ -271,7 +318,8 @@ def _sync_prospection_world(self): def preprocess_object_file_and_get_its_cache_path(self, path: str, ignore_cached_files: bool, description: ObjectDescription, name: str, - scale_mesh: Optional[float] = None) -> str: + scale_mesh: Optional[float] = None, + mesh_transform: Optional[Transform] = None) -> str: """ Update the cache directory with the given object. @@ -280,9 +328,11 @@ def preprocess_object_file_and_get_its_cache_path(self, path: str, ignore_cached :param description: The object description. :param name: The name of the object. :param scale_mesh: The scale of the mesh. + :param mesh_transform: The mesh transform to apply to the mesh. :return: The path of the cached object. """ - return self.cache_manager.update_cache_dir_with_object(path, ignore_cached_files, description, name, scale_mesh) + return self.cache_manager.update_cache_dir_with_object(path, ignore_cached_files, description, name, + scale_mesh, mesh_transform) @property def simulation_time_step(self): @@ -817,8 +867,6 @@ def set_link_color(self, link: Link, rgba_color: Color): @abstractmethod def get_link_color(self, link: Link) -> Color: """ - This method returns the rgba_color of this link. - :param link: The link for which the rgba_color should be returned. :return: The rgba_color as Color object with RGBA values between 0 and 1. """ @@ -827,32 +875,45 @@ def get_link_color(self, link: Link) -> Color: @abstractmethod def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: """ - Get the RGBA colors of each link in the object as a dictionary from link name to rgba_color. - :param obj: The object - :return: A dictionary with link names as keys and a Color object for each link as value. + :return: The RGBA colors of each link in the object as a dictionary from link name to rgba_color. """ pass @abstractmethod def get_object_axis_aligned_bounding_box(self, obj: Object) -> AxisAlignedBoundingBox: """ - Return the axis aligned bounding box of this object. The return of this method are two points in + :param obj: The object for which the bounding box should be returned. + :return: the axis aligned bounding box of this object. The return of this method are two points in world coordinate frame which define a bounding box. + """ + pass + def get_object_rotated_bounding_box(self, obj: Object) -> RotatedBoundingBox: + """ :param obj: The object for which the bounding box should be returned. - :return: AxisAlignedBoundingBox object containing the min and max points of the bounding box. + :return: the rotated bounding box of this object. The return of this method are two points in + world coordinate frame which define a bounding box. """ - pass + raise NotImplementedError @abstractmethod def get_link_axis_aligned_bounding_box(self, link: Link) -> AxisAlignedBoundingBox: """ - Return the axis aligned bounding box of the link. The return of this method are two points in + :param link: The link for which the bounding box should be returned. + :return: The axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box. """ pass + def get_link_rotated_bounding_box(self, link: Link) -> RotatedBoundingBox: + """ + :param link: The link for which the bounding box should be returned. + :return: The rotated bounding box of the link. The return of this method are two points in + world coordinate frame which define a bounding box. + """ + raise NotImplementedError + @abstractmethod def set_realtime(self, real_time: bool) -> None: """ diff --git a/src/pycram/description.py b/src/pycram/description.py index 689bec2f5..0a41fe434 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -5,16 +5,19 @@ import pathlib from abc import ABC, abstractmethod +from trimesh.parent import Geometry3D + from .ros.data_types import Time import trimesh from geometry_msgs.msg import Point, Quaternion from typing_extensions import Tuple, Union, Any, List, Optional, Dict, TYPE_CHECKING, Self, deprecated -from .datastructures.dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState, VisualShape +from .datastructures.dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState, VisualShape, \ + MeshVisualShape, RotatedBoundingBox from .datastructures.enums import JointType from .datastructures.pose import Pose, Transform from .datastructures.world_entity import WorldEntity -from .failures import ObjectDescriptionNotFound +from .failures import ObjectDescriptionNotFound, LinkHasNoGeometry, LinkGeometryHasNoMesh from .local_transformer import LocalTransformer if TYPE_CHECKING: @@ -53,7 +56,7 @@ def __init__(self, parsed_link_description: Any): @property @abstractmethod - def geometry(self) -> Union[VisualShape, None]: + def geometry(self) -> Union[List[VisualShape], VisualShape, None]: """ The geometry type of the collision element of this link. """ @@ -219,6 +222,87 @@ def __init__(self, _id: int, link_description: LinkDescription, obj: Object): self._current_pose: Optional[Pose] = None self.update_pose() + def get_axis_aligned_bounding_box(self, transform_to_link_pose: bool = True) -> AxisAlignedBoundingBox: + """ + :param transform_to_link_pose: If True, return the bounding box transformed to the link pose. + :return: The axis-aligned bounding box of a link. First try to get it from the simulator, if not, + then calculate it depending on the type of the link geometry. + """ + try: + return self.world.get_link_axis_aligned_bounding_box(self) + except NotImplementedError: + bounding_box = self.get_axis_aligned_bounding_box_from_geometry() + if transform_to_link_pose: + return bounding_box.get_transformed_box(self.transform) + else: + return bounding_box + + def get_rotated_bounding_box(self) -> RotatedBoundingBox: + """ + :return: The rotated bounding box of a link. First try to get it from the simulator, if not, + then calculate it depending on the type of the link geometry. + """ + try: + return self.world.get_link_rotated_bounding_box(self) + except NotImplementedError: + return RotatedBoundingBox.from_axis_aligned_bounding_box(self.get_axis_aligned_bounding_box(), + self.transform) + + def get_axis_aligned_bounding_box_from_geometry(self) -> AxisAlignedBoundingBox: + if isinstance(self.geometry, List): + all_boxes = [geom.get_axis_aligned_bounding_box(self.get_mesh_path(geom)) + if isinstance(geom, MeshVisualShape) else geom.get_axis_aligned_bounding_box() + for geom in self.geometry + ] + bounding_box = AxisAlignedBoundingBox.from_multiple_bounding_boxes(all_boxes) + else: + geom = self.geometry + bounding_box = geom.get_axis_aligned_bounding_box(self.get_mesh_path(geom)) \ + if isinstance(geom, MeshVisualShape) else geom.get_axis_aligned_bounding_box() + return bounding_box + + def get_convex_hull(self) -> Geometry3D: + """ + :return: The convex hull of the link geometry. + """ + try: + return self.world.get_link_convex_hull(self) + except NotImplementedError: + if isinstance(self.geometry, MeshVisualShape): + mesh_path = self.get_mesh_path(self.geometry) + mesh = trimesh.load(mesh_path) + return trimesh.convex.convex_hull(mesh).apply_transform(self.transform.get_homogeneous_matrix()) + else: + raise LinkGeometryHasNoMesh(self.name, type(self.geometry).__name__) + + def _plot_convex_hull(self): + """ + Plot the convex hull of the link geometry. + """ + hull = self.get_convex_hull() + hull.show() + + def get_mesh_path(self, geometry: MeshVisualShape) -> str: + """ + :param geometry: The geometry for which the mesh path should be returned. + :return: The path of the mesh file of this link if the geometry is a mesh. + """ + mesh_filename = self.get_mesh_filename(geometry) + return self.world.cache_manager.look_for_file_in_data_dir(pathlib.Path(mesh_filename)) + + def get_mesh_filename(self, geometry: MeshVisualShape) -> str: + """ + :return: The mesh file name of this link if the geometry is a mesh, otherwise raise a LinkGeometryHasNoMesh. + :raises LinkHasNoGeometry: If the link has no geometry. + :raises LinkGeometryHasNoMesh: If the geometry is not a mesh. + """ + if geometry is None: + raise LinkHasNoGeometry(self.name) + if isinstance(geometry, MeshVisualShape): + return geometry.file_name + else: + raise LinkGeometryHasNoMesh(self.name, type(geometry).__name__) + def set_pose(self, pose: Pose) -> None: """ Set the pose of this link to the given pose. @@ -338,12 +422,6 @@ def get_pose_wrt_link(self, link: 'Link') -> Pose: """ return self.local_transformer.transform_pose(self.pose, link.tf_frame) - def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: - """ - :return: An AxisAlignedBoundingBox object with the axis aligned bounding box of this link. - """ - return self.world.get_link_axis_aligned_bounding_box(self) - @property def position(self) -> Point: """ @@ -620,6 +698,7 @@ def __init__(self, path: Optional[str] = None): self._joints: Optional[List[JointDescription]] = None self._link_map: Optional[Dict[str, Any]] = None self._joint_map: Optional[Dict[str, Any]] = None + self.original_path: Optional[str] = path if path: self.update_description_from_file(path) @@ -737,7 +816,8 @@ def load_description(self, path: str) -> Any: pass def generate_description_from_file(self, path: str, name: str, extension: str, save_path: str, - scale_mesh: Optional[float] = None) -> None: + scale_mesh: Optional[float] = None, + mesh_transform: Optional[Transform] = None) -> None: """ Generate and preprocess the description from the file at the given path and save the preprocessed description. The generated description will be saved at the given save path. @@ -747,15 +827,19 @@ def generate_description_from_file(self, path: str, name: str, extension: str, s :param extension: The file extension of the file to preprocess. :param save_path: The path to save the generated description file. :param scale_mesh: The scale of the mesh. + :param mesh_transform: The transformation matrix to apply to the mesh. :raises ObjectDescriptionNotFound: If the description file could not be found/read. """ if extension in self.mesh_extensions: if extension == ".ply": mesh = trimesh.load(path) - path = path.replace(extension, ".obj") if scale_mesh is not None: mesh.apply_scale(scale_mesh) + if mesh_transform is not None: + transform = mesh_transform.get_homogeneous_matrix() + mesh.apply_transform(transform) + path = path.replace(extension, ".obj") mesh.export(path) self.generate_from_mesh_file(path, name, save_path=save_path) elif extension == self.get_file_extension(): diff --git a/src/pycram/failures.py b/src/pycram/failures.py index effe849d4..c9647aabc 100644 --- a/src/pycram/failures.py +++ b/src/pycram/failures.py @@ -490,3 +490,13 @@ class UnsupportedJointType(Exception): def __init__(self, joint_type: 'JointType'): super().__init__(f"Unsupported joint type: {joint_type}") + +class LinkHasNoGeometry(Exception): + def __init__(self, link_name: str): + super().__init__(f"Link {link_name} has no geometry.") + + +class LinkGeometryHasNoMesh(Exception): + def __init__(self, link_name: str, geometry_type: str): + super().__init__(f"Link {link_name} geometry with type {geometry_type} has no mesh.") + diff --git a/src/pycram/object_descriptors/mjcf.py b/src/pycram/object_descriptors/mjcf.py index 36e895372..cc9b8e914 100644 --- a/src/pycram/object_descriptors/mjcf.py +++ b/src/pycram/object_descriptors/mjcf.py @@ -1,15 +1,15 @@ import os import pathlib +from xml.etree import ElementTree as ET import numpy as np from dm_control import mjcf from geometry_msgs.msg import Point from typing_extensions import Union, List, Optional, Dict, Tuple -from xml.etree import ElementTree as ET from ..datastructures.dataclasses import Color, VisualShape, BoxVisualShape, CylinderVisualShape, \ - SphereVisualShape, MeshVisualShape -from ..datastructures.enums import JointType, MJCFGeomType, MJCFJointType + SphereVisualShape, MeshVisualShape, VisualShapeUnion +from ..datastructures.enums import JointType, MJCFGeomType, MJCFJointType, Shape from ..datastructures.pose import Pose from ..description import JointDescription as AbstractJointDescription, \ LinkDescription as AbstractLinkDescription, ObjectDescription as AbstractObjectDescription @@ -38,11 +38,17 @@ def __init__(self, mjcf_description: mjcf.Element): super().__init__(mjcf_description) @property - def geometry(self) -> Union[VisualShape, None]: + def geometry(self) -> Union[List[VisualShape], VisualShape, None]: """ :return: The geometry type of the collision element of this link. """ - return self._get_visual_shape(self.parsed_description.find_all('geom')[0]) + all_geoms = self.parsed_description.find_all('geom') + if len(all_geoms) == 0: + return None + elif len(all_geoms) == 1: + return self._get_visual_shape(all_geoms[0]) + else: + return [self._get_visual_shape(geom) for geom in all_geoms] @staticmethod def _get_visual_shape(mjcf_geometry) -> Union[VisualShape, None]: @@ -57,7 +63,8 @@ def _get_visual_shape(mjcf_geometry) -> Union[VisualShape, None]: if mjcf_geometry.type == MJCFGeomType.SPHERE.value: return SphereVisualShape(Color(), [0, 0, 0], mjcf_geometry.size[0]) if mjcf_geometry.type == MJCFGeomType.MESH.value: - return MeshVisualShape(Color(), [0, 0, 0], mjcf_geometry.scale, mjcf_geometry.filename) + mesh_filename = mjcf_geometry.mesh.file.prefix + mjcf_geometry.mesh.file.extension + return MeshVisualShape(Color(), [0, 0, 0], mjcf_geometry.mesh.scale, mesh_filename) return None @property @@ -73,7 +80,6 @@ def name(self) -> str: class JointDescription(AbstractJointDescription): - mjcf_type_map = { MJCFJointType.HINGE.value: JointType.REVOLUTE, MJCFJointType.BALL.value: JointType.SPHERICAL, @@ -175,15 +181,18 @@ class ObjectFactory(Factory): """ Create MJCF object descriptions from mesh files. """ - def __init__(self, object_name: str, file_path: str, config: Configuration, texture_type: str = "png"): + + def __init__(self, file_path: str, config: Configuration): super().__init__(file_path, config) + def from_mesh_file(self, object_name: str, texture_type: str = "png"): + self._world_builder = WorldBuilder(usd_file_path=self.tmp_usd_file_path) body_builder = self._world_builder.add_body(body_name=object_name) tmp_usd_mesh_file_path, tmp_origin_mesh_file_path = self.import_mesh( - mesh_file_path=file_path, merge_mesh=True) + mesh_file_path=self.source_file_path, merge_mesh=True) mesh_stage = Usd.Stage.Open(tmp_usd_mesh_file_path) for idx, mesh_prim in enumerate([prim for prim in mesh_stage.Traverse() if prim.IsA(UsdGeom.Mesh)]): mesh_name = mesh_prim.GetName() @@ -199,10 +208,11 @@ def __init__(self, object_name: str, file_path: str, config: Configuration, text geom_builder.add_mesh(mesh_name=mesh_name, mesh_property=mesh_property) # Add texture if available - texture_file_path = file_path.replace(pathlib.Path(file_path).suffix, f".{texture_type}") + texture_file_path = self.source_file_path.replace(pathlib.Path(self.source_file_path).suffix, + f".{texture_type}") if pathlib.Path(texture_file_path).exists(): self.add_material_with_texture(geom_builder=geom_builder, material_name=f"M_{object_name}_{idx}", - texture_file_path=texture_file_path) + texture_file_path=texture_file_path) geom_builder.build() @@ -235,6 +245,64 @@ def export_to_mjcf(self, output_file_path: str): exporter.export(keep_usd=False) +class PrimitiveObjectFactory(ObjectFactory): + + def __init__(self, object_name: str, shape_data: VisualShapeUnion, save_path: str, + orientation: Optional[List[float]] = None): + """ + Create an MJCF object description from a primitive shape. + + :param object_name: The name of the object. + :param shape_data: The shape data of the object. + :param save_path: The path to save the MJCF file. + :param orientation: The orientation of the object. + """ + self.shape_data: VisualShapeUnion = shape_data + self.orientation: List[float] = [0, 0, 0, 1] if orientation is None else orientation + config = Configuration(model_name=object_name, + fixed_base=False, + with_visual=True, + with_collision=True, + default_rgba=np.array(shape_data.rgba_color.get_rgba())) + super().__init__(save_path, config) + + def build_shape(self): + + self._world_builder = WorldBuilder(usd_file_path=self.tmp_usd_file_path) + + body_builder = self._world_builder.add_body(body_name=self.config.model_name) + + geom_type_map = { + Shape.SPHERE: GeomType.SPHERE, + Shape.BOX: GeomType.CUBE, + Shape.CYLINDER: GeomType.CYLINDER, + Shape.PLANE: GeomType.PLANE, + Shape.CAPSULE: GeomType.CAPSULE, + } + geom_property = GeomProperty(geom_type=geom_type_map[self.shape_data.visual_geometry_type], + is_visible=self.config.with_visual, + is_collidable=self.config.with_collision, + rgba=self.config.default_rgba) + + geom_builder = body_builder.add_geom( + geom_name=f"{self.config.model_name}_Shape", + geom_property=geom_property + ) + geom_pos = self.shape_data.visual_frame_position + geom_quat = np.array(self.orientation) + if self.shape_data.visual_geometry_type == Shape.PLANE: + geom_builder.set_transform(pos=geom_pos, quat=geom_quat, scale=np.array([50, 50, 1])) + elif self.shape_data.visual_geometry_type == Shape.BOX: + geom_builder.set_transform(pos=geom_pos, quat=geom_quat, scale=np.array(self.shape_data.half_extents) * 2) + elif self.shape_data.visual_geometry_type == Shape.SPHERE: + geom_builder.set_transform(pos=geom_pos, quat=geom_quat) + geom_builder.set_attribute(radius=self.shape_data.radius) + elif self.shape_data.visual_geometry_type in [Shape.CYLINDER, Shape.CAPSULE]: + geom_builder.set_transform(pos=geom_pos, quat=geom_quat) + geom_builder.set_attribute(radius=self.shape_data.radius, height=self.shape_data.length) + geom_builder.build() + + class ObjectDescription(AbstractObjectDescription): """ A class that represents an object description of an object. @@ -372,10 +440,11 @@ def generate_from_mesh_file(self, path: str, name: str, color: Optional[Color] = :param color: The color of the object. :param save_path: The path to save the generated xml file. """ - factory = ObjectFactory(object_name=name, file_path=path, + factory = ObjectFactory(file_path=path, config=Configuration(model_name=name, fixed_base=False, default_rgba=np.array(color.get_rgba()))) + factory.from_mesh_file(object_name=name) factory.export_to_mjcf(output_file_path=save_path) def generate_from_description_file(self, path: str, save_path: str, make_mesh_paths_absolute: bool = True) -> None: diff --git a/src/pycram/object_descriptors/urdf.py b/src/pycram/object_descriptors/urdf.py index 694d421be..dc0d7c728 100644 --- a/src/pycram/object_descriptors/urdf.py +++ b/src/pycram/object_descriptors/urdf.py @@ -32,12 +32,14 @@ def __init__(self, urdf_description: urdf.Link): super().__init__(urdf_description) @property - def geometry(self) -> Union[VisualShape, None]: + def geometry(self) -> Union[List[VisualShape], VisualShape, None]: """ :return: The geometry type of the URDF collision element of this link. """ if self.collision is None: return None + if isinstance(self.collision, List): + return [self._get_visual_shape(coll.geometry) for coll in self.collision] urdf_geometry = self.collision.geometry return self._get_visual_shape(urdf_geometry) @@ -62,18 +64,23 @@ def _get_visual_shape(urdf_geometry) -> Union[VisualShape, None]: def origin(self) -> Union[Pose, None]: if self.collision is None: return None - if self.collision.origin is None: + coll = self.collision[0] if isinstance(self.collision, List) else self.collision + if coll.origin is None: return None - return Pose(self.collision.origin.xyz, - quaternion_from_euler(*self.collision.origin.rpy).tolist()) + return Pose(coll.origin.xyz, + quaternion_from_euler(*coll.origin.rpy).tolist()) @property def name(self) -> str: return self.parsed_description.name @property - def collision(self) -> Collision: - return self.parsed_description.collision + def collision(self) -> Union[Collision, List[Collision], None]: + if self.parsed_description.collisions: + if len(self.parsed_description.collisions) == 1: + return self.parsed_description.collisions[0] + else: + return self.parsed_description.collisions class JointDescription(AbstractJointDescription): diff --git a/src/pycram/world_concepts/world_object.py b/src/pycram/world_concepts/world_object.py index ec5741179..dc7840855 100644 --- a/src/pycram/world_concepts/world_object.py +++ b/src/pycram/world_concepts/world_object.py @@ -8,11 +8,12 @@ import owlready2 from deprecated import deprecated from geometry_msgs.msg import Point, Quaternion +from trimesh.parent import Geometry3D from typing_extensions import Type, Optional, Dict, Tuple, List, Union from ..datastructures.dataclasses import (Color, ObjectState, LinkState, JointState, AxisAlignedBoundingBox, VisualShape, ClosestPointsList, - ContactPointsList) + ContactPointsList, RotatedBoundingBox) from ..datastructures.enums import ObjectType, JointType from ..datastructures.pose import Pose, Transform from ..datastructures.world import World @@ -60,7 +61,8 @@ def __init__(self, name: str, concept: Type[PhysicalObject], path: Optional[str] world: Optional[World] = None, color: Color = Color(), ignore_cached_files: bool = False, - scale_mesh: Optional[float] = None): + scale_mesh: Optional[float] = None, + mesh_transform: Optional[Transform] = None): """ The constructor loads the description file into the given World, if no World is specified the :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. @@ -103,7 +105,8 @@ def __init__(self, name: str, concept: Type[PhysicalObject], path: Optional[str] if path is not None: self.path = self.world.preprocess_object_file_and_get_its_cache_path(path, ignore_cached_files, self.description, self.name, - scale_mesh=scale_mesh) + scale_mesh=scale_mesh, + mesh_transform=mesh_transform) self.description.update_description_from_file(self.path) @@ -125,7 +128,16 @@ def __init__(self, name: str, concept: Type[PhysicalObject], path: Optional[str] self.world.add_object(self) + def get_mesh_path(self) -> str: + """ + Get the path to the mesh file of the object. + :return: The path to the mesh file. + """ + if self.has_one_link: + return self.root_link.get_mesh_path() + else: + raise ValueError("The object has more than one link, therefore the mesh path cannot be determined.") def _resolve_description(self, path: Optional[str] = None, description: Optional[ObjectDescription] = None) -> None: """ @@ -1361,7 +1373,32 @@ def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: :return: The axis aligned bounding box of this object. """ - return self.world.get_object_axis_aligned_bounding_box(self) + if self.has_one_link: + return self.root_link.get_axis_aligned_bounding_box() + else: + return self.world.get_object_axis_aligned_bounding_box(self) + + def get_rotated_bounding_box(self) -> RotatedBoundingBox: + """ + Return the rotated bounding box of this object. + + :return: The rotated bounding box of this object. + """ + if self.has_one_link: + return self.root_link.get_rotated_bounding_box() + else: + return self.world.get_object_rotated_bounding_box(self) + + def get_convex_hull(self) -> Geometry3D: + """ + Return the convex hull of this object. + + :return: The convex hull of this object. + """ + if self.has_one_link: + return self.root_link.get_convex_hull() + else: + return self.world.get_object_convex_hull(self) def get_base_origin(self) -> Pose: """ diff --git a/src/pycram/worlds/multiverse.py b/src/pycram/worlds/multiverse.py index b4b65380e..6cbeb0d78 100644 --- a/src/pycram/worlds/multiverse.py +++ b/src/pycram/worlds/multiverse.py @@ -13,7 +13,7 @@ MultiverseJointCMD from ..datastructures.pose import Pose from ..datastructures.world import World -from ..description import Link, Joint, ObjectDescription +from ..description import Link, Joint from ..object_descriptors.mjcf import ObjectDescription as MJCF from ..robot_description import RobotDescription from ..ros.logging import logwarn, logerr @@ -643,7 +643,7 @@ def get_link_axis_aligned_bounding_box(self, link: Link) -> AxisAlignedBoundingB def set_realtime(self, real_time: bool) -> None: logwarn("set_realtime is not implemented as an API in Multiverse, it is configured in the" - "multiverse configuration file (.muv file) as rtf_required where a value of 1 means real-time") + "multiverse configuration file (.muv file) as rtf_required where a value of 1 means real-time") def set_gravity(self, gravity_vector: List[float]) -> None: logwarn("set_gravity is not implemented in Multiverse") diff --git a/test/test_links.py b/test/test_links.py index 703b4f48a..3cd354a35 100644 --- a/test/test_links.py +++ b/test/test_links.py @@ -1,9 +1,53 @@ +import numpy as np +from matplotlib import pyplot as plt +from tf.transformations import quaternion_from_euler +from typing_extensions import List + from pycram.testing import BulletWorldTestCase from pycram.datastructures.dataclasses import Color +from pycram.datastructures.pose import Pose class TestLinks(BulletWorldTestCase): + def test_get_convex_hull(self): + self.milk.set_orientation(quaternion_from_euler(0, np.pi/4, 0)) + hull = self.milk.root_link.get_convex_hull() + self.assertIsNotNone(hull) + self.assertTrue(len(hull.vertices) > 0) + self.assertTrue(len(hull.faces) > 0) + plot = False + if plot: + self.plot_3d_points([hull.vertices]) + + def test_rotated_bounding_box(self): + self.milk.set_pose(Pose([1, 1, 1], quaternion_from_euler(np.pi/4, 0, 0).tolist())) + aabb = self.milk.get_axis_aligned_bounding_box() + aabb_points = np.array(aabb.get_points_list()) + rbb = self.milk.get_rotated_bounding_box() + rot_points = np.array(rbb.get_points_list()) + plot = False + if plot: + self.plot_3d_points([aabb_points, rot_points]) + + @staticmethod + def plot_3d_points(list_of_points: List[np.ndarray]): + fig = plt.figure() + ax = fig.add_subplot(projection='3d') + + for points in list_of_points: + color = np.random.rand(3,) + ax.scatter(points[:, 0], points[:, 1], points[:, 2], c=color, marker='o') + + ax.set_xlabel('X Label') + ax.set_ylabel('Y Label') + ax.set_zlabel('Z Label') + plt.xlim(0, 2) + plt.ylim(0, 2) + ax.set_zlim(0, 2) + + plt.show() + def test_add_constraint(self): milk_link = self.milk.root_link robot_link = self.robot.root_link diff --git a/test/test_multiverse.py b/test/test_multiverse.py index e52d9604c..d0e75ce91 100644 --- a/test/test_multiverse.py +++ b/test/test_multiverse.py @@ -7,7 +7,7 @@ from tf.transformations import quaternion_from_euler, quaternion_multiply from typing_extensions import Optional, List -from pycram.datastructures.dataclasses import ContactPointsList, ContactPoint +from pycram.datastructures.dataclasses import ContactPointsList, ContactPoint, AxisAlignedBoundingBox from pycram.datastructures.enums import ObjectType, Arms, JointType from pycram.datastructures.pose import Pose from pycram.robot_description import RobotDescriptionManager @@ -87,6 +87,34 @@ def test_spawn_xml_object(self): bread = Object("bread_1", ObjectType.GENERIC_OBJECT, "bread_1.xml", pose=Pose([1, 1, 0.1])) self.assert_poses_are_equal(bread.get_pose(), Pose([1, 1, 0.1])) + def test_get_axis_aligned_bounding_box_for_one_link_object(self): + position = [1, 1, 0.1] + milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1, 1, 0.1], + quaternion_from_euler(np.pi/4, 0, 0).tolist())) + aabb = milk.get_axis_aligned_bounding_box() + self.assertIsInstance(aabb, AxisAlignedBoundingBox) + min_p_1, max_p_1 = aabb.get_min_max() + width = max_p_1[0] - min_p_1[0] + length = max_p_1[1] - min_p_1[1] + height = max_p_1[2] - min_p_1[2] + self.assertTrue(width > 0) + self.assertTrue(length > 0) + self.assertTrue(height > 0) + # Move the object and check if the bounding box is updated correctly + position_shift = 1 + milk.set_position([position[0] + position_shift, position[1] + position_shift, 0.1]) + aabb = milk.get_axis_aligned_bounding_box() + min_p_2, max_p_2 = aabb.get_min_max() + width_2 = max_p_2[0] - min_p_2[0] + length_2 = max_p_2[1] - min_p_2[1] + height_2 = max_p_2[2] - min_p_2[2] + self.assertAlmostEqual(width, width_2, delta=0.001) + self.assertAlmostEqual(length, length_2, delta=0.001) + self.assertAlmostEqual(height, height_2, delta=0.001) + for i in range(3): + self.assertAlmostEqual(min_p_1[0] + position_shift, min_p_2[0], delta=0.001) + self.assertAlmostEqual(max_p_1[0] + position_shift, max_p_2[0], delta=0.001) + def test_spawn_mesh_object(self): milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1, 1, 0.1])) self.assert_poses_are_equal(milk.get_pose(), Pose([1, 1, 0.1])) @@ -389,7 +417,7 @@ def spawn_big_bowl() -> Object: def spawn_milk(position: List, orientation: Optional[List] = None, frame="map") -> Object: if orientation is None: orientation = [0, 0, 0, 1] - milk = Object("milk_box", ObjectType.MILK, "milk_box.xml", + milk = Object("milk_box", ObjectType.MILK, "milk_box.urdf", pose=Pose(position, orientation, frame=frame)) return milk