robotic 0.2.5.dev3__cp39-cp39-manylinux2014_x86_64.whl → 0.2.7__cp39-cp39-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.

Files changed (56) hide show
  1. robotic/__init__.py +2 -0
  2. robotic/_robotic.pyi +59 -24
  3. robotic/_robotic.so +0 -0
  4. robotic/include/rai/Control/CtrlTargets.h +3 -3
  5. robotic/include/rai/Core/array.h +3 -3
  6. robotic/include/rai/Core/arrayDouble.h +0 -3
  7. robotic/include/rai/DataGen/rndStableConfigs.h +0 -1
  8. robotic/include/rai/Geo/mesh.h +1 -1
  9. robotic/include/rai/Geo/signedDistanceFunctions.h +1 -1
  10. robotic/include/rai/Gui/RenderData.h +3 -2
  11. robotic/include/rai/KOMO/komo.h +1 -0
  12. robotic/include/rai/KOMO/manipTools.h +12 -10
  13. robotic/include/rai/KOMO/{opt-benchmarks.h → testProblems_KOMO.h} +36 -0
  14. robotic/include/rai/Kin/F_geometrics.h +9 -0
  15. robotic/include/rai/Kin/featureSymbols.h +6 -1
  16. robotic/include/rai/Kin/frame.h +1 -1
  17. robotic/include/rai/Kin/kin.h +1 -0
  18. robotic/include/rai/Kin/simulation.h +1 -0
  19. robotic/include/rai/Kin/viewer.h +1 -1
  20. robotic/include/rai/LGP/LGP_Tool.h +6 -6
  21. robotic/include/rai/Optim/NLP_Sampler.h +4 -4
  22. robotic/include/rai/Optim/NLP_Solver.h +1 -0
  23. robotic/include/rai/Optim/SlackGaussNewton.h +54 -0
  24. robotic/include/rai/Optim/gradient.h +2 -2
  25. robotic/include/rai/Optim/opt-ipopt.h +1 -1
  26. robotic/include/rai/Optim/options.h +8 -7
  27. robotic/include/rai/Optim/{benchmarks.h → testProblems_Opt.h} +33 -16
  28. robotic/librai.so +0 -0
  29. robotic/manipulation.py +88 -111
  30. robotic/meshTool +0 -0
  31. robotic/rai-robotModels/panda/panda.g +3 -2
  32. robotic/rai-robotModels/scenarios/ballFinger.g +3 -3
  33. robotic/rai-robotModels/scenarios/mobilePanda.g +3 -0
  34. robotic/rai-robotModels/scenarios/pendulum.g +3 -2
  35. robotic/rai-robotModels/tests/arm.g +7 -7
  36. robotic/ry-h5info.py +28 -0
  37. robotic/version.py +1 -1
  38. {robotic-0.2.5.dev3.dist-info → robotic-0.2.7.dist-info}/METADATA +1 -1
  39. {robotic-0.2.5.dev3.dist-info → robotic-0.2.7.dist-info}/RECORD +50 -54
  40. robotic/include/rai/MCTS/env_robert.h +0 -106
  41. robotic/include/rai/MCTS/problem_BlindBranch.h +0 -47
  42. robotic/include/rai/MCTS/solver_AStar.h +0 -90
  43. robotic/include/rai/MCTS/solver_MBTS.h +0 -109
  44. robotic/include/rai/MCTS/solver_PlainMC.h +0 -58
  45. robotic/include/rai/MCTS/solver_marc.h +0 -63
  46. /robotic/include/rai/Geo/{geoOptim.h → testProblems_Geo.h} +0 -0
  47. {robotic-0.2.5.dev3.data → robotic-0.2.7.data}/scripts/ry-bot +0 -0
  48. {robotic-0.2.5.dev3.data → robotic-0.2.7.data}/scripts/ry-info +0 -0
  49. {robotic-0.2.5.dev3.data → robotic-0.2.7.data}/scripts/ry-meshTool +0 -0
  50. {robotic-0.2.5.dev3.data → robotic-0.2.7.data}/scripts/ry-test +0 -0
  51. {robotic-0.2.5.dev3.data → robotic-0.2.7.data}/scripts/ry-urdf2rai +0 -0
  52. {robotic-0.2.5.dev3.data → robotic-0.2.7.data}/scripts/ry-urdf2yaml +0 -0
  53. {robotic-0.2.5.dev3.data → robotic-0.2.7.data}/scripts/ry-view +0 -0
  54. {robotic-0.2.5.dev3.dist-info → robotic-0.2.7.dist-info}/LICENSE +0 -0
  55. {robotic-0.2.5.dev3.dist-info → robotic-0.2.7.dist-info}/WHEEL +0 -0
  56. {robotic-0.2.5.dev3.dist-info → robotic-0.2.7.dist-info}/top_level.txt +0 -0
