| Functions | |
| def | alpha_shape_with_cgal (coords, alpha=None) | 
| def | halfedge_to_triangle (he) | 
| def | vertex_to_tuple (v) | 
| Variables | |
| float | alpha = 0.2 | 
| collision_model | |
| bool | convex = True | 
| data = robot.createData() | |
| faces = np.arange(len(verts)).reshape(-1, 3) | |
| int | facet_dims = 2 | 
| frame | |
| float | horizon = 0.2 | 
| string | mesh_dir = pinocchio_model_dir | 
| string | model_path = pinocchio_model_dir / "example-robot-data/robots" | 
| int | n_samples = 5 | 
| open | |
| string | pinocchio_model_dir = Path(__file__).parent.parent / "models" | 
| poly = g.TriangularMeshGeometry(vertices=verts, faces=faces) | |
| tuple | q0 = (robot.upperPositionLimit.T + robot.lowerPositionLimit.T) / 2 | 
| robot | |
| string | urdf_filename = "panda.urdf" | 
| string | urdf_model_path = model_path / "panda_description/urdf" / urdf_filename | 
| verts = verts.T | |
| visual_model | |
| viz = MeshcatVisualizer(robot, collision_model, visual_model) | |
| def reachable-workspace.alpha_shape_with_cgal | ( | coords, | |
| alpha = None | |||
| ) | 
Compute the alpha shape of a set of points. (Code thanks to A. Skuric) Retrieved from http://blog.thehumangeo.com/2014/05/12/drawing-boundaries-in-python/ :param coords : Coordinates of points :param alpha: List of alpha values to influence the gooeyness of the border. Smaller numbers don't fall inward as much as larger numbers. Too large, and you lose everything! :return: Shapely.MultiPolygons which is the hull of the input set of points
Definition at line 80 of file reachable-workspace.py.
| def reachable-workspace.halfedge_to_triangle | ( | he | ) | 
Definition at line 70 of file reachable-workspace.py.
| def reachable-workspace.vertex_to_tuple | ( | v | ) | 
Definition at line 67 of file reachable-workspace.py.
| float reachable-workspace.alpha = 0.2 | 
Definition at line 114 of file reachable-workspace.py.
| reachable-workspace.collision_model | 
Definition at line 19 of file reachable-workspace.py.
| bool reachable-workspace.convex = True | 
Definition at line 49 of file reachable-workspace.py.
| reachable-workspace.data = robot.createData() | 
Definition at line 22 of file reachable-workspace.py.
| reachable-workspace.faces = np.arange(len(verts)).reshape(-1, 3) | 
Definition at line 52 of file reachable-workspace.py.
| int reachable-workspace.facet_dims = 2 | 
Definition at line 45 of file reachable-workspace.py.
| reachable-workspace.frame | 
Definition at line 41 of file reachable-workspace.py.
| float reachable-workspace.horizon = 0.2 | 
Definition at line 40 of file reachable-workspace.py.
| string reachable-workspace.mesh_dir = pinocchio_model_dir | 
Definition at line 14 of file reachable-workspace.py.
| string reachable-workspace.model_path = pinocchio_model_dir / "example-robot-data/robots" | 
Definition at line 13 of file reachable-workspace.py.
| int reachable-workspace.n_samples = 5 | 
Definition at line 44 of file reachable-workspace.py.
| reachable-workspace.open | 
Definition at line 27 of file reachable-workspace.py.
| string reachable-workspace.pinocchio_model_dir = Path(__file__).parent.parent / "models" | 
Definition at line 11 of file reachable-workspace.py.
Definition at line 123 of file reachable-workspace.py.
| tuple reachable-workspace.q0 = (robot.upperPositionLimit.T + robot.lowerPositionLimit.T) / 2 | 
Definition at line 39 of file reachable-workspace.py.
| reachable-workspace.robot | 
Definition at line 19 of file reachable-workspace.py.
| string reachable-workspace.urdf_filename = "panda.urdf" | 
Definition at line 16 of file reachable-workspace.py.
| string reachable-workspace.urdf_model_path = model_path / "panda_description/urdf" / urdf_filename | 
Definition at line 17 of file reachable-workspace.py.
| reachable-workspace.verts = verts.T | 
Definition at line 52 of file reachable-workspace.py.
| reachable-workspace.visual_model | 
Definition at line 19 of file reachable-workspace.py.
| reachable-workspace.viz = MeshcatVisualizer(robot, collision_model, visual_model) | 
Definition at line 25 of file reachable-workspace.py.