robotic 0.3.1.dev0__cp310-cp310-manylinux2014_x86_64.whl → 0.3.1.dev2__cp310-cp310-manylinux2014_x86_64.whl
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
Potentially problematic release.
This version of robotic might be problematic. Click here for more details.
- robotic/DataGen.pyi +6 -0
- robotic/_robotic.pyi +79 -47
- robotic/_robotic.so +0 -0
- robotic/include/rai/Core/graph.h +1 -1
- robotic/include/rai/Core/util.h +9 -0
- robotic/include/rai/DataGen/shapenetGrasps.h +1 -0
- robotic/include/rai/Gui/opengl.h +3 -3
- robotic/include/rai/KOMO/komo.h +1 -1
- robotic/include/rai/Kin/frame.h +1 -1
- robotic/include/rai/Kin/kin.h +2 -4
- robotic/include/rai/Kin/kin_physx.h +2 -2
- robotic/include/rai/Kin/simulation.h +4 -4
- robotic/include/rai/Kin/viewer.h +12 -1
- robotic/include/rai/LGP/LGP_computers.h +1 -1
- robotic/include/rai/PathAlgos/ConfigurationProblem.h +2 -2
- robotic/include/rai/PathAlgos/RRT_PathFinder.h +1 -1
- robotic/librai.so +0 -0
- robotic/manipulation.py +5 -7
- robotic/meshTool +0 -0
- robotic/src/mujoco_io.py +1 -1
- robotic/src/yaml_helper.py +10 -0
- robotic/version.py +1 -1
- {robotic-0.3.1.dev0.dist-info → robotic-0.3.1.dev2.dist-info}/METADATA +1 -1
- {robotic-0.3.1.dev0.dist-info → robotic-0.3.1.dev2.dist-info}/RECORD +34 -34
- {robotic-0.3.1.dev0.data → robotic-0.3.1.dev2.data}/scripts/ry-bot +0 -0
- {robotic-0.3.1.dev0.data → robotic-0.3.1.dev2.data}/scripts/ry-h5info +0 -0
- {robotic-0.3.1.dev0.data → robotic-0.3.1.dev2.data}/scripts/ry-info +0 -0
- {robotic-0.3.1.dev0.data → robotic-0.3.1.dev2.data}/scripts/ry-meshTool +0 -0
- {robotic-0.3.1.dev0.data → robotic-0.3.1.dev2.data}/scripts/ry-test +0 -0
- {robotic-0.3.1.dev0.data → robotic-0.3.1.dev2.data}/scripts/ry-urdfConvert.py +0 -0
- {robotic-0.3.1.dev0.data → robotic-0.3.1.dev2.data}/scripts/ry-view +0 -0
- {robotic-0.3.1.dev0.dist-info → robotic-0.3.1.dev2.dist-info}/WHEEL +0 -0
- {robotic-0.3.1.dev0.dist-info → robotic-0.3.1.dev2.dist-info}/licenses/LICENSE +0 -0
- {robotic-0.3.1.dev0.dist-info → robotic-0.3.1.dev2.dist-info}/top_level.txt +0 -0
robotic/DataGen.pyi
CHANGED
|
@@ -48,6 +48,10 @@ class ShapenetGrasps:
|
|
|
48
48
|
"""
|
|
49
49
|
def getConfig(self) -> _robotic.Config:
|
|
50
50
|
...
|
|
51
|
+
def getEvalGripperPoses(self) -> arr:
|
|
52
|
+
"""
|
|
53
|
+
return the relative gripper after each motion phase: esp. poses[1] (after closing fingers) is interesting; the later ones allow you to estimate relative motion yourself)
|
|
54
|
+
"""
|
|
51
55
|
def getPointCloud(self) -> arr:
|
|
52
56
|
"""
|
|
53
57
|
(direct interface) return pcl of loaded object
|
|
@@ -64,6 +68,8 @@ class ShapenetGrasps:
|
|
|
64
68
|
"""
|
|
65
69
|
(direct interface) clear scene and load object and gripper
|
|
66
70
|
"""
|
|
71
|
+
def resetObjectPose(self, idx: int = 0, rndOrientation: bool = True) -> None:
|
|
72
|
+
...
|
|
67
73
|
def sampleGraspPose(self) -> arr:
|
|
68
74
|
"""
|
|
69
75
|
(direct interface) return (relative) pose of random sampled grasp candidate
|
robotic/_robotic.pyi
CHANGED
|
@@ -103,6 +103,14 @@ class BotOp:
|
|
|
103
103
|
"""
|
|
104
104
|
constructor
|
|
105
105
|
"""
|
|
106
|
+
def attach(self, gripper: ..., obj: ...) -> None:
|
|
107
|
+
"""
|
|
108
|
+
cheating: attach two objects kinematically
|
|
109
|
+
"""
|
|
110
|
+
def detach(self, obj: ...) -> None:
|
|
111
|
+
"""
|
|
112
|
+
cheating: detach two previously attached objects
|
|
113
|
+
"""
|
|
106
114
|
def getCameraFxycxy(self, sensorName: str) -> arr:
|
|
107
115
|
"""
|
|
108
116
|
returns camera intrinsics
|
|
@@ -315,7 +323,7 @@ class Config:
|
|
|
315
323
|
"""
|
|
316
324
|
returns the list of collisable pairs -- this should help debugging the 'contact' flag settings in a configuration
|
|
317
325
|
"""
|
|
318
|
-
def getCollisions(self, belowMargin: float =
|
|
326
|
+
def getCollisions(self, belowMargin: float = 0.0) -> list:
|
|
319
327
|
"""
|
|
320
328
|
return the results of collision computations: a list of 3 tuples with (frame1, frame2, distance). Optionally report only on distances below a margin To get really precise distances and penetrations use the FS.distance feature with the two frame names
|
|
321
329
|
"""
|
|
@@ -357,7 +365,7 @@ class Config:
|
|
|
357
365
|
"""
|
|
358
366
|
get the joint state as a numpy vector, optionally only for a subset of joints specified as list of joint names
|
|
359
367
|
"""
|
|
360
|
-
def get_viewer(self
|
|
368
|
+
def get_viewer(self) -> ConfigurationViewer:
|
|
361
369
|
...
|
|
362
370
|
def processInertias(self, recomputeInertias: bool = True, transformToDiagInertia: bool = False) -> None:
|
|
363
371
|
"""
|
|
@@ -393,7 +401,7 @@ class Config:
|
|
|
393
401
|
"""
|
|
394
402
|
def setJointStateSlice(self, arg0: list[float], arg1: int) -> None:
|
|
395
403
|
...
|
|
396
|
-
def set_viewer(self, arg0:
|
|
404
|
+
def set_viewer(self, arg0: ConfigurationViewer) -> None:
|
|
397
405
|
...
|
|
398
406
|
def view(self, pause: bool = False, message: str = None) -> int:
|
|
399
407
|
"""
|
|
@@ -403,40 +411,10 @@ class Config:
|
|
|
403
411
|
"""
|
|
404
412
|
close the view
|
|
405
413
|
"""
|
|
406
|
-
def view_focalLength(self) -> float:
|
|
407
|
-
"""
|
|
408
|
-
return the focal length of the view camera (only intrinsic parameter)
|
|
409
|
-
"""
|
|
410
|
-
def view_focus(self, frameName: str, absHeight: float = 2.0) -> None:
|
|
411
|
-
"""
|
|
412
|
-
focus on a particular frame, given via name; second argument distances camara so that view window has roughly given absHeight around object
|
|
413
|
-
"""
|
|
414
|
-
def view_fxycxy(self) -> arr:
|
|
415
|
-
"""
|
|
416
|
-
return (fx, fy, cx, cy): the focal length and image center in PIXEL UNITS
|
|
417
|
-
"""
|
|
418
|
-
def view_getDepth(self) -> numpy.ndarray[numpy.float32]:
|
|
419
|
-
...
|
|
420
|
-
def view_getRgb(self) -> numpy.ndarray[numpy.uint8]:
|
|
421
|
-
...
|
|
422
|
-
def view_pose(self) -> arr:
|
|
423
|
-
"""
|
|
424
|
-
return the 7D pose of the view camera
|
|
425
|
-
"""
|
|
426
|
-
def view_raise(self) -> None:
|
|
427
|
-
"""
|
|
428
|
-
raise the view
|
|
429
|
-
"""
|
|
430
414
|
def view_recopyMeshes(self) -> None:
|
|
431
415
|
...
|
|
432
|
-
def
|
|
433
|
-
|
|
434
|
-
saves a png image of the current view, numbered with a global counter, with the intention to make a video
|
|
435
|
-
"""
|
|
436
|
-
def view_setCamera(self, arg0: Frame) -> None:
|
|
437
|
-
"""
|
|
438
|
-
set the camera pose to a frame, and check frame attributes for intrinsic parameters (focalLength, width height)
|
|
439
|
-
"""
|
|
416
|
+
def viewer(self) -> ConfigurationViewer:
|
|
417
|
+
...
|
|
440
418
|
def watchFile(self, arg0: str) -> None:
|
|
441
419
|
"""
|
|
442
420
|
launch a viewer that listents (inode) to changes of a file (made by you in an editor), and reloads, displays and animates the configuration whenever the file is changed
|
|
@@ -468,9 +446,65 @@ class ConfigurationViewer:
|
|
|
468
446
|
@staticmethod
|
|
469
447
|
def _pybind11_conduit_v1_(*args, **kwargs):
|
|
470
448
|
...
|
|
449
|
+
def focus(self, position_7d: arr, heightAbs: float = 1.0) -> None:
|
|
450
|
+
"""
|
|
451
|
+
focus at a 3D position; second argument distances camara so that view window has roughly given absHeight around object
|
|
452
|
+
"""
|
|
453
|
+
def getCamera_focalLength(self) -> float:
|
|
454
|
+
"""
|
|
455
|
+
return the focal length of the view camera (only intrinsic parameter)
|
|
456
|
+
"""
|
|
457
|
+
def getCamera_fxycxy(self) -> arr:
|
|
458
|
+
"""
|
|
459
|
+
return (fx, fy, cx, cy): the focal length and image center in PIXEL UNITS
|
|
460
|
+
"""
|
|
461
|
+
def getCamera_pose(self) -> arr:
|
|
462
|
+
"""
|
|
463
|
+
get the camera pose directly
|
|
464
|
+
"""
|
|
465
|
+
def getDepth(self) -> ...:
|
|
466
|
+
"""
|
|
467
|
+
return the view's depth array (scaled to meters)
|
|
468
|
+
"""
|
|
469
|
+
def getEventCursor(self) -> arr:
|
|
470
|
+
"""
|
|
471
|
+
return the position and normal of the 'curser': mouse position 3D projected into scene via depth, and 3D normal of depth map -- returned as 6D vector
|
|
472
|
+
"""
|
|
473
|
+
def getEventCursorObject(self) -> int:
|
|
474
|
+
"""
|
|
475
|
+
(aka mouse picking) return the frame ID (or -1) that the 'cursor' currently points at
|
|
476
|
+
"""
|
|
477
|
+
def getEvents(self) -> StringA:
|
|
478
|
+
"""
|
|
479
|
+
return accumulated events as list of strings
|
|
480
|
+
"""
|
|
481
|
+
def getRgb(self) -> ...:
|
|
482
|
+
"""
|
|
483
|
+
return the view's rgb image
|
|
484
|
+
"""
|
|
485
|
+
def raiseWindow(self) -> None:
|
|
486
|
+
"""
|
|
487
|
+
raise the window
|
|
488
|
+
"""
|
|
471
489
|
def savePng(self, saveVideoPath: ... = 'z.vid/', count: int = -1) -> None:
|
|
472
490
|
"""
|
|
473
|
-
|
|
491
|
+
saves a png image of the current view, numbered with a global counter, with the intention to make a video
|
|
492
|
+
"""
|
|
493
|
+
def setCamera(self, camFrame: Frame) -> None:
|
|
494
|
+
"""
|
|
495
|
+
set the camera pose to a frame, and check frame attributes for intrinsic parameters (focalLength, width height)
|
|
496
|
+
"""
|
|
497
|
+
def setCameraPose(self, pose_7d: arr) -> None:
|
|
498
|
+
"""
|
|
499
|
+
set the camera pose directly
|
|
500
|
+
"""
|
|
501
|
+
def setWindow(self, title: str, width: int, height: int) -> None:
|
|
502
|
+
"""
|
|
503
|
+
set title, width, and height
|
|
504
|
+
"""
|
|
505
|
+
def setupEventHandler(self, blockDefaultHandler: bool) -> None:
|
|
506
|
+
"""
|
|
507
|
+
setup callbacks to grab window events and return them with methods below
|
|
474
508
|
"""
|
|
475
509
|
def visualsOnly(self, _visualsOnly: bool = True) -> None:
|
|
476
510
|
"""
|
|
@@ -722,10 +756,6 @@ class Frame:
|
|
|
722
756
|
@staticmethod
|
|
723
757
|
def _pybind11_conduit_v1_(*args, **kwargs):
|
|
724
758
|
...
|
|
725
|
-
def addAttributes(self, arg0: dict) -> None:
|
|
726
|
-
"""
|
|
727
|
-
add/set attributes for the frame
|
|
728
|
-
"""
|
|
729
759
|
def asDict(self) -> dict:
|
|
730
760
|
...
|
|
731
761
|
def computeCompoundInertia(self) -> Frame:
|
|
@@ -776,8 +806,10 @@ class Frame:
|
|
|
776
806
|
...
|
|
777
807
|
def makeRoot(self, untilPartBreak: bool) -> None:
|
|
778
808
|
...
|
|
779
|
-
def
|
|
780
|
-
|
|
809
|
+
def setAttributes(self, arg0: dict) -> Frame:
|
|
810
|
+
"""
|
|
811
|
+
set attributes for the frame
|
|
812
|
+
"""
|
|
781
813
|
def setColor(self, arg0: arr) -> Frame:
|
|
782
814
|
...
|
|
783
815
|
def setContact(self, arg0: int) -> Frame:
|
|
@@ -792,7 +824,7 @@ class Frame:
|
|
|
792
824
|
...
|
|
793
825
|
def setJointState(self, arg0: arr) -> Frame:
|
|
794
826
|
...
|
|
795
|
-
def setLines(self, verts: arr, colors: ... =
|
|
827
|
+
def setLines(self, verts: arr, colors: ... = ..., singleConnectedLine: bool = False) -> Frame:
|
|
796
828
|
"""
|
|
797
829
|
attach lines as shape
|
|
798
830
|
"""
|
|
@@ -814,17 +846,17 @@ class Frame:
|
|
|
814
846
|
"""
|
|
815
847
|
attach a point cloud shape
|
|
816
848
|
"""
|
|
817
|
-
def setPose(self, arg0: arr) ->
|
|
849
|
+
def setPose(self, arg0: arr) -> Frame:
|
|
818
850
|
...
|
|
819
|
-
def setPoseByText(self, arg0: str) ->
|
|
851
|
+
def setPoseByText(self, arg0: str) -> Frame:
|
|
820
852
|
...
|
|
821
853
|
def setPosition(self, arg0: arr) -> Frame:
|
|
822
854
|
...
|
|
823
855
|
def setQuaternion(self, arg0: arr) -> Frame:
|
|
824
856
|
...
|
|
825
|
-
def setRelativePose(self, arg0: arr) ->
|
|
857
|
+
def setRelativePose(self, arg0: arr) -> Frame:
|
|
826
858
|
...
|
|
827
|
-
def setRelativePoseByText(self, arg0: str) ->
|
|
859
|
+
def setRelativePoseByText(self, arg0: str) -> Frame:
|
|
828
860
|
...
|
|
829
861
|
def setRelativePosition(self, arg0: arr) -> Frame:
|
|
830
862
|
...
|
robotic/_robotic.so
CHANGED
|
Binary file
|
robotic/include/rai/Core/graph.h
CHANGED
|
@@ -189,7 +189,7 @@ struct Graph : NodeL {
|
|
|
189
189
|
Node* readNode(std::istream& is, bool verbose, bool parseInfo); //used only internally..
|
|
190
190
|
void readJson(std::istream& is);
|
|
191
191
|
void writeJson(std::istream& is);
|
|
192
|
-
void write(std::ostream& os=cout, const char* ELEMSEP="
|
|
192
|
+
void write(std::ostream& os=cout, const char* ELEMSEP="\n", const char* BRACKETS=0, int indent=-1, bool yamlMode=false, bool binary=false) const;
|
|
193
193
|
void writeDot(std::ostream& os, bool withoutHeader=false, bool defaultEdges=false, int nodesOrEdges=0, int focusIndex=-1, bool subGraphsAsNodes=false);
|
|
194
194
|
void writeHtml(std::ostream& os, std::istream& is);
|
|
195
195
|
void writeYaml(std::ostream& os) const;
|
robotic/include/rai/Core/util.h
CHANGED
|
@@ -621,6 +621,15 @@ inline bool operator==(Type& t1, Type& t2) { return t1.typeId() == t2.typeId();
|
|
|
621
621
|
// return x;
|
|
622
622
|
// }
|
|
623
623
|
|
|
624
|
+
//===========================================================================
|
|
625
|
+
//
|
|
626
|
+
// shared ptrs
|
|
627
|
+
//
|
|
628
|
+
|
|
629
|
+
template<class T> void _delete(T* ptr){}
|
|
630
|
+
template<class T> std::shared_ptr<T> _shared(T& x){ return std::shared_ptr<T>(&x, &_delete<T>); }
|
|
631
|
+
|
|
632
|
+
|
|
624
633
|
//===========================================================================
|
|
625
634
|
//
|
|
626
635
|
/// running code on init (in cpp files)
|
robotic/include/rai/Gui/opengl.h
CHANGED
|
@@ -107,8 +107,8 @@ void write_png(const byteA& img, const char* file_name, bool swap_rows=true);
|
|
|
107
107
|
struct OpenGL {
|
|
108
108
|
/// @name little structs to store objects and callbacks
|
|
109
109
|
struct GLHoverCall { virtual bool hoverCallback(OpenGL&) = 0; };
|
|
110
|
-
struct GLClickCall { virtual bool clickCallback(OpenGL
|
|
111
|
-
struct GLKeyCall { virtual bool keyCallback(OpenGL
|
|
110
|
+
struct GLClickCall { virtual bool clickCallback(OpenGL&, int button, int buttonIsDown) = 0; };
|
|
111
|
+
struct GLKeyCall { virtual bool keyCallback(OpenGL&, int key, int mods, bool keyIsDown) = 0; };
|
|
112
112
|
struct GLScrollCall { virtual bool scrollCallback(OpenGL&, int) = 0; };
|
|
113
113
|
struct GLEvent { int button, key, x, y; float dx, dy; void set(int b, int k, int _x, int _y, float _dx, float _dy) { button=b; key=k; x=_x; y=_y; dx=_dx; dy=_dy; } };
|
|
114
114
|
struct GLView { double le, ri, bo, to; rai::Array<rai::RenderData*> drawers; rai::Camera camera; GLView() { le=bo=0.; ri=to=1.; } str text; };
|
|
@@ -147,7 +147,7 @@ struct OpenGL {
|
|
|
147
147
|
Signaler isUpdating;
|
|
148
148
|
Signaler watching;
|
|
149
149
|
OpenGLDrawOptions drawOptions;
|
|
150
|
-
|
|
150
|
+
int selectID=-1;
|
|
151
151
|
std::shared_ptr<rai::RenderData> _data;
|
|
152
152
|
|
|
153
153
|
bool fullscreen=false; ///<window starts in fullscreenmode on the primary screen
|
robotic/include/rai/KOMO/komo.h
CHANGED
|
@@ -203,7 +203,7 @@ struct KOMO : NonCopyable {
|
|
|
203
203
|
int view_slice(uint t, bool pause=false);
|
|
204
204
|
void view_close();
|
|
205
205
|
std::shared_ptr<rai::ConfigurationViewer> get_viewer();
|
|
206
|
-
void set_viewer(std::shared_ptr<rai::ConfigurationViewer>& _viewer);
|
|
206
|
+
void set_viewer(const std::shared_ptr<rai::ConfigurationViewer>& _viewer);
|
|
207
207
|
|
|
208
208
|
|
|
209
209
|
void plotTrajectory();
|
robotic/include/rai/Kin/frame.h
CHANGED
|
@@ -169,7 +169,7 @@ struct Frame : NonCopyable {
|
|
|
169
169
|
Frame& setMesh(const arr& verts, const uintA& tris, const byteA& colors={}, const uintA& cvxParts={});
|
|
170
170
|
Frame& setMeshFile(str file, double scale=1.);
|
|
171
171
|
Frame& setTextureFile(str imgFile, const arr& texCoords={});
|
|
172
|
-
Frame& setLines(const arr& verts, const byteA& colors={});
|
|
172
|
+
Frame& setLines(const arr& verts, const byteA& colors={}, bool singleConnectedLine=false);
|
|
173
173
|
Frame& setPointCloud(const arr& points, const byteA& colors= {}, const arr& normals= {});
|
|
174
174
|
Frame& setConvexMesh(const arr& points, const byteA& colors= {}, double radius=0.);
|
|
175
175
|
Frame& setSdf(std::shared_ptr<SDF>& sdf);
|
robotic/include/rai/Kin/kin.h
CHANGED
|
@@ -271,7 +271,7 @@ public:
|
|
|
271
271
|
void addProxies(const uintA& collisionPairs);
|
|
272
272
|
|
|
273
273
|
/// @name extensions on demand
|
|
274
|
-
std::shared_ptr<ConfigurationViewer
|
|
274
|
+
std::shared_ptr<ConfigurationViewer> get_viewer();
|
|
275
275
|
OpenGL& gl();
|
|
276
276
|
void view_lock(const char* _lockInfo);
|
|
277
277
|
void view_unlock();
|
|
@@ -280,15 +280,13 @@ public:
|
|
|
280
280
|
FeatherstoneInterface& fs();
|
|
281
281
|
bool hasView();
|
|
282
282
|
int view(bool pause=false, const char* txt=nullptr);
|
|
283
|
-
void view_savePng(str saveVideoPath="z.vid/", int count=-1);
|
|
284
283
|
void saveVideoPic(uint& t, const char* pathPrefix="vid/");
|
|
285
284
|
void glAdd(void (*call)(void*, OpenGL&), void* classP);
|
|
286
285
|
int glAnimate();
|
|
287
286
|
void view_close();
|
|
288
|
-
void view_focus(const char* frameName, double heightAbs=1.);
|
|
289
287
|
void view_setCameraPose(const arr& pose);
|
|
290
288
|
arr view_getCameraPose();
|
|
291
|
-
void set_viewer(std::shared_ptr<ConfigurationViewer>& _viewer);
|
|
289
|
+
void set_viewer(const std::shared_ptr<ConfigurationViewer>& _viewer);
|
|
292
290
|
void coll_stepFcl();
|
|
293
291
|
void stepPhysx(double tau);
|
|
294
292
|
void stepOde(double tau);
|
|
@@ -38,8 +38,8 @@ struct PhysXInterface {
|
|
|
38
38
|
void pullMotorStates(rai::Configuration& C, arr& qDot);
|
|
39
39
|
|
|
40
40
|
void changeObjectType(rai::Frame* f, int type);
|
|
41
|
-
void
|
|
42
|
-
void removeJoint(rai::
|
|
41
|
+
void addRigidJoint(rai::Frame* from, rai::Frame* to);
|
|
42
|
+
void removeJoint(const rai::Frame* from, const rai::Frame* to);
|
|
43
43
|
void postAddObject(rai::Frame* f);
|
|
44
44
|
|
|
45
45
|
void setGravity(float grav);
|
|
@@ -86,8 +86,8 @@ struct Simulation {
|
|
|
86
86
|
//what are really the fundamental perturbations? Their (reactive?) management should be realized by 'agents'. We need a method to add purturbation agents.
|
|
87
87
|
void addImp(ImpType type, const StringA& frames, const arr& parameters);
|
|
88
88
|
|
|
89
|
-
void attach(Frame*
|
|
90
|
-
void detach(Frame*
|
|
89
|
+
void attach(Frame* from, Frame* to);
|
|
90
|
+
void detach(Frame* from, Frame* to);
|
|
91
91
|
|
|
92
92
|
//== management interface
|
|
93
93
|
|
|
@@ -126,8 +126,8 @@ struct TeleopCallbacks : OpenGL::GLClickCall, OpenGL::GLKeyCall, OpenGL::GLHover
|
|
|
126
126
|
TeleopCallbacks(rai::Configuration& C, rai::Frame* marker=0) : C(C), marker(marker) { q_ref = C.getJointState(); }
|
|
127
127
|
|
|
128
128
|
bool hasNewMarker();
|
|
129
|
-
virtual bool clickCallback(OpenGL& gl);
|
|
130
|
-
virtual bool keyCallback(OpenGL& gl);
|
|
129
|
+
virtual bool clickCallback(OpenGL& gl, int button, int buttonIsDown);
|
|
130
|
+
virtual bool keyCallback(OpenGL& gl, int key, int mods, bool _keyIsDown);
|
|
131
131
|
virtual bool hoverCallback(OpenGL& gl);
|
|
132
132
|
};
|
|
133
133
|
|
robotic/include/rai/Kin/viewer.h
CHANGED
|
@@ -40,8 +40,18 @@ struct ConfigurationViewer : RenderData {
|
|
|
40
40
|
void savePng(str saveVideoPath="z.vid/", int count=-1);
|
|
41
41
|
|
|
42
42
|
void raiseWindow();
|
|
43
|
+
void setWindow(const char* window_title, int w=400, int h=400);
|
|
43
44
|
void glDraw(OpenGL&);
|
|
44
|
-
void setCamera(rai::Frame*
|
|
45
|
+
void setCamera(rai::Frame* camFrame);
|
|
46
|
+
void setCameraPose(const arr& pose);
|
|
47
|
+
void focus(const arr& position, double heightAbs=1.);
|
|
48
|
+
arr getCameraPose();
|
|
49
|
+
|
|
50
|
+
void setupEventHandler(bool blockDefaultHandler);
|
|
51
|
+
StringA getEvents();
|
|
52
|
+
arr getEventCursor();
|
|
53
|
+
uint getEventCursorObject();
|
|
54
|
+
Mutex& getEventsMutex();
|
|
45
55
|
|
|
46
56
|
//mimic a OpenGL, directly calling the same methods in its gl
|
|
47
57
|
void _resetPressedKey();
|
|
@@ -51,6 +61,7 @@ private://draw data
|
|
|
51
61
|
bool abortPlay;
|
|
52
62
|
uint pngCount=0;
|
|
53
63
|
bool drawFrameLines=true;
|
|
64
|
+
shared_ptr<struct ViewerEventHandler> eventHandler;
|
|
54
65
|
public:
|
|
55
66
|
int drawSlice;
|
|
56
67
|
String text;
|
|
@@ -31,7 +31,7 @@ struct QueryResult {
|
|
|
31
31
|
stdOutPipe(QueryResult)
|
|
32
32
|
|
|
33
33
|
struct ConfigurationProblem {
|
|
34
|
-
rai::Configuration
|
|
34
|
+
shared_ptr<rai::Configuration> C;
|
|
35
35
|
arr limits;
|
|
36
36
|
uintA sphericalCoordinates;
|
|
37
37
|
|
|
@@ -45,7 +45,7 @@ struct ConfigurationProblem {
|
|
|
45
45
|
uint evals=0;
|
|
46
46
|
double queryTime=0.;
|
|
47
47
|
|
|
48
|
-
ConfigurationProblem(rai::Configuration
|
|
48
|
+
ConfigurationProblem(shared_ptr<rai::Configuration> _C, bool _useBroadCollisions=true, double _collisionTolerance=1e-3, int _verbose=0);
|
|
49
49
|
|
|
50
50
|
void setExplicitCollisionPairs(const StringA& _collisionPairs);
|
|
51
51
|
|
|
@@ -78,7 +78,7 @@ struct RRT_PathFinder : NonCopyable {
|
|
|
78
78
|
arr path;
|
|
79
79
|
|
|
80
80
|
//setup
|
|
81
|
-
void setProblem(Configuration
|
|
81
|
+
void setProblem(shared_ptr<Configuration> C);
|
|
82
82
|
void setStartGoal(const arr& _starts, const arr& _goals);
|
|
83
83
|
void setExplicitCollisionPairs(const StringA& collisionPairs);
|
|
84
84
|
|
robotic/librai.so
CHANGED
|
Binary file
|
robotic/manipulation.py
CHANGED
|
@@ -1,6 +1,7 @@
|
|
|
1
1
|
import robotic as ry
|
|
2
2
|
import numpy as np
|
|
3
3
|
import time
|
|
4
|
+
import pprint
|
|
4
5
|
|
|
5
6
|
class KOMO_ManipulationHelper():
|
|
6
7
|
|
|
@@ -361,18 +362,15 @@ class KOMO_ManipulationHelper():
|
|
|
361
362
|
if not self.ret.feasible:
|
|
362
363
|
print(f' -- infeasible:{self.info}\n {self.ret}')
|
|
363
364
|
if verbose>1:
|
|
364
|
-
|
|
365
|
+
objs = self.komo.report()
|
|
366
|
+
#pprint.pp(objs)
|
|
367
|
+
for k, v in objs.items():
|
|
368
|
+
print(f'objective {k}: {v}')
|
|
365
369
|
self.komo.view(True, f'failed: {self.info}\n{self.ret}')
|
|
366
|
-
if verbose>2:
|
|
367
|
-
while(self.komo.view_play(True, 1.)):
|
|
368
|
-
pass
|
|
369
370
|
else:
|
|
370
371
|
print(f' -- feasible:{self.info}\n {self.ret}')
|
|
371
372
|
if verbose>2:
|
|
372
373
|
self.komo.view(True, f'success: {self.info}\n{self.ret}')
|
|
373
|
-
if verbose>3:
|
|
374
|
-
while(self.komo.view_play(True, 1.)):
|
|
375
|
-
pass
|
|
376
374
|
|
|
377
375
|
return self.ret
|
|
378
376
|
|
robotic/meshTool
CHANGED
|
Binary file
|
robotic/src/mujoco_io.py
CHANGED
|
@@ -34,7 +34,7 @@ class MujocoLoader():
|
|
|
34
34
|
|
|
35
35
|
self.C = ry.Config()
|
|
36
36
|
self.base = self.C.addFrame('base')
|
|
37
|
-
self.base.
|
|
37
|
+
self.base.setAttributes({'multibody':True})
|
|
38
38
|
self.base.setPosition(basePos)
|
|
39
39
|
self.base.setQuaternion(baseQuat)
|
|
40
40
|
self.add_node(root, self.base, path, 0)
|
robotic/src/yaml_helper.py
CHANGED
|
@@ -1,3 +1,6 @@
|
|
|
1
|
+
#!/usr/bin/env python3
|
|
2
|
+
|
|
3
|
+
import sys
|
|
1
4
|
import yaml
|
|
2
5
|
#from ruamel import yaml
|
|
3
6
|
|
|
@@ -17,3 +20,10 @@ yaml.add_representer(quoted_string, quoted_string_rep)
|
|
|
17
20
|
def yaml_write_dict(data, filename):
|
|
18
21
|
with open(filename, 'w') as fil:
|
|
19
22
|
yaml.dump(noflow_dict(data), fil, default_flow_style=True, sort_keys=False, width=500)
|
|
23
|
+
|
|
24
|
+
if __name__ == "__main__":
|
|
25
|
+
filename = sys.argv[1]
|
|
26
|
+
with open(filename, 'r', encoding='utf-8') as fil:
|
|
27
|
+
data = yaml.safe_load(fil)
|
|
28
|
+
print(yaml.dump(noflow_dict(data), None, default_flow_style=True, sort_keys=False, width=500))
|
|
29
|
+
|
robotic/version.py
CHANGED
|
@@ -1 +1 @@
|
|
|
1
|
-
__version__ = '0.3.1.
|
|
1
|
+
__version__ = '0.3.1.dev2'
|
|
@@ -1,10 +1,10 @@
|
|
|
1
|
-
robotic/DataGen.pyi,sha256=
|
|
1
|
+
robotic/DataGen.pyi,sha256=qDQjATpbIgFvOrWk7F3ZTVbOuyXjT5nwHxrsRfGxWRU,3716
|
|
2
2
|
robotic/__init__.py,sha256=H8Qi-wA95h6SuziEFNZFEt6Tpt5UrttS9ftBjZCsMm4,421
|
|
3
|
-
robotic/_robotic.pyi,sha256=
|
|
4
|
-
robotic/_robotic.so,sha256=
|
|
5
|
-
robotic/librai.so,sha256=
|
|
6
|
-
robotic/manipulation.py,sha256=
|
|
7
|
-
robotic/meshTool,sha256=
|
|
3
|
+
robotic/_robotic.pyi,sha256=QGS7Zw1nxilAqTCbv0YemHU8ZDab02kp59FRkExtsHM,75530
|
|
4
|
+
robotic/_robotic.so,sha256=zdEmt66SxlXlOJwHhBrpwO2EU_a0DtnHNKI4L-4j_8o,1238824
|
|
5
|
+
robotic/librai.so,sha256=9MntSREVZlircpqFB83r8fVzv4oW0Ve3l2n9zIdl7OE,38726016
|
|
6
|
+
robotic/manipulation.py,sha256=0B7UzU9J7b4f19thz67TbvknoncxffQEMHSBB6ez1Jg,22279
|
|
7
|
+
robotic/meshTool,sha256=wxcOt_C3PAn2vbnMpGYm57rjrU4iZLoEriODlQResmg,52176
|
|
8
8
|
robotic/mujoco-import.py,sha256=8eC8ldlFwnYQfqII3FVdWEQ7zd1PkSdAF-oyryIQtkY,231
|
|
9
9
|
robotic/nlp.py,sha256=n9_hOj3i707DdL_r49Yd2eWyjsSOahW8DmJrEhQlNFw,3200
|
|
10
10
|
robotic/render.py,sha256=OE1dvyWHD7Oyzk4wlhXZ7m3v3xxa3zAL5_LCV1RgJXk,4662
|
|
@@ -17,7 +17,7 @@ robotic/ry-urdfConvert.py,sha256=8Efnq3PU202rrZrVEZiGwzFOJdvrLjTJ2q-gnY6-tiU,255
|
|
|
17
17
|
robotic/ry-view,sha256=T1Omn1QS7cNAtjQhBjMJTNz7aW5FgoOf9vBIfW0mFME,613
|
|
18
18
|
robotic/test.py,sha256=8hiDRB2kB37hE5cZ7h26AJDnSGYb1y8DwOrcEGD_5Hc,620
|
|
19
19
|
robotic/test.pyi,sha256=vVxwRSerjUG4bpB7pIhof7ZatrBqwg3Bj5voywa-YTI,917
|
|
20
|
-
robotic/version.py,sha256=
|
|
20
|
+
robotic/version.py,sha256=6zFXj91tQaAP1c18NoFsA-iEzHyvj6isEdLopC6_G48,27
|
|
21
21
|
robotic/include/rai/Algo/MLcourse.h,sha256=TGkAJWC5ollGfPw0-gcYL0TZeDJiHtWFzkHSMK8_lqU,1828
|
|
22
22
|
robotic/include/rai/Algo/RidgeRegression.h,sha256=VXiv6-xr3j--CN7DJTzUg9Xb49zV9FZ9dwzxP1CmcPM,3730
|
|
23
23
|
robotic/include/rai/Algo/SplineCtrlFeed.h,sha256=9ZtYLHXx9sExj0lZV6F5ZWaCtkm0R4hMiYb-KJjktnc,3339
|
|
@@ -50,17 +50,17 @@ robotic/include/rai/Core/array.h,sha256=YcI48DcBMUYgdlXP4V1dV6juBUe1iCtbKoxWjp4n
|
|
|
50
50
|
robotic/include/rai/Core/array.ipp,sha256=DNmfosznj0jF-5lXTb8NUejfrVfs_Fw3O0IvvnDfF7M,63560
|
|
51
51
|
robotic/include/rai/Core/arrayDouble.h,sha256=9pr_9g50dFluF2dLgc29bl9o6ri9C84p69fNW2PYqXg,28724
|
|
52
52
|
robotic/include/rai/Core/defines.h,sha256=hBTgf5EiJ50rQYW1saGw8Ox87aKVFOYVKnFw0jojVW0,6894
|
|
53
|
-
robotic/include/rai/Core/graph.h,sha256=
|
|
53
|
+
robotic/include/rai/Core/graph.h,sha256=K8LFdhTJ0zGXnd-uI8TaR_k5aTbX3Mf9uUCvr9Yhzxk,21127
|
|
54
54
|
robotic/include/rai/Core/h5.h,sha256=cfs8cew5QYpOxbWFZHV9TXVh5_dEJdFF1-aGZVR54EY,1162
|
|
55
55
|
robotic/include/rai/Core/thread.h,sha256=wjwvXACwI8B6rhZSf2UDruWUb8kT9Xjm-VE-OnUQpwk,18248
|
|
56
|
-
robotic/include/rai/Core/util.h,sha256=
|
|
56
|
+
robotic/include/rai/Core/util.h,sha256=MB07dgIgOYQxsGpGnQS8VmfGch3MnDBbp3qQSn1zTB4,19694
|
|
57
57
|
robotic/include/rai/Core/util.ipp,sha256=soCVdpzWTpLL9i6rilFPNGozHZP40yhkmuXul7gHC7o,2157
|
|
58
58
|
robotic/include/rai/Core/lapack/blaswrap.h,sha256=jl8W6GwBGMiU-ND9ILeKqWlIvryw7AsIydPUCQGT_ew,3750
|
|
59
59
|
robotic/include/rai/Core/lapack/cblas.h,sha256=4bSmMzZ4idIPlmcwjw5HuwY1cs5RU73ZwmfydSpaBdk,32367
|
|
60
60
|
robotic/include/rai/Core/lapack/clapack.h,sha256=8rLteHzzGpKhJZXv4Eom9mk8lzbwRwjJuIqJuR1eePc,343373
|
|
61
61
|
robotic/include/rai/Core/lapack/lapacke.h,sha256=cpP6MEjkLGyhS8mV6ysRlTVeUam6f8zBgFUJB1phuwM,1045408
|
|
62
62
|
robotic/include/rai/DataGen/rndStableConfigs.h,sha256=bIz2RovkruMjYaaDwJIkyevsF6oV16y7dhyKm6sp_6s,391
|
|
63
|
-
robotic/include/rai/DataGen/shapenetGrasps.h,sha256=
|
|
63
|
+
robotic/include/rai/DataGen/shapenetGrasps.h,sha256=NlpKWicgaylzw1si7EPzeM7cE_-V9jvhB4mK1Slmt8E,1620
|
|
64
64
|
robotic/include/rai/Geo/assimpInterface.h,sha256=2Jg7v2GZ83nz4kkgPLzbSWTIBmL9nZg-LhMlWcjiF_o,1055
|
|
65
65
|
robotic/include/rai/Geo/depth2PointCloud.h,sha256=0mXJnTk0sMB--KDE9CO_2gKgGw4gHXUe7xg6DcROhvk,1168
|
|
66
66
|
robotic/include/rai/Geo/fclInterface.h,sha256=d89JFW3WKI64gOdQSGs6uFdE7NcMavNg89BMHhzMDac,984
|
|
@@ -90,10 +90,10 @@ robotic/include/rai/Geo/ply/ply.h,sha256=_oAXgQ5CyHvUMtPDBxYtOBbnKDVoZf5PKMswisq
|
|
|
90
90
|
robotic/include/rai/Geo/vhacd/VHACD.h,sha256=QT_cT6PPzec_mxKODsS9cJGr6nBt6S8cUJF7dCeBQCc,258343
|
|
91
91
|
robotic/include/rai/Gui/RenderData.h,sha256=SQEJbq1lTdCBsbMx8Yo6Dk_EPpQ2pNxM5l9D9xVU-qk,4986
|
|
92
92
|
robotic/include/rai/Gui/color.h,sha256=4ElBkpWgwBuqQEFD4Mdhv_afZE4ul6NkptwFQ2oDS5o,2596
|
|
93
|
-
robotic/include/rai/Gui/opengl.h,sha256=
|
|
93
|
+
robotic/include/rai/Gui/opengl.h,sha256=eFp5yfBh0sjqzGQ6xqeZdadsQzwYYVgeur_GMpmEdWA,9091
|
|
94
94
|
robotic/include/rai/Gui/plot.h,sha256=xhTBY84UN4KpgZsX7SJQGqVKd1jU7jojGVKFv02v0xU,2341
|
|
95
95
|
robotic/include/rai/KOMO/PathSmoother.h,sha256=y-t3yVEZvxfQIs8_EA-WI7FJ_RzfbG8TEfdiNAruuUI,813
|
|
96
|
-
robotic/include/rai/KOMO/komo.h,sha256=
|
|
96
|
+
robotic/include/rai/KOMO/komo.h,sha256=q4BhbBXiV3hrI05iqJdMIKYcqFVrozo2fmEIDY1PpDA,13395
|
|
97
97
|
robotic/include/rai/KOMO/komo_NLP.h,sha256=kSzUMDmw4yzAXtpNB2v38dpw2tBS8n8R_op_T3yS3DQ,3681
|
|
98
98
|
robotic/include/rai/KOMO/manipTools.h,sha256=WMdCxQB2rTcb3kzbiW9CHDpmGJZcKRqAnT861_iTsH4,4233
|
|
99
99
|
robotic/include/rai/KOMO/objective.h,sha256=Cl4-KjheRMNWoh_xFas5tLWMKSMlJf-HLDihfqvfcSw,2704
|
|
@@ -117,18 +117,18 @@ robotic/include/rai/Kin/dof_particles.h,sha256=PboLndC5a5extUKAfUPAIsJEGTTs6_ACD
|
|
|
117
117
|
robotic/include/rai/Kin/dof_path.h,sha256=XRPj3bH90JUIdkTS4jxwbAb5n9yAsRoemWUWUV1xDtQ,792
|
|
118
118
|
robotic/include/rai/Kin/feature.h,sha256=xicsrElMcYnYXdIXdO5LBLmXxvCGVUVgZJY2NIarO5I,3935
|
|
119
119
|
robotic/include/rai/Kin/featureSymbols.h,sha256=JVXbXoW43PlEGOgwHPpULlbXUQzkl79F1EFnfl-0wyk,1984
|
|
120
|
-
robotic/include/rai/Kin/frame.h,sha256=
|
|
121
|
-
robotic/include/rai/Kin/kin.h,sha256=
|
|
120
|
+
robotic/include/rai/Kin/frame.h,sha256=xqNwSGPxCmGOgCEtMZmeE80RJLXcHdpJRHWIkxbqCwU,14617
|
|
121
|
+
robotic/include/rai/Kin/kin.h,sha256=uu2rwBXk0vMLH4NzXJTBHyV2sRRXK_zHrnoy61zh0qc,16060
|
|
122
122
|
robotic/include/rai/Kin/kin_bullet.h,sha256=y8aApXpXY4bD5QN_WmDAU2vNEvvbdo1Rd4zY7qo-FKE,1970
|
|
123
123
|
robotic/include/rai/Kin/kin_feather.h,sha256=o-hOJA8UcmIBKx_qPzoG9R7fxzz-4zhBNMBmBTK21oA,1627
|
|
124
124
|
robotic/include/rai/Kin/kin_ode.h,sha256=zwB8Le1WMGRkQBc9bssndJICkjO1lZ_y1aZKCwP4c1Y,3686
|
|
125
|
-
robotic/include/rai/Kin/kin_physx.h,sha256=
|
|
125
|
+
robotic/include/rai/Kin/kin_physx.h,sha256=03YEr0M3ieuVnfwuHl9J2xRU2FwpLGvq4gUTjJqcDqA,1887
|
|
126
126
|
robotic/include/rai/Kin/proxy.h,sha256=jfFQrvokqvt8bGYEzGQoD2ZpnuWuLzCeOjFfUvdxcx0,1473
|
|
127
|
-
robotic/include/rai/Kin/simulation.h,sha256=
|
|
128
|
-
robotic/include/rai/Kin/viewer.h,sha256=
|
|
127
|
+
robotic/include/rai/Kin/simulation.h,sha256=RlFZ7w9xaQZ6GY_Wwb4BXbgy3rhzZaKnujVzM2vqLY4,5332
|
|
128
|
+
robotic/include/rai/Kin/viewer.h,sha256=XhfZ3QUYdCuye3NnCwPe2XnoJAqnf9RCtMAZLsc3fd4,2432
|
|
129
129
|
robotic/include/rai/LGP/LGP_SkeletonTool.h,sha256=T4lXAUxY2QFo_ETZEm7RqRzfmU6NAHdVcow8qj_8-9Y,3240
|
|
130
130
|
robotic/include/rai/LGP/LGP_Tool.h,sha256=vcQ3ixwJ4wepPDX8ZGkDBKGIpchJQWMOoMu82_cS_8I,4230
|
|
131
|
-
robotic/include/rai/LGP/LGP_computers.h,sha256=
|
|
131
|
+
robotic/include/rai/LGP/LGP_computers.h,sha256=YmHWOrSGz5HHNY5mUQheD-kPhOvzO3HsVRcaGvpME6o,6492
|
|
132
132
|
robotic/include/rai/LGP/LGP_node.h,sha256=gMNQLfkbdMR1C-sNufI3K23Qt_Su3tqfIWz46Ta0JNo,4100
|
|
133
133
|
robotic/include/rai/LGP/LGP_tree.h,sha256=J6W4Qypr70g0EZg30tTZBuca_6_O0sDQAGGv6Ow8oaE,4001
|
|
134
134
|
robotic/include/rai/LGP/Motif.h,sha256=-1cYCDDxJK3at3LKT2R-qRoum7o7CnziBg30yijt4Ls,592
|
|
@@ -155,9 +155,9 @@ robotic/include/rai/Optim/options.h,sha256=JSqHw6agqLkvfvw6kd54KHQ6Hz7xZyHeRkWAu
|
|
|
155
155
|
robotic/include/rai/Optim/primalDual.h,sha256=xHXhAPbZWPVj17ZGpDr4OrLJLYj_G1Wr_k4TCPFBiHc,1272
|
|
156
156
|
robotic/include/rai/Optim/testProblems_Opt.h,sha256=rYPVdz7y1pkmzJH6aIw3pQ6JqN2_HhJ50CAAdsL2r9A,6531
|
|
157
157
|
robotic/include/rai/Optim/utils.h,sha256=VMTSVUcg3UWN8RhBYSSyqoBCa_AcUrZ_7zvcz3XWEC0,3517
|
|
158
|
-
robotic/include/rai/PathAlgos/ConfigurationProblem.h,sha256=
|
|
158
|
+
robotic/include/rai/PathAlgos/ConfigurationProblem.h,sha256=Zl_J3yooYFxA2-z-ulFL67nfzQBX90hUbD_cVFzpb3U,1351
|
|
159
159
|
robotic/include/rai/PathAlgos/PathResult.h,sha256=xxZiD8ClGKO719mQR50BsIzOlHeoH0UH4QNzWifoz6c,1070
|
|
160
|
-
robotic/include/rai/PathAlgos/RRT_PathFinder.h,sha256=
|
|
160
|
+
robotic/include/rai/PathAlgos/RRT_PathFinder.h,sha256=DQ3ceE8A6CJ7xaf0NOihTy1w0WjAEJnPJU0J6NaDHe8,3293
|
|
161
161
|
robotic/include/rai/Perception/audio.h,sha256=HQPC8bmOv4Mdfl8f71eUmKFlRE0_N_spY3bg6YJzduo,1105
|
|
162
162
|
robotic/include/rai/Perception/avutil.h,sha256=RlxtNGw8mvKYrWI7Sy8neILBDb1SF2wuf4hFKjPx-4w,802
|
|
163
163
|
robotic/include/rai/Perception/colorseg.h,sha256=1zax9KZGSJcTZ7MTnLZBSbHlZsJqQ1NkvU6cStzQ4vc,2314
|
|
@@ -353,18 +353,18 @@ robotic/src/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
|
|
|
353
353
|
robotic/src/cleanMeshes.py,sha256=42T9WwN_cn4u_s_BzN2eRfBQxmZTEQ6ZYPBtsesA5BM,1678
|
|
354
354
|
robotic/src/mesh_helper.py,sha256=AMSOz3Eew9uJkDm5tFThbfJKcEQCmGyRLN4bZphISNk,16691
|
|
355
355
|
robotic/src/meshlabFilters.mlx,sha256=SCIiIk7XZusvKEKY62pHSem_R3TcMUP8BFaLTVUcnEg,3833
|
|
356
|
-
robotic/src/mujoco_io.py,sha256=
|
|
356
|
+
robotic/src/mujoco_io.py,sha256=drLNE4yo30hpOY01-AsuCWKLvNoG5w2YDSzR_rlyfz0,9474
|
|
357
357
|
robotic/src/urdf_io.py,sha256=bbPcJWS9rnYk8CWgEZTmx1XJRBIDrfwgCj-S_RFxl9U,8800
|
|
358
|
-
robotic/src/yaml_helper.py,sha256=
|
|
359
|
-
robotic-0.3.1.
|
|
360
|
-
robotic-0.3.1.
|
|
361
|
-
robotic-0.3.1.
|
|
362
|
-
robotic-0.3.1.
|
|
363
|
-
robotic-0.3.1.
|
|
364
|
-
robotic-0.3.1.
|
|
365
|
-
robotic-0.3.1.
|
|
366
|
-
robotic-0.3.1.
|
|
367
|
-
robotic-0.3.1.
|
|
368
|
-
robotic-0.3.1.
|
|
369
|
-
robotic-0.3.1.
|
|
370
|
-
robotic-0.3.1.
|
|
358
|
+
robotic/src/yaml_helper.py,sha256=Jf9QaKSNQrPkUPqd5FUDv7_h0wDlGXrhCdMwu6y-Nh0,925
|
|
359
|
+
robotic-0.3.1.dev2.data/scripts/ry-bot,sha256=LBNbbQeNNNd_tupI5463Xe-RKSD6xy4HGTbJloisCGk,2280
|
|
360
|
+
robotic-0.3.1.dev2.data/scripts/ry-h5info,sha256=eh9McT5Ury7bbTudxkSOLWo-tZ6heiSEpGStM07N-Dc,810
|
|
361
|
+
robotic-0.3.1.dev2.data/scripts/ry-info,sha256=fL5QXJL4Xx-Q42L2C29HHbj1XsmWdWiKIv9rVfc5sm4,425
|
|
362
|
+
robotic-0.3.1.dev2.data/scripts/ry-meshTool,sha256=h4f4wFPNaey3ziz870SrEvy6SsQSL-ZnR_cH3UuAZxE,101
|
|
363
|
+
robotic-0.3.1.dev2.data/scripts/ry-test,sha256=vcaPrFq9Co9N2F2Mdl2_1CTieOBssSoEhU67wXqJ2EY,981
|
|
364
|
+
robotic-0.3.1.dev2.data/scripts/ry-urdfConvert.py,sha256=762MIDmAhdCCj55QftY7wsy9gOEs-TDEWcRPt5dECyc,2542
|
|
365
|
+
robotic-0.3.1.dev2.data/scripts/ry-view,sha256=_GjUbVS2X3AWnlXqIHwU5dofLmUKA2-NUPySgS-QJNI,599
|
|
366
|
+
robotic-0.3.1.dev2.dist-info/licenses/LICENSE,sha256=oT-pAsUSXiuMq2_3omR87-GFBeBnegQYixH4Bm_7wag,1071
|
|
367
|
+
robotic-0.3.1.dev2.dist-info/METADATA,sha256=gpaBPxgQWGSgSEWO6QTYiggxiHoSazBYmyJfNP2FJcg,6659
|
|
368
|
+
robotic-0.3.1.dev2.dist-info/WHEEL,sha256=0-G7woG4LgutcYzUGJCOYFgoh749-FtfhSMeIPLVGS0,104
|
|
369
|
+
robotic-0.3.1.dev2.dist-info/top_level.txt,sha256=x5A4haAZ18y9FpO1IhXSVJ2TFdhVAgT5JMkejHUg_9U,8
|
|
370
|
+
robotic-0.3.1.dev2.dist-info/RECORD,,
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|