@@ -0,0 +1,54 @@
1
+ /* ------------------------------------------------------------------
2
+ Copyright (c) 2011-2024 Marc Toussaint
3
+ email: toussaint@tu-berlin.de
4
+
5
+ This code is distributed under the MIT License.
6
+ Please see <root-path>/LICENSE for details.
7
+ -------------------------------------------------------------- */
8
+
9
+ #pragma once
10
+
11
+ #include "options.h"
12
+ #include "NLP.h"
13
+ #include "../Core/util.h"
14
+
15
+ //===========================================================================
16
+
17
+ namespace rai {
18
+
19
+ struct SlackGaussNewton_Options {
20
+ RAI_PARAM("sam/", double, tolerance, .01)
21
+ RAI_PARAM("sam/", double, margin, .0)
22
+ RAI_PARAM("sam/", int, verbose, 2)
23
+
24
+ RAI_PARAM("sam/", int, maxEvals, 50)
25
+ RAI_PARAM("sam/", double, stepMax, .1)
26
+ RAI_PARAM("sam/", double, damping, 1e-2)
27
+ };
28
+
29
+ struct SlackGaussNewton {
30
+ OptOptions opt;
31
+ std::shared_ptr<NLP> nlp;
32
+
33
+ SlackGaussNewton(const shared_ptr<NLP>& _nlp, const arr& x_init={});
34
+ SlackGaussNewton& setOptions(const OptOptions& _opt) { opt = _opt; return *this; }
35
+ std::shared_ptr<SolverReturn> solve();
36
+
37
+ private:
38
+ arr x;
39
+ uint evals=0;
40
+ uint iters=0;
41
+ double step();
42
+
43
+ struct Eval {
44
+ arr x;
45
+ arr phi, J;
46
+ arr err;
47
+ arr s, Js;
48
+ void eval(const arr& _x, SlackGaussNewton& walker);
49
+ } ev;
50
+ };
51
+
52
+ //===========================================================================
53
+
54
+ }
@@ -50,12 +50,12 @@ struct Rprop {
50
50
  unique_ptr<struct sRprop> self;
51
51
  Rprop();
52
52
  ~Rprop();
53
- void init(double initialStepSize=1., double minStepSize=1e-6, double maxStepSize=50.);
53
+ void init(double initialStepSize=1., double minStepSize=1e-6, double stepMaxSize=50.);
54
54
  bool step(arr& x, const ScalarFunction& f);
55
55
  uint loop(arr& x, const ScalarFunction& f, double stoppingTolerance=1e-2, double initialStepSize=1., uint maxIterations=1000, int verbose=0);
56
56
  };
57
57
 
58
58
  inline uint optRprop(arr& x, const ScalarFunction& f, rai::OptOptions opt=DEFAULT_OPTIONS) {
59
- return Rprop().loop(x, f, opt.stopTolerance, opt.initStep, opt.stopEvals, opt.verbose);
59
+ return Rprop().loop(x, f, opt.stopTolerance, opt.stepInit, opt.stopEvals, opt.verbose);
60
60
  }
61
61
 
@@ -15,6 +15,6 @@ struct IpoptInterface {
15
15
 
16
16
  IpoptInterface(const shared_ptr<NLP>& P) : P(P) {}
17
17
 
18
- arr solve(const arr& x_init=NoArr);
18
+ shared_ptr<SolverReturn> solve(const arr& x_init=NoArr);
19
19
  };
20
20
 
@@ -23,21 +23,22 @@ struct OptOptions {
23
23
  RAI_PARAM("opt/", int, stopInners, 1000)
24
24
  RAI_PARAM("opt/", int, stopOuters, 1000)
25
25
  RAI_PARAM("opt/", int, stopLineSteps, 10)
26
- RAI_PARAM("opt/", int, stopTinySteps, 10)
27
- RAI_PARAM("opt/", double, initStep, 1.)
28
- RAI_PARAM("opt/", double, minStep, -1.)
29
- RAI_PARAM("opt/", double, maxStep, .2)
30
- RAI_PARAM("opt/", double, damping, 1.)
26
+ RAI_PARAM("opt/", int, stopTinySteps, 4)
27
+ RAI_PARAM("opt/", double, stepInit, 1.)
28
+ RAI_PARAM("opt/", double, stepMin, -1.)
29
+ RAI_PARAM("opt/", double, stepMax, .2)
31
30
  RAI_PARAM("opt/", double, stepInc, 1.5)
32
31
  RAI_PARAM("opt/", double, stepDec, .5)
32
+ RAI_PARAM("opt/", double, damping, 1.)
33
33
  RAI_PARAM("opt/", double, wolfe, .01)
34
- RAI_PARAM("opt/", bool, boundedNewton, true)
35
34
  RAI_PARAM("opt/", double, muInit, 1.)
36
35
  RAI_PARAM("opt/", double, muInc, 5.)
37
36
  RAI_PARAM("opt/", double, muMax, 1e4)
38
37
  RAI_PARAM("opt/", double, muLBInit, .1)
39
38
  RAI_PARAM("opt/", double, muLBDec, .2)
40
- RAI_PARAM("opt/", double, maxLambda, -1.)
39
+ RAI_PARAM("opt/", double, lambdaMax, -1.)
40
+ RAI_PARAM("opt/", double, interiorPadding, 1e-2)
41
+ RAI_PARAM("opt/", bool, boundedNewton, true)
41
42
  RAI_PARAM_ENUM("opt/", ConstrainedMethodType, constrainedMethod, augmentedLag)
42
43
  // void write(std::ostream& os) const;
43
44
  };
