def data(self, data): self.name = data['name'] self.joints = [Joint.from_data(d) for d in data['joints']] self.links = [Link.from_data(d) for d in data['links']] self.materials = [Material.from_data(d) for d in data['materials']] self.attr = _attr_from_data(data['attr']) self._scale_factor = data['_scale_factor'] self._rebuild_tree()
def _set_data(self, data): self.name = data.get('name', '') self.joints = [Joint.from_data(d) for d in data.get('joints', [])] self.links = [Link.from_data(d) for d in data.get('links', [])] self.materials = [Material.from_data(d) for d in data.get('materials', [])] self.attr = _attr_from_data(data.get('attr', {})) self._scale_factor = data.get('_scale_factor', 1.) self._rebuild_tree()
def add_link(self, name, visual_mesh=None, visual_color=None, collision_mesh=None, **kwargs): """Adds a link to the robot model. Provides an easy way to programmatically add a link to the robot model. Parameters ---------- name : str The name of the link visual_mesh : :class:`compas.datastructures.Mesh`, optional The link's visual mesh. visual_color : list of 3 float, optional The rgb color of the mesh. Defaults to (0.8, 0.8, 0.8) collision_mesh : :class:`compas.datastructures.Mesh`, optional The link's collision mesh. Returns ------- :class:`Link` The created `Link` Raises ------ ValueError If the link name is already used in the chain. Examples -------- >>> sphere = Sphere((0, 0, 0), 1) >>> mesh = Mesh.from_shape(sphere) >>> robot = RobotModel('robot') >>> link = robot.add_link('link0', visual_mesh=mesh) """ all_link_names = [l.name for l in self.links] if name in all_link_names: raise ValueError("Link name '%s' already used in chain." % name) visual = [] collision = [] if visual_mesh: if not visual_color: visual_color = (0.8, 0.8, 0.8) v = Visual(Geometry(MeshDescriptor(""))) v.material = Material(color=Color("%f %f %f 1" % visual_color)) v.geometry.shape.geometry = visual_mesh visual.append(v) if collision_mesh: # use visual_mesh as collision_mesh if none passed? c = Collision(Geometry(MeshDescriptor(""))) c.geometry.shape.geometry = collision_mesh collision.append(c) link = Link(name, visual=visual, collision=collision, **kwargs) self.links.append(link) return link
def add_link(self, name, visual_meshes=None, visual_color=None, collision_meshes=None, **kwargs): """Adds a link to the robot model. Provides an easy way to programmatically add a link to the robot model. Parameters ---------- name : str The name of the link visual_meshes : list of :class:`compas.datastructures.Mesh` or :class:`compas.geometry.Shape`, optional The link's visual mesh. visual_color : list of 3 float, optional The rgb color of the mesh. Defaults to (0.8, 0.8, 0.8) collision_meshes : list of :class:`compas.datastructures.Mesh` or :class:`compas.geometry.Shape`, optional The link's collision mesh. Returns ------- :class:`Link` The created `Link` Raises ------ ValueError If the link name is already used in the chain. Examples -------- >>> sphere = Sphere((0, 0, 0), 1) >>> mesh = Mesh.from_shape(sphere) >>> robot = RobotModel('robot') >>> link = robot.add_link('link0', visual_mesh=mesh) """ self._check_link_name(name) visual_meshes, kwargs = self._consolidate_meshes(visual_meshes, 'visual_mesh', **kwargs) collision_meshes, kwargs = self._consolidate_meshes(collision_meshes, 'collision_mesh', **kwargs) if not visual_color: visual_color = (0.8, 0.8, 0.8) visuals = [] collisions = [] for visual in visual_meshes: if isinstance(visual, Mesh): v = Visual(Geometry(MeshDescriptor(""))) v.geometry.shape.geometry = visual else: v = Visual.from_primitive(visual) v.material = Material(color=Color("%f %f %f 1" % visual_color)) visuals.append(v) for collision in collision_meshes: # use visual_mesh as collision_mesh if none passed? if isinstance(collision, Mesh): c = Collision(Geometry(MeshDescriptor(""))) c.geometry.shape.geometry = collision else: c = Collision.from_primitive(collision) collisions.append(c) link = Link(name, visual=visuals, collision=collisions, **kwargs) self.links.append(link) # Must build the tree structure, if adding the first link to an empty robot if len(self.links) == 1: self._rebuild_tree() self._create(self.root, Transformation()) return link