@@ -83,24 +83,19 @@ struct NLP_RandomLP : NLP {
83
83
 
84
84
  //===========================================================================
85
85
 
86
- struct ChoiceConstraintFunction : NLP {
87
- enum WhichConstraint { none=0, wedge2D=1, halfcircle2D, randomLinear, circleLine2D, boundConstrained, boundConstrainedIneq } which;
88
- uint n;
89
- arr randomG;
90
- ChoiceConstraintFunction();
86
+ struct BoxNLP : NLP {
87
+ BoxNLP();
88
+ void evaluate(arr& phi, arr& J, const arr& x);
89
+ };
90
+
91
+ //===========================================================================
91
92
 
93
+ struct ModesNLP : NLP {
94
+ arr cen;
95
+ arr radii;
96
+
97
+ ModesNLP();
92
98
  void evaluate(arr& phi, arr& J, const arr& x);
93
- void getFHessian(arr& H, const arr& x);
94
- // virtual uint dim_g(){
95
- // if(which==randomLinear) return ;
96
- // if(which==wedge2D) return n;
97
- // if(which==circleLine2D) return 1;
98
- // return 2;
99
- // }
100
- // virtual uint dim_h(){
101
- // if(which==circleLine2D) return 1;
102
- // return 0;
103
- // }
104
99
  };
105
100
 
106
101
  //===========================================================================
@@ -210,3 +205,25 @@ struct NLP_CircleLine : NLP {
210
205
  }
211
206
  };
212
207
 
208
+ //===========================================================================
209
+
210
+ struct ChoiceConstraintFunction : NLP {
211
+ enum WhichConstraint { none=0, wedge2D=1, halfcircle2D, randomLinear, circleLine2D, boundConstrained, boundConstrainedIneq } which;
212
+ uint n;
213
+ arr randomG;
214
+ ChoiceConstraintFunction();
215
+
216
+ void evaluate(arr& phi, arr& J, const arr& x);
217
+ void getFHessian(arr& H, const arr& x);
218
+ // virtual uint dim_g(){
219
+ // if(which==randomLinear) return ;
220
+ // if(which==wedge2D) return n;
221
+ // if(which==circleLine2D) return 1;
222
+ // return 2;
223
+ // }
224
+ // virtual uint dim_h(){
225
+ // if(which==circleLine2D) return 1;
226
+ // return 0;
227
+ // }
228
+ };
229
+
robotic/librai.so CHANGED
Binary file
robotic/manipulation.py CHANGED
@@ -2,18 +2,18 @@ import robotic as ry
2
2
  import numpy as np
3
3
  import time
4
4
 
5
- class ManipulationModelling():
5
+ class KOMO_ManipulationHelper():
6
6
 
7
7
  def __init__(self, info=str()):
8
- self.komo = None
9
8
  self.info = info
9
+ self.komo = ry.KOMO()
10
10
 
11
- def setup_inverse_kinematics(self, C, homing_scale=1e-1, accumulated_collisions=True, joint_limits=True, quaternion_norms=False):
11
+ def setup_inverse_kinematics(self, C, homing_scale=1e-1, accumulated_collisions=True, joint_limits=True, quaternion_norms=True):
12
12
  '''
13
13
  setup a 1 phase single step problem
14
14
  '''
15
- assert self.komo==None
16
- self.komo = ry.KOMO(C, 1., 1, 0, accumulated_collisions)
15
+ self.komo.setTiming(1., 1, 1., 0)
16
+ self.komo.setConfig(C, accumulated_collisions)
17
17
  self.komo.addControlObjective([], 0, homing_scale)
18
18
  if accumulated_collisions:
19
19
  self.komo.addObjective([], ry.FS.accumulatedCollisions, [], ry.OT.eq, [1e0])
@@ -22,9 +22,9 @@ class ManipulationModelling():
22
22
  if quaternion_norms:
23
23
  self.komo.addQuaternionNorms()
24
24
 
25
- def setup_sequence(self, C, K, homing_scale, velocity_scale, accumulated_collisions, joint_limits, quaternion_norms):
26
- assert self.komo==None
27
- self.komo = ry.KOMO(C, K, 1, 1, accumulated_collisions)
25
+ def setup_sequence(self, C, K, homing_scale=1e-2, velocity_scale=1e-1, accumulated_collisions=True, joint_limits=True, quaternion_norms=True):
26
+ self.komo.setTiming(float(K), 1, 1., 1)
27
+ self.komo.setConfig(C, accumulated_collisions)
28
28
  self.komo.addControlObjective([], 0, homing_scale)
29
29
  self.komo.addControlObjective([], 1, velocity_scale)
30
30
  if accumulated_collisions:
@@ -34,9 +34,9 @@ class ManipulationModelling():
34
34
  if quaternion_norms:
35
35
  self.komo.addQuaternionNorms()
36
36
 
37
- def setup_motion(self, C, K, steps_per_phase, homing_scale, acceleration_scale, accumulated_collisions, joint_limits, quaternion_norms):
38
- assert self.komo==None
39
- self.komo = ry.KOMO(C, K, steps_per_phase, 2, accumulated_collisions)
37
+ def setup_motion(self, C, K, steps_per_phase, homing_scale=0., acceleration_scale=1e-1, accumulated_collisions=True, joint_limits=True, quaternion_norms=True):
38
+ self.komo.setTiming(K, steps_per_phase, 1., 2)
39
+ self.komo.setConfig(C, True) #accumulated_collisions)
40
40
  if homing_scale>0.:
41
41
  self.komo.addControlObjective([], 0, homing_scale)
42
42
  self.komo.addControlObjective([], 2, acceleration_scale)
@@ -55,7 +55,6 @@ class ManipulationModelling():
55
55
  setup a 2 phase pick-and-place problem, with a pick switch at time 1, and a place switch at time 2
56
56
  the place mode switch at the final time two might seem obselete, but this switch also implies the geometric constraints of placeOn
57
57
  '''
58
- assert self.komo==None
59
58
  self.setup_sequence(C, 2, homing_scale, velocity_scale, accumulated_collisions, joint_limits, quaternion_norms)
60
59
 
61
60
  #-- option 1: old-style mode switches: //a temporary free stable joint gripper -> object
@@ -64,36 +63,29 @@ class ManipulationModelling():
64
63
  self.add_stable_frame(ry.JT.free, gripper, 'obj_grasp', initFrame=obj)
65
64
  self.snap_switch(1., 'obj_grasp', obj)
66
65
  #-- option 3: a permanent free stable object->grasp joint; and a snap gripper->grasp
67
- # self.add_stable_frame(ry.JT.free, obj, 'obj_grasp', initFrame=obj)
66
+ # self.komo.add_stable_frame(ry.JT.free, obj, 'obj_grasp', initFrame=obj)
68
67
  # self.snap_switch(1., gripper, 'obj_grasp')
69
68
 
70
69
  def setup_point_to_point_motion(self, C, q1, homing_scale=1e-2, acceleration_scale=1e-1, accumulated_collisions=True, joint_limits=True, quaternion_norms=False):
71
70
  '''
72
71
  setup a 1 phase fine-grained motion problem with 2nd order (acceleration) control costs
73
72
  '''
74
- assert self.komo==None
75
- self.setup_motion(C, 1, 32, homing_scale, acceleration_scale, accumulated_collisions, joint_limits, quaternion_norms)
73
+ self.setup_motion(C, 1, 50, homing_scale, acceleration_scale, accumulated_collisions, joint_limits, quaternion_norms)
76
74
 
77
- self.komo.initWithWaypoints([q1], 1, interpolate=True, qHomeInterpolate=.5, verbose=0)
75
+ self.komo.initWithWaypoints([q1], 1, interpolate=True, qHomeInterpolate=(.2 if homing_scale>1e-2 else .0), verbose=0)
78
76
  self.komo.addObjective([1.], ry.FS.qItself, [], ry.OT.eq, scale=[1e0], target=q1)
79
77
 
80
- def setup_point_to_point_rrt(self, C, q0, q1, explicitCollisionPairs):
81
- rrt = ry.PathFinder()
82
- rrt.setProblem(C, q0, q1)
83
- if len(explicitCollisionPairs):
84
- rrt.setExplicitCollisionPairs(explicitCollisionPairs)
85
-
86
78
  def add_stable_frame(self, jointType, parent, name, initFrame=None, markerSize=-1.):
87
79
  if isinstance(initFrame, str):
88
- #initFrame = self.komo.getConfig().getFrame(initFrame)
89
80
  f = self.komo.addFrameDof(name, parent, jointType, True, initFrame, None)
90
81
  else:
91
82
  f = self.komo.addFrameDof(name, parent, jointType, True, None, initFrame)
92
83
  if markerSize>0.:
93
- f.setShape(ry.ST.marker, [.2])
84
+ f.setShape(ry.ST.marker, [.1])
94
85
  f.setColor([1., 0., 1.])
86
+
95
87
  #f.joint.sampleSdv=1.
96
- #f.joint.setRandom(self.komo.timeSlices.d1, 0)
88
+ #f.joint.setRandom(self.timeSlices.d1, 0)
97
89
 
98
90
  def grasp_top_box(self, time, gripper, obj, grasp_direction='xz'):
99
91
  '''
@@ -185,7 +177,7 @@ class ManipulationModelling():
185
177
  boxSize = obj_frame.getSize()
186
178
  if obj_frame.getShapeType()==ry.ST.ssBox:
187
179
  boxSize = boxSize[:3]
188
- elif obj_frame.getType()==ry.ST.ssCylinder:
180
+ elif obj_frame.getShapeType()==ry.ST.ssCylinder:
189
181
  boxSize = [boxSize[1], boxSize[1], boxSize[0]]
190
182
  else:
191
183
  raise Exception('NIY')
@@ -238,41 +230,32 @@ class ManipulationModelling():
238
230
  def straight_push(self, time_interval, obj, gripper, table):
239
231
  #start & end helper frames
240
232
  helperStart = f'_straight_pushStart_{gripper}_{obj}_{time_interval[0]}'
241
- helperEnd = f'_straight_pushEnd_{gripper}_{obj}_{time_interval[1]}'
233
+ #helperEnd = f'_straight_pushEnd_{gripper}_{obj}_{time_interval[1]}'
242
234
  if not self.komo.getConfig().getFrame(helperStart, False):
243
- self.add_stable_frame(ry.JT.hingeZ, table, helperStart, obj, .3)
244
- if not self.komo.getConfig().getFrame(helperEnd, False):
245
- self.add_stable_frame(ry.JT.transXYPhi, table, helperEnd, obj, .3)
246
-
247
- #-- couple both frames symmetricaly
248
- #aligned orientation
249
- self.komo.addObjective([time_interval[0]], ry.FS.vectorYDiff, [helperStart, helperEnd], ry.OT.eq, [1e1])
250
- #aligned position
251
- self.komo.addObjective([time_interval[0]], ry.FS.positionRel, [helperEnd, helperStart], ry.OT.eq, 1e1*np.array([[1., 0., 0.], [0., 0., 1.]]))
252
- self.komo.addObjective([time_interval[0]], ry.FS.positionRel, [helperStart, helperEnd], ry.OT.eq, 1e1*np.array([[1., 0., 0.], [0., 0., 1.]]))
253
- #at least 2cm appart, positivenot !not direction
254
- self.komo.addObjective([time_interval[0]], ry.FS.positionRel, [helperEnd, helperStart], ry.OT.ineq, -1e2*np.array([[0., 1., 0.]]), [.0, .02, .0])
255
- self.komo.addObjective([time_interval[0]], ry.FS.positionRel, [helperStart, helperEnd], ry.OT.ineq, 1e2*np.array([[0., 1., 0.]]), [.0, -.02, .0])
235
+ # self.add_stable_frame(ry.JT.hingeZ, table, helperStart, obj, .3)
236
+ helper_frame = self.komo.addFrameDof(helperStart, obj, ry.JT.hingeZ, True)
237
+ # helper_frame.setAutoLimits()
238
+ # helper_frame.joint.sampleUniform=1.
239
+
240
+ #x-axis of A aligns with diff-pos of B AT END TIMEnot (always backward diff)
241
+ self.komo.addObjective([time_interval[1]], ry.FS.AlignYWithDiff, [helperStart, obj], ry.OT.eq, [1e0], [], 1)
256
242
 
257
243
  #gripper touch
258
- self.komo.addObjective([time_interval[0]], ry.FS.negDistance, [gripper, obj], ry.OT.eq, [1e1], [-.02])
244
+ self.komo.addObjective([time_interval[0]], ry.FS.negDistance, [gripper, obj], ry.OT.eq, [1e1], [-.025])
259
245
  #gripper start position
260
246
  self.komo.addObjective([time_interval[0]], ry.FS.positionRel, [gripper, helperStart], ry.OT.eq, 1e1*np.array([[1., 0., 0.], [0., 0., 1.]]))
261
247
  self.komo.addObjective([time_interval[0]], ry.FS.positionRel, [gripper, helperStart], ry.OT.ineq, 1e1*np.array([[0., 1., 0.]]), [.0, -.02, .0])
262
248
  #gripper start orientation
263
- self.komo.addObjective([time_interval[0]], ry.FS.scalarProductYY, [gripper, helperStart], ry.OT.ineq, [-1e1], [.2])
264
- self.komo.addObjective([time_interval[0]], ry.FS.scalarProductYZ, [gripper, helperStart], ry.OT.ineq, [-1e1], [.2])
265
- self.komo.addObjective([time_interval[0]], ry.FS.vectorXDiff, [gripper, helperStart], ry.OT.eq, [1e1])
266
-
267
- #obj end position
268
- self.komo.addObjective([time_interval[1]], ry.FS.positionDiff, [obj, helperEnd], ry.OT.eq, [1e1])
269
- #obj end orientation: unchanged
270
- self.komo.addObjective([time_interval[1]], ry.FS.quaternion, [obj], ry.OT.eq, [1e1], [], 1); #qobjPose.rot.getArr4d())
249
+ self.komo.addObjective([time_interval[0]], ry.FS.scalarProductYY, [gripper, helperStart], ry.OT.ineq, [-1e0], [.2])
250
+ self.komo.addObjective([time_interval[0]], ry.FS.scalarProductYZ, [gripper, helperStart], ry.OT.ineq, [-1e0], [.2])
251
+ self.komo.addObjective([time_interval[0]], ry.FS.vectorXDiff, [gripper, helperStart], ry.OT.eq, [1e0])
252
+
253
+ self.freeze_relativePose([time_interval[1]], gripper, obj)
271
254
 
272
255
  return helperStart
273
256
 
274
257
  def pull(self, times, obj, gripper, table):
275
- self.add_stable_frame(ry.JT.transXYPhi, table, '_pull_end', obj)
258
+ self.komo.add_stable_frame(ry.JT.transXYPhi, table, '_pull_end', obj)
276
259
  self.komo.addObjective([times[0]], ry.FS.vectorZ, [gripper], ry.OT.eq, [1e1], np.array([0,0,1]))
277
260
  self.komo.addObjective([times[1]], ry.FS.vectorZ, [gripper], ry.OT.eq, [1e1], np.array([0,0,1]))
278
261
  self.komo.addObjective([times[0]], ry.FS.vectorZ, [obj], ry.OT.eq, [1e1], np.array([0,0,1]))
@@ -281,34 +264,35 @@ class ManipulationModelling():
281
264
  self.komo.addObjective([times[0]], ry.FS.positionRel, [gripper, obj], ry.OT.eq, 1e1*np.array([[1., 0., 0.], [0., 1., 0.]]), np.array([0, 0, 0]))
282
265
  self.komo.addObjective([times[0]], ry.FS.negDistance, [gripper, obj], ry.OT.eq, [1e1], [-.005])
283
266
 
284
- def no_collisions(self, time_interval, objs, margin=.001):
267
+ def no_collisions(self, time_interval, objs, margin=.001, scale=1e1):
285
268
  '''
286
- inequality on distance between multiple objects
269
+ inequality on distance between pairs of objects
287
270
  '''
288
271
  while len(objs) > 1:
289
272
  comp = objs[0]
290
273
  del objs[0]
291
274
  for obj in objs:
292
- self.komo.addObjective(time_interval, ry.FS.negDistance, [comp, obj], ry.OT.ineq, [1e1], [-margin])
275
+ self.komo.addObjective(time_interval, ry.FS.negDistance, [comp, obj], ry.OT.ineq, [scale], [-margin])
293
276
 
294
- def snap_switch(self, time, parent, obj):
277
+ def freeze_joint(self, time_interval, joints):
295
278
  '''
296
- a kinematic mode switch, where at given time the obj becomes attached to parent with zero relative transform
297
- the parent is typically a stable_frame (i.e. a frame that has parameterized but stable (i.e. constant) relative transform)
279
+ constrain velocity of joint to zero
298
280
  '''
299
- self.komo.addRigidSwitch(time, [parent, obj])
281
+ self.komo.addObjective(time_interval, ry.FS.qItself, joints, ry.OT.eq, [1e1], [], 1)
300
282
 
301
- def switch_place():
283
+ def freeze_relativePose(self, time_interval, obj, relFrom):
302
284
  '''
303
- a kinematic mode switch, where obj becomes attached to table, with a 3D parameterized (XYPhi) stable relative pose
304
- this requires obj and table to be boxes and assumes default placement alone z-axis
305
- more general placements have to be modelled with switch_pick (table picking the object) and additinal user-defined geometric constraints
285
+ constrain velocity of the pose of 'obj' relative to 'relFrom' to zero
306
286
  '''
287
+ self.komo.addObjective(time_interval, ry.FS.poseRel, [obj, relFrom], ry.OT.eq, [1e1], [], 1)
307
288
 
308
- def target_position():
289
+ def snap_switch(self, time, parent, obj):
309
290
  '''
310
- impose a specific 3D target position on some object
291
+ a kinematic mode switch, where at given time the obj becomes attached to parent with zero relative transform
292
+ the parent is typically a stable_frame (i.e. a frame that has parameterized but stable (i.e. constant) relative transform)
311
293
  '''
294
+ self.komo.addRigidSwitch(time, [parent, obj])
295
+
312
296
 
313
297
  def target_relative_xy_position(self, time, obj, relativeTo, pos):
314
298
  '''
@@ -333,7 +317,7 @@ class ManipulationModelling():
333
317
  helper = f'_{gripper}_retract_{time_interval[0]}'
334
318
  f = self.komo.getFrame(gripper, time_interval[0])
335
319
  self.add_stable_frame(ry.JT.none, '', helper, f)
336
- # self.komo.view(True, helper)
320
+ # self.view(True, helper)
337
321
 
338
322
  self.komo.addObjective(time_interval, ry.FS.positionRel, [gripper, helper], ry.OT.eq, 1e2 * np.array([[1, 0, 0]]))
339
323
  self.komo.addObjective(time_interval, ry.FS.quaternionDiff, [gripper, helper], ry.OT.eq, [1e2])
@@ -343,7 +327,7 @@ class ManipulationModelling():
343
327
  helper = f'_{gripper}_approach_{time_interval[1]}'
344
328
  f = self.komo.getFrame(gripper, time_interval[1])
345
329
  self.add_stable_frame(ry.JT.none, '', helper, f)
346
- # self.komo.view(True, helper)
330
+ # self.view(True, helper)
347
331
 
348
332
  self.komo.addObjective(time_interval, ry.FS.positionRel, [gripper, helper], ry.OT.eq, 1e2 * np.array([[1, 0, 0]]))
349
333
  self.komo.addObjective(time_interval, ry.FS.quaternionDiff, [gripper, helper], ry.OT.eq, [1e2])
@@ -368,71 +352,64 @@ class ManipulationModelling():
368
352
  self.komo.addObjective([time_interval[0]], ry.FS.positionRel, [gripper, helper], ry.OT.ineq, -1e2 * np.array([[0, 0, 1]]), [0., 0., dist])
369
353
 
370
354
  def solve(self, verbose=1):
371
- if self.komo:
372
- sol = ry.NLP_Solver()
373
- sol.setProblem(self.komo.nlp())
374
- sol.setOptions(damping=1e-1, verbose=verbose-1, stopTolerance=1e-3, maxLambda=100., stopInners=20, stopEvals=200)
375
- self.ret = sol.solve()
376
- if self.ret.feasible:
377
- self.path = self.komo.getPath()
378
- else:
379
- self.path = None
380
- if verbose>0:
381
- if not self.ret.feasible:
382
- print(f' -- infeasible:{self.info}\n {self.ret}')
383
- if verbose>1:
384
- print(self.komo.report(False, True))
385
- self.komo.view(True, f'failed: {self.info}\n{self.ret}')
386
- if verbose>2:
387
- while(self.komo.view_play(True, 1.)):
388
- pass
389
- else:
390
- print(f' -- feasible:{self.info}\n {self.ret}')
391
- if verbose>2:
392
- self.komo.view(True, f'success: {self.info}\n{self.ret}')
393
- if verbose>3:
394
- while(self.komo.view_play(True, 1.)):
395
- pass
396
-
397
- elif self.rrt:
398
- ret = self.rrt.solve()
399
- if ret.feasible:
400
- self.path = ret.x
355
+ sol = ry.NLP_Solver()
356
+ sol.setProblem(self.komo.nlp())
357
+ sol.setOptions(damping=1e-1, verbose=verbose-1, stopTolerance=1e-3, lambdaMax=100., stopInners=20, stopEvals=200)
358
+ self.ret = sol.solve()
359
+ if self.ret.feasible:
360
+ self.path = self.komo.getPath()
361
+ else:
362
+ self.path = None
363
+ if verbose>0:
364
+ if not self.ret.feasible:
365
+ print(f' -- infeasible:{self.info}\n {self.ret}')
366
+ if verbose>1:
367
+ print(self.komo.report(False, True))
368
+ self.komo.view(True, f'failed: {self.info}\n{self.ret}')
369
+ if verbose>2:
370
+ while(self.komo.view_play(True, 1.)):
371
+ pass
401
372
  else:
402
- self.path = None
373
+ print(f' -- feasible:{self.info}\n {self.ret}')
374
+ if verbose>2:
375
+ self.komo.view(True, f'success: {self.info}\n{self.ret}')
376
+ if verbose>3:
377
+ while(self.komo.view_play(True, 1.)):
378
+ pass
403
379
 
404
- else:
405
- raise Exception('no problem defined')
406
-
407
- return self.path
380
+ return self.ret
408
381
 
409
382
  def debug(self, listObjectives, plotOverTime):
410
383
  # cout <<' -- DEBUG: ' <<info <<endl
411
384
  # cout <<' == solver return: ' <<*ret <<endl
412
- # cout <<' == all KOMO objectives with increasing errors:\n' <<self.komo.report(False, listObjectives, plotOverTime) <<endl
413
- # # cout <<' == objectives sorted by error and Lagrange gradient:\n' <<sol.reportLagrangeGradients(self.komo.featureNames) <<endl
385
+ # cout <<' == all KOMO objectives with increasing errors:\n' <<self.report(False, listObjectives, plotOverTime) <<endl
386
+ # # cout <<' == objectives sorted by error and Lagrange gradient:\n' <<sol.reportLagrangeGradients(self.featureNames) <<endl
414
387
  # cout <<' == view objective errors over slices in gnuplot' <<endl
415
388
  # cout <<' == scroll through solution in display window using SHIFT-scroll' <<endl
416
389
  self.komo.view(True, f'debug: {info}\n{self.ret}')
417
390
 
418
- def play(self, C, duration=1.):
391
+ def play(self, C: ry.Config, duration=1.):
392
+ dofs = C.getJointIDs()
393
+ path = self.komo.getPath(dofs)
419
394
  for t in range(self.path.shape[0]):
420
- C.setJointState(self.path[t])
395
+ C.setJointState(path[t])
421
396
  C.view(False, f'step {t}\n{self.info}')
422
397
  time.sleep(duration/self.path.shape[0])
423
398
 
424
399
  def sub_motion(self, phase, fixEnd=True, homing_scale=1e-2, acceleration_scale=1e-1, accumulated_collisions=True, quaternion_norms=False):
425
400
  (C, q0, q1) = self.komo.getSubProblem(phase)
426
- manip = ManipulationModelling(f'sub_motion_{phase}--{self.info}')
427
- manip.setup_point_to_point_motion(C, q1, homing_scale, acceleration_scale, accumulated_collisions, quaternion_norms)
428
- return manip
401
+ komo = KOMO_ManipulationHelper(f'sub_motion_{phase}--{self.info}')
402
+ komo.setup_point_to_point_motion(C, q1, homing_scale, acceleration_scale, accumulated_collisions, quaternion_norms)
403
+ return komo
429
404
 
430
405
  def sub_rrt(self, phase, explicitCollisionPairs=[]):
431
406
  (C, q0, q1) = self.komo.getSubProblem(phase)
432
- manip = ManipulationModelling(f'sub_rrt_{phase}--{self.info}')
433
- manip.setup_point_to_point_rrt(C, q0, q1, explicitCollisionPairs)
434
- return manip
435
-
407
+ rrt = ry.RRT_PathFinder()
408
+ rrt.setProblem(C, q0, q1)
409
+ if len(explicitCollisionPairs):
410
+ rrt.setExplicitCollisionPairs(explicitCollisionPairs)
411
+ return rrt
412
+
436
413
  @property
437
414
  def feasible(self):
438
415
  return self.ret.feasible
robotic/meshTool CHANGED
Binary file
@@ -39,8 +39,9 @@ Edit panda_joint4: { q: -2. }
39
39
  Edit panda_joint5: { q: -0. }
40
40
  Edit panda_joint6: { q: 2., limits: [.5, 3.] }
41
41
  Edit panda_joint7: { q: -.5 }
42
- Edit panda_finger_joint1: { q: .05 }
43
-
42
+ Edit panda_finger_joint1: { q: .04 }
43
+ Edit panda_finger_joint2: { q: .04 }
44
+
44
45
  ## kill rigid hand joints
45
46
 
46
47
  Edit panda_joint8: { joint: none }
@@ -1,5 +1,5 @@
1
1
  base { X:[0 0 .5], multibody, multibody_gravity: false }
2
- jointX(base){ joint:transX, mass:.01, limits=[-.5,.5], sampleUniform=1. }
3
- jointY(jointX){ joint:transY, mass:.01, limits=[-.5,.5], sampleUniform=1. }
4
- jointZ(jointY){ joint:transZ, limits=[-.5,.5], sampleUniform=1. }
2
+ jointX(base){ joint:transX, mass:.01, limits: [-1.,1.], motorLambda: .01, motorMass: .1, sampleUniform: 1. }
3
+ jointY(jointX){ joint:transY, mass:.01, limits: [-1.,1.], motorLambda: .01, motorMass: .1, sampleUniform: 1. }
4
+ jointZ(jointY){ joint:transZ, limits: [-1.,1.], motorLambda: .01, motorMass: .1, sampleUniform: 1. }
5
5
  finger(jointZ){ shape:sphere, size:[.2], color:[.5 1 1], contact:1, mass:.1 }
@@ -15,3 +15,6 @@ Prefix: False
15
15
  ## position them on the table
16
16
  Edit l_panda_base (ranger_base_link): { Q: "t(-.25 .0 .04) d(180 0 0 1)", joint: rigid }
17
17
  #Edit r_panda_base (ranger_base_link): { Q: "t( .22 .05 .02) d(0 0 0 1)", joint: rigid }
18
+
19
+ ## box
20
+ controlBox (ranger_base_link){ Q: [.15 0 .1], shape: ssBox, size: [.35 .45 .16 .01], color: [.1] }
@@ -2,11 +2,12 @@ world: {}
2
2
 
3
3
  roof (world): { shape: ssBox, Q: [0, 0, 2.], size: [2., 2., .1, .02], color: [.9, .9, .9, .2] }
4
4
 
5
- pend2base: { X:[0., 0., 2.], mass: .1, shape:ssBox, size: [.2, .2, .2, .01], multibody: true, multibody_gravity: true } %, multibody_fixedBase: false }
5
+ pend2base: { X:[0., 0., 2.], mass: .1, shape:ssBox, size: [.2, .2, .2, .01], multibody: true, multibody_gravity: true } #, multibody_fixedBase: false }
6
6
  pend2joint (pend2base): { joint: quatBall, q: [1, 0, .5, .5] }
7
7
  pend2a(pend2joint): { Q: [0, 0, -.6], shape: capsule, size: [1.2, .02], color: [.6] }
8
8
  pend2b(pend2joint): { Q: [0 .25 -1.2], shape: ssBox, size: [.1 2.5 .1 .02], color:[.6], mass: .5 }
9
9
 
10
+ table(world): { Q:[0, 0, .35], shape:ssBox, size:[2, 2, .1, .01], restitution: .9 }
11
+
10
12
  ball: { X:[0 0 1], shape: sphere, size: [.2], mass: 1., restitution: .9 }
11
13
 
12
- table(world): { Q:[0, 0, .35], shape:ssBox, size:[2, 2, .1, .01], restitution: .9 }
@@ -9,14 +9,14 @@ arm5: { shape: capsule, size: [0.1, 0.1, .4, .1], contact: -1, }
9
9
  arm6: { shape: capsule, size: [0.1, 0.1, .4, .1], contact: -1, }
10
10
  arm7: { shape: capsule, size: [0.1, 0.1, .4, .1], contact: -1, }
11
11
 
12
- (stem arm1): { joint: hingeX, pre: "t(0 0 1) d(90 1 0 0)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
12
+ (stem arm1): { joint: hingeX, limits:[-2,2], pre: "t(0 0 1) d(90 1 0 0)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
13
13
 
14
- (arm1 arm2): { joint: hingeX, pre: "t(0 0 0.2) d(45 0 0 1)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
15
- (arm2 arm3): { joint: hingeX, pre: "t(0 0 0.2) d(45 0 0 1)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
16
- (arm3 arm4): { joint: hingeX, pre: "t(0 0 0.2) d(45 0 0 1)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
17
- (arm4 arm5): { joint: quatBall, pre: "t(0 0 0.2) d(45 0 0 1)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
18
- (arm5 arm6): { joint: hingeX, pre: "t(0 0 0.2) d(45 0 0 1)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
19
- (arm6 arm7): { joint: hingeX, pre: "t(0 0 0.2) d(45 0 0 1)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
14
+ (arm1 arm2): { joint: hingeX, limits:[-2,2], pre: "t(0 0 0.2) d(45 0 0 1)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
15
+ (arm2 arm3): { joint: hingeX, limits:[-2,2], pre: "t(0 0 0.2) d(45 0 0 1)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
16
+ (arm3 arm4): { joint: hingeX, limits:[-2,2], pre: "t(0 0 0.2) d(45 0 0 1)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
17
+ (arm4 arm5): { joint: quatBall, limits:[-2,-2,-2,-2,2,2,2,2], pre: "t(0 0 0.2) d(45 0 0 1)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
18
+ (arm5 arm6): { joint: hingeX, limits:[-2,2], pre: "t(0 0 0.2) d(45 0 0 1)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
19
+ (arm6 arm7): { joint: hingeX, limits:[-2,2], pre: "t(0 0 0.2) d(45 0 0 1)", post: "t(0 0 .2)", Q: "T d(1 0 0 0)" }
20
20
 
21
21
  target: { X: "t(.7 -.5 1.2)", shape: sphere, size: [.1, .1, .1, .05], color: [0, .5, 0] }
22
22
 
robotic/ry-h5info.py ADDED
@@ -0,0 +1,28 @@
1
+ #!/usr/bin/env python3
2
+
3
+ import argparse
4
+ import h5py
5
+
6
+ parser = argparse.ArgumentParser(description='h5-file info')
7
+
8
+ parser.add_argument('FILE', type=str,
9
+ help='h5-file name')
10
+
11
+ def print_attrs(name, obj):
12
+ if isinstance(obj, h5py.Dataset):
13
+ print(' ', name, obj.name, obj.shape, obj.dtype)
14
+ else:
15
+ print('---', name)
16
+
17
+ def main():
18
+ args = parser.parse_args()
19
+
20
+ print('=== file', args.FILE)
21
+ try:
22
+ with h5py.File(args.FILE, 'r') as fil:
23
+ fil.visititems(print_attrs)
24
+ except KeyboardInterrupt:
25
+ sys.exit(1)
26
+
27
+ if __name__ == "__main__":
28
+ main()
robotic/version.py CHANGED
@@ -1 +1 @@
1
- __version__ = '0.2.5.dev3'
1
+ __version__ = '0.2.7'
@@ -1,6 +1,6 @@
1
1
  Metadata-Version: 2.2
2
2
  Name: robotic
3
- Version: 0.2.5.dev3
3
+ Version: 0.2.7
4
4
  Summary: Robotic Control Interface & Manipulation Planning Library
5
5
  Home-page: https://github.com/MarcToussaint/robotic/
6
6
  Author: Marc Toussaint