robotic 0.3.2__cp38-cp38-manylinux2014_x86_64.whl → 0.3.3.dev0__cp38-cp38-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/__init__.py +4 -1
- robotic/_robotic.pyi +45 -34
- robotic/_robotic.so +0 -0
- robotic/include/rai/Algo/RidgeRegression.h +1 -1
- robotic/include/rai/Core/arrayDouble.h +15 -4
- robotic/include/rai/Core/util.h +3 -0
- robotic/include/rai/DataGen/rndStableConfigs.h +1 -0
- robotic/include/rai/Geo/geo.h +4 -4
- robotic/include/rai/Geo/mesh.h +5 -5
- robotic/include/rai/Geo/pairCollision.h +1 -1
- robotic/include/rai/Geo/signedDistanceFunctions.h +2 -3
- robotic/include/rai/KOMO/komo.h +2 -0
- robotic/include/rai/KOMO/komo_NLP.h +2 -2
- robotic/include/rai/KOMO/manipTools.h +4 -0
- robotic/include/rai/KOMO/testProblems_KOMO.h +0 -7
- robotic/include/rai/Kin/kin_physx.h +6 -4
- robotic/include/rai/Kin/simulation.h +9 -4
- robotic/include/rai/LGP/LGP_TAMP_Abstraction.h +33 -0
- robotic/include/rai/LGP/LGP_Tool.h +4 -25
- robotic/include/rai/LGP/LGP_computers2.h +196 -0
- robotic/include/rai/LGP/NLP_Descriptor.h +5 -0
- robotic/include/rai/Optim/BayesOpt.h +3 -3
- robotic/include/rai/Optim/GlobalIterativeNewton.h +1 -1
- robotic/include/rai/Optim/NLP.h +7 -5
- robotic/include/rai/Optim/SlackGaussNewton.h +0 -10
- robotic/include/rai/Optim/constrained.h +1 -1
- robotic/include/rai/Optim/gradient.h +8 -6
- robotic/include/rai/Optim/lagrangian.h +3 -2
- robotic/include/rai/Optim/lbfgs.h +18 -0
- robotic/include/rai/Optim/liblbfgs.h +755 -0
- robotic/include/rai/Optim/m_LeastSquaresZeroOrder.h +38 -0
- robotic/include/rai/Optim/newton.h +3 -3
- robotic/include/rai/Optim/opt-ceres.h +2 -2
- robotic/include/rai/Optim/options.h +3 -2
- robotic/include/rai/Optim/primalDual.h +1 -1
- robotic/include/rai/Optim/testProblems_Opt.h +20 -8
- robotic/include/rai/Optim/utils.h +20 -79
- robotic/include/rai/Perception/pcl.h +10 -10
- robotic/librai.so +0 -0
- robotic/meshTool +0 -0
- robotic/rai-robotModels/panda/panda.g +9 -9
- robotic/rai-robotModels/panda/panda_withoutCollisionModels.g +3 -11
- robotic/rai-robotModels/pr2/pr2.g +5 -5
- robotic/rai-robotModels/pr2/pr2_clean.g +19 -19
- robotic/rai-robotModels/robotiq/robotiq_clean.g +2 -2
- robotic/rai-robotModels/scenarios/liftRing.g +2 -2
- robotic/rai-robotModels/scenarios/pandaSingle.g +1 -1
- robotic/rai-robotModels/tests/arm.g +15 -16
- robotic/ry-h5info +3 -12
- robotic/src/h5_helper.py +20 -5
- robotic/src/h5_helper.py~ +42 -0
- robotic/version.py +1 -1
- robotic-0.3.3.dev0.data/scripts/ry-h5info +23 -0
- {robotic-0.3.2.dist-info → robotic-0.3.3.dev0.dist-info}/METADATA +9 -9
- {robotic-0.3.2.dist-info → robotic-0.3.3.dev0.dist-info}/RECORD +64 -58
- robotic/test.py +0 -15
- robotic-0.3.2.data/scripts/ry-h5info +0 -32
- {robotic-0.3.2.data → robotic-0.3.3.dev0.data}/scripts/ry-bot +0 -0
- {robotic-0.3.2.data → robotic-0.3.3.dev0.data}/scripts/ry-info +0 -0
- {robotic-0.3.2.data → robotic-0.3.3.dev0.data}/scripts/ry-meshTool +0 -0
- {robotic-0.3.2.data → robotic-0.3.3.dev0.data}/scripts/ry-test +0 -0
- {robotic-0.3.2.data → robotic-0.3.3.dev0.data}/scripts/ry-urdfConvert.py +0 -0
- {robotic-0.3.2.data → robotic-0.3.3.dev0.data}/scripts/ry-view +0 -0
- {robotic-0.3.2.dist-info → robotic-0.3.3.dev0.dist-info}/LICENSE +0 -0
- {robotic-0.3.2.dist-info → robotic-0.3.3.dev0.dist-info}/WHEEL +0 -0
- {robotic-0.3.2.dist-info → robotic-0.3.3.dev0.dist-info}/top_level.txt +0 -0
robotic/__init__.py
CHANGED
|
@@ -13,5 +13,8 @@ from .manipulation import KOMO_ManipulationHelper
|
|
|
13
13
|
#from .src.config_urdf import URDFLoader
|
|
14
14
|
#from .src.mesh_helper import MeshHelper
|
|
15
15
|
|
|
16
|
+
|
|
16
17
|
import os
|
|
17
|
-
|
|
18
|
+
rai_path = os.path.abspath(os.path.dirname(__file__)) + '/rai-robotModels'
|
|
19
|
+
os.environ["RAI_PATH"] = rai_path
|
|
20
|
+
setRaiPath( rai_path )
|
robotic/_robotic.pyi
CHANGED
|
@@ -6,14 +6,7 @@ import numpy
|
|
|
6
6
|
import typing
|
|
7
7
|
from . import DataGen
|
|
8
8
|
from . import test
|
|
9
|
-
__all__ = ['
|
|
10
|
-
class Actions2KOMO_Translator:
|
|
11
|
-
"""
|
|
12
|
-
Actions2KOMO_Translator
|
|
13
|
-
"""
|
|
14
|
-
@staticmethod
|
|
15
|
-
def _pybind11_conduit_v1_(*args, **kwargs):
|
|
16
|
-
...
|
|
9
|
+
__all__ = ['ArgWord', 'BSpline', 'BotOp', 'CameraView', 'CameraViewSensor', 'Config', 'ConfigurationViewer', 'ControlMode', 'DataGen', 'FS', 'Frame', 'JT', 'KOMO', 'KOMO_Objective', 'LGP_TAMP_Abstraction', 'LGP_Tool', 'NLP', 'NLP_Factory', 'NLP_Sampler', 'NLP_Solver', 'NLP_SolverOptions', 'OT', 'OptBench_Skeleton_Handover', 'OptBench_Skeleton_Pick', 'OptBench_Skeleton_StackAndBalance', 'OptBenchmark_InvKin_Endeff', 'OptMethod', 'Quaternion', 'RRT_PathFinder', 'ST', 'SY', 'Simulation', 'SimulationEngine', 'Skeleton', 'SolverReturn', 'compiled', 'default_LGP_TAMP_Abstraction', 'depthImage2PointCloud', 'get_NLP_Problem_names', 'make_NLP_Problem', 'params_add', 'params_clear', 'params_file', 'params_get', 'params_print', 'raiPath', 'rnd_seed', 'rnd_seed_random', 'setRaiPath', 'test']
|
|
17
10
|
class ArgWord:
|
|
18
11
|
"""
|
|
19
12
|
[todo: replace by str]
|
|
@@ -381,6 +374,8 @@ class Config:
|
|
|
381
374
|
"""
|
|
382
375
|
get the joint state as a numpy vector, optionally only for a subset of joints specified as list of joint names
|
|
383
376
|
"""
|
|
377
|
+
def getRoots(self) -> list[Frame]:
|
|
378
|
+
...
|
|
384
379
|
def get_viewer(self) -> ConfigurationViewer:
|
|
385
380
|
...
|
|
386
381
|
def processInertias(self, recomputeInertias: bool = True, transformToDiagInertia: bool = False) -> None:
|
|
@@ -494,6 +489,8 @@ class ConfigurationViewer:
|
|
|
494
489
|
"""
|
|
495
490
|
return accumulated events as list of strings
|
|
496
491
|
"""
|
|
492
|
+
def getGLFWWindow(self) -> int:
|
|
493
|
+
...
|
|
497
494
|
def getRgb(self) -> ...:
|
|
498
495
|
"""
|
|
499
496
|
return the view's rgb image
|
|
@@ -1142,6 +1139,13 @@ class KOMO_Objective:
|
|
|
1142
1139
|
@staticmethod
|
|
1143
1140
|
def _pybind11_conduit_v1_(*args, **kwargs):
|
|
1144
1141
|
...
|
|
1142
|
+
class LGP_TAMP_Abstraction:
|
|
1143
|
+
"""
|
|
1144
|
+
LGP_TAMP_Abstraction
|
|
1145
|
+
"""
|
|
1146
|
+
@staticmethod
|
|
1147
|
+
def _pybind11_conduit_v1_(*args, **kwargs):
|
|
1148
|
+
...
|
|
1145
1149
|
class LGP_Tool:
|
|
1146
1150
|
"""
|
|
1147
1151
|
Tools to compute things (and solve) a Task-and-Motion Planning problem formulated as Logic-Geometric Program
|
|
@@ -1149,7 +1153,7 @@ class LGP_Tool:
|
|
|
1149
1153
|
@staticmethod
|
|
1150
1154
|
def _pybind11_conduit_v1_(*args, **kwargs):
|
|
1151
1155
|
...
|
|
1152
|
-
def __init__(self, arg0: Config, arg1:
|
|
1156
|
+
def __init__(self, arg0: Config, arg1: LGP_TAMP_Abstraction) -> None:
|
|
1153
1157
|
"""
|
|
1154
1158
|
initialization
|
|
1155
1159
|
"""
|
|
@@ -1476,20 +1480,20 @@ class OptMethod:
|
|
|
1476
1480
|
|
|
1477
1481
|
Ceres
|
|
1478
1482
|
"""
|
|
1479
|
-
Ceres: typing.ClassVar[OptMethod] # value = <OptMethod.Ceres:
|
|
1480
|
-
Ipopt: typing.ClassVar[OptMethod] # value = <OptMethod.Ipopt:
|
|
1483
|
+
Ceres: typing.ClassVar[OptMethod] # value = <OptMethod.Ceres: 14>
|
|
1484
|
+
Ipopt: typing.ClassVar[OptMethod] # value = <OptMethod.Ipopt: 12>
|
|
1481
1485
|
LBFGS: typing.ClassVar[OptMethod] # value = <OptMethod.LBFGS: 3>
|
|
1482
|
-
NLopt: typing.ClassVar[OptMethod] # value = <OptMethod.NLopt:
|
|
1483
|
-
__members__: typing.ClassVar[dict[str, OptMethod]] # value = {'none': <OptMethod.none: 0>, 'gradientDescent': <OptMethod.gradientDescent: 1>, 'rprop': <OptMethod.rprop: 2>, 'LBFGS': <OptMethod.LBFGS: 3>, 'newton': <OptMethod.newton: 4>, 'augmentedLag': <OptMethod.augmentedLag: 5>, 'squaredPenalty': <OptMethod.squaredPenalty:
|
|
1486
|
+
NLopt: typing.ClassVar[OptMethod] # value = <OptMethod.NLopt: 11>
|
|
1487
|
+
__members__: typing.ClassVar[dict[str, OptMethod]] # value = {'none': <OptMethod.none: 0>, 'gradientDescent': <OptMethod.gradientDescent: 1>, 'rprop': <OptMethod.rprop: 2>, 'LBFGS': <OptMethod.LBFGS: 3>, 'newton': <OptMethod.newton: 4>, 'augmentedLag': <OptMethod.augmentedLag: 5>, 'squaredPenalty': <OptMethod.squaredPenalty: 8>, 'logBarrier': <OptMethod.logBarrier: 6>, 'singleSquaredPenalty': <OptMethod.singleSquaredPenalty: 9>, 'slackGN': <OptMethod.slackGN: 10>, 'NLopt': <OptMethod.NLopt: 11>, 'Ipopt': <OptMethod.Ipopt: 12>, 'Ceres': <OptMethod.Ceres: 14>}
|
|
1484
1488
|
augmentedLag: typing.ClassVar[OptMethod] # value = <OptMethod.augmentedLag: 5>
|
|
1485
1489
|
gradientDescent: typing.ClassVar[OptMethod] # value = <OptMethod.gradientDescent: 1>
|
|
1486
|
-
logBarrier: typing.ClassVar[OptMethod] # value = <OptMethod.logBarrier:
|
|
1490
|
+
logBarrier: typing.ClassVar[OptMethod] # value = <OptMethod.logBarrier: 6>
|
|
1487
1491
|
newton: typing.ClassVar[OptMethod] # value = <OptMethod.newton: 4>
|
|
1488
1492
|
none: typing.ClassVar[OptMethod] # value = <OptMethod.none: 0>
|
|
1489
1493
|
rprop: typing.ClassVar[OptMethod] # value = <OptMethod.rprop: 2>
|
|
1490
|
-
singleSquaredPenalty: typing.ClassVar[OptMethod] # value = <OptMethod.singleSquaredPenalty:
|
|
1491
|
-
slackGN: typing.ClassVar[OptMethod] # value = <OptMethod.slackGN:
|
|
1492
|
-
squaredPenalty: typing.ClassVar[OptMethod] # value = <OptMethod.squaredPenalty:
|
|
1494
|
+
singleSquaredPenalty: typing.ClassVar[OptMethod] # value = <OptMethod.singleSquaredPenalty: 9>
|
|
1495
|
+
slackGN: typing.ClassVar[OptMethod] # value = <OptMethod.slackGN: 10>
|
|
1496
|
+
squaredPenalty: typing.ClassVar[OptMethod] # value = <OptMethod.squaredPenalty: 8>
|
|
1493
1497
|
@staticmethod
|
|
1494
1498
|
def _pybind11_conduit_v1_(*args, **kwargs):
|
|
1495
1499
|
...
|
|
@@ -1523,6 +1527,10 @@ class Quaternion:
|
|
|
1523
1527
|
"""
|
|
1524
1528
|
See the Quaternion Lecture Note https://www.user.tu-berlin.de/mtoussai/notes/quaternions.html for details
|
|
1525
1529
|
"""
|
|
1530
|
+
w: float
|
|
1531
|
+
x: float
|
|
1532
|
+
y: float
|
|
1533
|
+
z: float
|
|
1526
1534
|
@staticmethod
|
|
1527
1535
|
def _pybind11_conduit_v1_(*args, **kwargs):
|
|
1528
1536
|
...
|
|
@@ -1534,13 +1542,19 @@ class Quaternion:
|
|
|
1534
1542
|
"""
|
|
1535
1543
|
concatenation (quaternion multiplication) of two transforms
|
|
1536
1544
|
"""
|
|
1537
|
-
def
|
|
1545
|
+
def __neg__(self) -> Quaternion:
|
|
1546
|
+
"""
|
|
1547
|
+
inverse quaternion
|
|
1548
|
+
"""
|
|
1549
|
+
def __str__(self) -> str:
|
|
1550
|
+
...
|
|
1551
|
+
def append(self, q: Quaternion) -> Quaternion:
|
|
1538
1552
|
...
|
|
1539
1553
|
def applyOnPointArray(self, pts: arr) -> None:
|
|
1540
1554
|
...
|
|
1541
1555
|
def asArr(self) -> arr:
|
|
1542
1556
|
...
|
|
1543
|
-
def flipSign(self) ->
|
|
1557
|
+
def flipSign(self) -> Quaternion:
|
|
1544
1558
|
...
|
|
1545
1559
|
def getJacobian(self) -> arr:
|
|
1546
1560
|
...
|
|
@@ -1552,11 +1566,11 @@ class Quaternion:
|
|
|
1552
1566
|
...
|
|
1553
1567
|
def getRollPitchYaw(self) -> arr:
|
|
1554
1568
|
...
|
|
1555
|
-
def invert(self) ->
|
|
1569
|
+
def invert(self) -> Quaternion:
|
|
1556
1570
|
...
|
|
1557
1571
|
def multiply(self, f: float) -> None:
|
|
1558
1572
|
...
|
|
1559
|
-
def normalize(self) ->
|
|
1573
|
+
def normalize(self) -> Quaternion:
|
|
1560
1574
|
...
|
|
1561
1575
|
def set(self, q: arr) -> Quaternion:
|
|
1562
1576
|
...
|
|
@@ -1870,6 +1884,8 @@ class Simulation:
|
|
|
1870
1884
|
...
|
|
1871
1885
|
def detach(self, from: Frame, to: Frame) -> None:
|
|
1872
1886
|
...
|
|
1887
|
+
def getFreeFrames(self) -> list[Frame]:
|
|
1888
|
+
...
|
|
1873
1889
|
def getGripperWidth(self, gripperFrameName: str) -> float:
|
|
1874
1890
|
...
|
|
1875
1891
|
def getImageAndDepth(self) -> tuple:
|
|
@@ -1878,7 +1894,7 @@ class Simulation:
|
|
|
1878
1894
|
...
|
|
1879
1895
|
def getState(self) -> tuple:
|
|
1880
1896
|
"""
|
|
1881
|
-
returns a
|
|
1897
|
+
returns a 5-tuple of (time, q, qDot, freePos, freeVel)
|
|
1882
1898
|
"""
|
|
1883
1899
|
def getTimeToSplineEnd(self) -> float:
|
|
1884
1900
|
...
|
|
@@ -1900,7 +1916,7 @@ class Simulation:
|
|
|
1900
1916
|
"""
|
|
1901
1917
|
reset the spline reference, i.e., clear the current spline buffer and initialize it to constant spline at current position (to which setSplineRef can append)
|
|
1902
1918
|
"""
|
|
1903
|
-
def resetTime(self) -> None:
|
|
1919
|
+
def resetTime(self, arg0: float) -> None:
|
|
1904
1920
|
...
|
|
1905
1921
|
def selectSensor(self, sensorName: str) -> ...:
|
|
1906
1922
|
...
|
|
@@ -1911,7 +1927,7 @@ class Simulation:
|
|
|
1911
1927
|
* times: array with single total duration, or time for each control point (times.N==path.d0)
|
|
1912
1928
|
* append: append (with zero-velocity at append), or smoothly overwrite
|
|
1913
1929
|
"""
|
|
1914
|
-
def setState(self,
|
|
1930
|
+
def setState(self, time: float, q: arr, qDot: arr, freePos: arr, freeVel: arr) -> None:
|
|
1915
1931
|
...
|
|
1916
1932
|
def step(self, u_control: arr = ..., tau: float = 0.01, u_mode: ControlMode = ...) -> None:
|
|
1917
1933
|
...
|
|
@@ -2006,20 +2022,11 @@ class SolverReturn:
|
|
|
2006
2022
|
...
|
|
2007
2023
|
def dict(self) -> dict:
|
|
2008
2024
|
...
|
|
2009
|
-
class TAMP_Provider:
|
|
2010
|
-
"""
|
|
2011
|
-
TAMP_Provider
|
|
2012
|
-
"""
|
|
2013
|
-
@staticmethod
|
|
2014
|
-
def _pybind11_conduit_v1_(*args, **kwargs):
|
|
2015
|
-
...
|
|
2016
2025
|
def compiled() -> str:
|
|
2017
2026
|
"""
|
|
2018
2027
|
return a compile date+time version string
|
|
2019
2028
|
"""
|
|
2020
|
-
def
|
|
2021
|
-
...
|
|
2022
|
-
def default_TAMP_Provider(C: Config, lgp_config_file: str) -> TAMP_Provider:
|
|
2029
|
+
def default_LGP_TAMP_Abstraction(C: Config, lgp_config_file: str) -> LGP_TAMP_Abstraction:
|
|
2023
2030
|
...
|
|
2024
2031
|
def depthImage2PointCloud(depth: numpy.ndarray[numpy.float32], fxycxy: arr) -> arr:
|
|
2025
2032
|
"""
|
|
@@ -2045,6 +2052,10 @@ def params_file(filename: str) -> None:
|
|
|
2045
2052
|
"""
|
|
2046
2053
|
add parameters from a file
|
|
2047
2054
|
"""
|
|
2055
|
+
def params_get() -> dict:
|
|
2056
|
+
"""
|
|
2057
|
+
return parameters as dict
|
|
2058
|
+
"""
|
|
2048
2059
|
def params_print() -> None:
|
|
2049
2060
|
"""
|
|
2050
2061
|
print the parameters
|
robotic/_robotic.so
CHANGED
|
Binary file
|
|
@@ -74,7 +74,7 @@ struct KernelRidgeRegression {
|
|
|
74
74
|
arr evaluate(const arr& X, arr& bayesSigma2=NoArr); ///< returns f(x) and \s^2(x) for a set of points X
|
|
75
75
|
|
|
76
76
|
double evaluate(const arr& x, arr& df_x, arr& H, double plusSigma, bool onlySigma); ///< returns f(x) + coeff*\sigma(x) and its gradient and Hessian
|
|
77
|
-
ScalarFunction getF(double plusSigma);
|
|
77
|
+
shared_ptr<ScalarFunction> getF(double plusSigma);
|
|
78
78
|
};
|
|
79
79
|
|
|
80
80
|
struct KernelLogisticRegression {
|
|
@@ -288,7 +288,18 @@ typedef std::function<arr(const arr& x)> fct;
|
|
|
288
288
|
typedef std::function<arr(const arr& x)> VectorFunction;
|
|
289
289
|
|
|
290
290
|
/// a scalar function \f$f:~x\mapsto y\in\mathbb{R}\f$ with optional gradient and hessian
|
|
291
|
-
|
|
291
|
+
struct ScalarFunction {
|
|
292
|
+
uint dim;
|
|
293
|
+
virtual double f(arr& g, arr& H, const arr& x) = 0;
|
|
294
|
+
virtual ~ScalarFunction() {}
|
|
295
|
+
std::function<double(const arr& x)> cfunc(){ return [this](const arr& x){ return this->f(NoArr, NoArr, x); }; }
|
|
296
|
+
};
|
|
297
|
+
|
|
298
|
+
struct Conv_cfunc2ScalarFunction : ScalarFunction {
|
|
299
|
+
std::function<double(arr& g, arr& H, const arr& x)> cfunc;
|
|
300
|
+
Conv_cfunc2ScalarFunction(std::function<double(arr& g, arr& H, const arr& x)> _cfunc) : cfunc(_cfunc) {}
|
|
301
|
+
double f(arr& g, arr& H, const arr& x){ return cfunc(g, H, x); }
|
|
302
|
+
};
|
|
292
303
|
|
|
293
304
|
/// a kernel function
|
|
294
305
|
struct KernelFunction {
|
|
@@ -426,10 +437,10 @@ arr reshapeColor(const arr& col, int d0=-1);
|
|
|
426
437
|
|
|
427
438
|
void scanArrFile(const char* name);
|
|
428
439
|
|
|
429
|
-
arr finiteDifferenceGradient(
|
|
440
|
+
arr finiteDifferenceGradient(ScalarFunction& f, const arr& x, arr& Janalytic=NoArr, double eps=1e-8);
|
|
430
441
|
arr finiteDifferenceJacobian(const VectorFunction& f, const arr& _x, arr& Janalytic=NoArr, double eps=1e-8);
|
|
431
|
-
bool checkGradient(
|
|
432
|
-
bool checkHessian(
|
|
442
|
+
bool checkGradient(ScalarFunction& f, const arr& x, double tolerance, bool verbose=false);
|
|
443
|
+
bool checkHessian(ScalarFunction& f, const arr& x, double tolerance, bool verbose=false);
|
|
433
444
|
bool checkJacobian(const VectorFunction& f, const arr& x, double tolerance, bool verbose=false, const StringA& featureNames= {});
|
|
434
445
|
void boundClip(arr& y, const arr& bounds);
|
|
435
446
|
bool boundCheck(const arr& x, const arr& bounds, double eps=1e-3, bool verbose=true);
|
robotic/include/rai/Core/util.h
CHANGED
|
@@ -184,6 +184,7 @@ struct String : public std::iostream {
|
|
|
184
184
|
String& printf(const char* format, ...);
|
|
185
185
|
void resize(uint n, bool copy); //low-level resizing the string buffer - with additinal final 0
|
|
186
186
|
void append(char x);
|
|
187
|
+
String& append(const char* s);
|
|
187
188
|
void prepend(const String& s);
|
|
188
189
|
void replace(uint i, uint n, const char* xp, uint xN);
|
|
189
190
|
void removePrefix(const char* prefix);
|
|
@@ -212,6 +213,8 @@ struct String : public std::iostream {
|
|
|
212
213
|
bool endsWith(const String& substring) const;
|
|
213
214
|
bool endsWith(const char* substring) const;
|
|
214
215
|
|
|
216
|
+
void substituteEnvironmentVariables();
|
|
217
|
+
|
|
215
218
|
/// @name I/O
|
|
216
219
|
void write(std::ostream& os) const;
|
|
217
220
|
uint read(std::istream& is, const char* skipSymbols=0, const char* stopSymbols=0, int eatStopSymbol=-1);
|
robotic/include/rai/Geo/geo.h
CHANGED
|
@@ -134,16 +134,16 @@ struct Quaternion {
|
|
|
134
134
|
Quaternion& setInterpolateEmbedded(double t, const Quaternion& from, const Quaternion to);
|
|
135
135
|
Quaternion& setInterpolateProper(double t, const Quaternion& from, const Quaternion to);
|
|
136
136
|
void integrateDiffEq(arr& qdot, double tau);
|
|
137
|
-
|
|
138
|
-
|
|
137
|
+
Quaternion& invert();
|
|
138
|
+
Quaternion& flipSign();
|
|
139
139
|
void uniqueSign();
|
|
140
|
-
|
|
140
|
+
Quaternion& normalize();
|
|
141
141
|
void multiply(double f);
|
|
142
142
|
|
|
143
143
|
void appendX(double radians);
|
|
144
144
|
void appendY(double radians);
|
|
145
145
|
void appendZ(double radians);
|
|
146
|
-
|
|
146
|
+
Quaternion& append(const Quaternion& q);
|
|
147
147
|
|
|
148
148
|
double diffZero() const;
|
|
149
149
|
void checkZero() const;
|
robotic/include/rai/Geo/mesh.h
CHANGED
|
@@ -70,11 +70,11 @@ struct Mesh {
|
|
|
70
70
|
void setCapsule(double r, double l, uint fineness=2);
|
|
71
71
|
void setSSBox(double x_width, double y_width, double z_height, double r, uint fineness=2);
|
|
72
72
|
void setSSCvx(const arr& core, double r, uint fineness=2);
|
|
73
|
-
void setImplicitSurface(const
|
|
74
|
-
void setImplicitSurface(const
|
|
75
|
-
void setImplicitSurface(const arr& gridValues, const arr& lo, const arr&
|
|
76
|
-
void setImplicitSurface(const floatA& gridValues, const arr& lo, const arr&
|
|
77
|
-
void setImplicitSurfaceBySphereProjection(
|
|
73
|
+
void setImplicitSurface(std::function<double (const arr&)> f, double lo=-10., double up=+10., uint res=100);
|
|
74
|
+
void setImplicitSurface(std::function<double(const arr& x)> f, const arr& bounds, uint res);
|
|
75
|
+
void setImplicitSurface(const arr& gridValues, const arr& lo, const arr& up);
|
|
76
|
+
void setImplicitSurface(const floatA& gridValues, const arr& lo, const arr& up);
|
|
77
|
+
void setImplicitSurfaceBySphereProjection(ScalarFunction& f, double rad, uint fineness=3);
|
|
78
78
|
Mesh& setRandom(uint vertices=10);
|
|
79
79
|
void setGrid(uint X, uint Y);
|
|
80
80
|
|
|
@@ -43,7 +43,7 @@ struct PairCollision : NonCopyable {
|
|
|
43
43
|
const rai::Transformation& t1, const rai::Transformation& t2,
|
|
44
44
|
double rad1=0., double rad2=0.);
|
|
45
45
|
//sdf-to-sdf
|
|
46
|
-
PairCollision(ScalarFunction func1, ScalarFunction func2, const arr& seed);
|
|
46
|
+
PairCollision(ScalarFunction& func1, ScalarFunction& func2, const arr& seed);
|
|
47
47
|
|
|
48
48
|
~PairCollision() {}
|
|
49
49
|
|
|
@@ -18,8 +18,7 @@
|
|
|
18
18
|
|
|
19
19
|
struct SDF : ScalarFunction {
|
|
20
20
|
SDF(const rai::Transformation& _pose)
|
|
21
|
-
:
|
|
22
|
-
pose(_pose) {}
|
|
21
|
+
: pose(_pose) {}
|
|
23
22
|
~SDF() {}
|
|
24
23
|
rai::Transformation pose;
|
|
25
24
|
arr lo, up;
|
|
@@ -157,4 +156,4 @@ struct PCL2Field {
|
|
|
157
156
|
|
|
158
157
|
//===========================================================================
|
|
159
158
|
|
|
160
|
-
|
|
159
|
+
shared_ptr<ScalarFunction> DistanceFunction_SSBox();
|
robotic/include/rai/KOMO/komo.h
CHANGED
|
@@ -103,6 +103,7 @@ struct KOMO : rai::NonCopyable {
|
|
|
103
103
|
void clearObjectives(); ///< clear all objective
|
|
104
104
|
void removeObjective(const Objective* ob);
|
|
105
105
|
void copyObjectives(KOMO& komoB, bool deepCopyFeatures=true);
|
|
106
|
+
void checkConsistency();
|
|
106
107
|
|
|
107
108
|
void addContact_slide(double startTime, double endTime, const char* from, const char* to);
|
|
108
109
|
void addContact_stick(double startTime, double endTime, const char* from, const char* to, double frictionCone_mu=.8);
|
|
@@ -217,6 +218,7 @@ struct KOMO : rai::NonCopyable {
|
|
|
217
218
|
//
|
|
218
219
|
|
|
219
220
|
rai::Frame* addFrameDof(const char* name, const char* parent, rai::JointType jointType, bool stable, const char* originFrameName=0, rai::Frame* originFrame=0, const rai::Transformation& relOrigin=0);
|
|
221
|
+
void initFrameDof(rai::Frame* f, rai::Frame *q0Frame);
|
|
220
222
|
void addForceExchangeDofs(const arr& times, const char* onto, const char* from, rai::ForceExchangeType _type, const arr& initPoa={}, const arr& initForce={});
|
|
221
223
|
void set_x(const arr& x, const uintA& selectedConfigurationsOnly= {}); ///< set the state trajectory of all configurations
|
|
222
224
|
private:
|
|
@@ -57,7 +57,7 @@ struct KOMO_SubNLP : NLP {
|
|
|
57
57
|
};
|
|
58
58
|
|
|
59
59
|
//this treats EACH PART and force-dof as its own variable
|
|
60
|
-
struct
|
|
60
|
+
struct Conv_KOMO2FactoredNLP : NLP_Factored {
|
|
61
61
|
KOMO& komo;
|
|
62
62
|
|
|
63
63
|
//redundant to NLP_Factored::variableDims -- but sub can SUBSELECT!; in addition: dofs and names
|
|
@@ -75,7 +75,7 @@ struct Conv_KOMO_FactoredNLP : NLP_Factored {
|
|
|
75
75
|
VariableIndexEntry& vars(uint var_id) { if(subVars.N) return __variableIndex(subVars(var_id)); else return __variableIndex(var_id); }
|
|
76
76
|
FeatureIndexEntry& feats(uint feat_id) { if(subVars.N) return __featureIndex(subFeats(feat_id)); else return __featureIndex(feat_id); }
|
|
77
77
|
|
|
78
|
-
|
|
78
|
+
Conv_KOMO2FactoredNLP(KOMO& _komo, const rai::Array<DofL>& varDofs);
|
|
79
79
|
|
|
80
80
|
virtual void subSelect(const uintA& activeVariables, const uintA& conditionalVariables);
|
|
81
81
|
virtual uint numTotalVariables() { return __variableIndex.N; }
|
|
@@ -47,6 +47,10 @@ struct ManipulationHelper {
|
|
|
47
47
|
void freeze_joint(const arr& time_interval, const StringA& joints);
|
|
48
48
|
void freeze_relativePose(const arr& time_interval, str to, str from);
|
|
49
49
|
|
|
50
|
+
void action_pick(str action, double time, str gripper, str obj); //action can be 'pick_touch', 'pick_box'
|
|
51
|
+
void action_place_straightOn(str action, double time, str obj, str table); //action must be 'place_straightOn'
|
|
52
|
+
void action_place_box(str action, double time, str obj, str table, str gripper, str place_direction); //action can be 'place_box'
|
|
53
|
+
|
|
50
54
|
void snap_switch(double time, str parent, str obj);
|
|
51
55
|
|
|
52
56
|
void target_position();
|
|
@@ -19,13 +19,6 @@ namespace rai{
|
|
|
19
19
|
StringA get_NLP_Problem_names();
|
|
20
20
|
}
|
|
21
21
|
|
|
22
|
-
struct KOMO_wrap : std::shared_ptr<NLP> {
|
|
23
|
-
std::shared_ptr<KOMO> komo;
|
|
24
|
-
KOMO_wrap(const std::shared_ptr<KOMO>& _komo) : komo(_komo){
|
|
25
|
-
std::shared_ptr<NLP>::operator=( komo->nlp() );
|
|
26
|
-
}
|
|
27
|
-
};
|
|
28
|
-
|
|
29
22
|
shared_ptr<KOMO> problem_IK();
|
|
30
23
|
shared_ptr<KOMO> problem_IKobstacle();
|
|
31
24
|
shared_ptr<KOMO> problem_IKtorus();
|
|
@@ -28,14 +28,16 @@ struct PhysXInterface {
|
|
|
28
28
|
|
|
29
29
|
PhysXInterface(rai::Configuration& C, int verbose=1, const rai::PhysX_Options* _opt=0);
|
|
30
30
|
~PhysXInterface();
|
|
31
|
+
const FrameL& getFreeFrames();
|
|
32
|
+
const FrameL& getJointFrames();
|
|
31
33
|
|
|
32
34
|
void step(double tau=.01);
|
|
33
35
|
|
|
34
|
-
void
|
|
35
|
-
void
|
|
36
|
+
void pushFreeStates(const rai::Configuration& C, const arr& frameVelocities=NoArr, bool onlyKinematic=false);
|
|
37
|
+
void pullFreeStates(rai::Configuration& C, arr& frameVelocities=NoArr);
|
|
36
38
|
|
|
37
|
-
void
|
|
38
|
-
void
|
|
39
|
+
void pushJointTargets(const rai::Configuration& C, const arr& qDot_ref=NoArr, bool setStatesInstantly=false);
|
|
40
|
+
void pullJointStates(rai::Configuration& C, arr& qDot);
|
|
39
41
|
|
|
40
42
|
void changeObjectType(rai::Frame* f, int type);
|
|
41
43
|
void addRigidJoint(rai::Frame* from, rai::Frame* to);
|
|
@@ -59,7 +59,7 @@ struct Simulation {
|
|
|
59
59
|
//-- get state information
|
|
60
60
|
const arr& get_q() { return C.getJointState(); }
|
|
61
61
|
const arr& get_qDot();
|
|
62
|
-
const arr
|
|
62
|
+
const arr get_frameVelocities();
|
|
63
63
|
double getTimeToSplineEnd();
|
|
64
64
|
double getGripperWidth(const char* gripperFrameName);
|
|
65
65
|
bool getGripperIsGrasping(const char* gripperFrameName);
|
|
@@ -92,9 +92,12 @@ struct Simulation {
|
|
|
92
92
|
//== management interface
|
|
93
93
|
|
|
94
94
|
//-- store and reset the state of the simulation
|
|
95
|
-
void resetTime();
|
|
96
|
-
|
|
97
|
-
void
|
|
95
|
+
void resetTime(double t=0.);
|
|
96
|
+
struct State { double time; arr q, qDot, freePos, freeVel; };
|
|
97
|
+
void getState(State& state);
|
|
98
|
+
void setState(const State& state);
|
|
99
|
+
FrameL getFreeFrames();
|
|
100
|
+
FrameL getJointFrames();
|
|
98
101
|
void pushConfigurationToSimulator(const arr& frameVelocities=NoArr, const arr& qDot=NoArr);
|
|
99
102
|
|
|
100
103
|
//-- post-hoc world manipulations
|
|
@@ -108,6 +111,8 @@ struct Simulation {
|
|
|
108
111
|
std::shared_ptr<struct PhysXInterface> hidden_physx();
|
|
109
112
|
OpenGL& hidden_gl();
|
|
110
113
|
void loadTeleopCallbacks();
|
|
114
|
+
private:
|
|
115
|
+
void _controls2refs(arr& q_ref, arr& qDot_ref, double tau, const arr& q_real, const arr& u_control, ControlMode u_mode);
|
|
111
116
|
};
|
|
112
117
|
|
|
113
118
|
//===========================================================================
|
|
@@ -0,0 +1,33 @@
|
|
|
1
|
+
#pragma once
|
|
2
|
+
|
|
3
|
+
#include <KOMO/komo.h>
|
|
4
|
+
|
|
5
|
+
namespace rai {
|
|
6
|
+
|
|
7
|
+
//===========================================================================
|
|
8
|
+
|
|
9
|
+
struct LGP_TAMP_Abstraction{
|
|
10
|
+
virtual ~LGP_TAMP_Abstraction() {}
|
|
11
|
+
|
|
12
|
+
//parameters
|
|
13
|
+
virtual Configuration& getConfig() = 0;
|
|
14
|
+
bool useBroadCollisions=false;
|
|
15
|
+
StringA explicitCollisions;
|
|
16
|
+
|
|
17
|
+
//abstraction of the logic parts: get feasible action sequences
|
|
18
|
+
virtual Array<StringA> getNewActionSequence() = 0;
|
|
19
|
+
|
|
20
|
+
//abstraction of the motion parts: given an action sequence, what are the constraints on waypoints, and potential additional running constraints on motions between waypoints
|
|
21
|
+
virtual std::shared_ptr<KOMO> setup_sequence(Configuration& C, uint K) = 0;
|
|
22
|
+
virtual std::shared_ptr<KOMO> setup_motion(Configuration& C, uint K) = 0;
|
|
23
|
+
virtual void add_action_constraints(std::shared_ptr<KOMO>& komo, double time, const StringA& action) = 0;
|
|
24
|
+
virtual void add_action_constraints_motion(std::shared_ptr<KOMO>& komo, double time, const StringA& prev_action, const StringA& action, uint actionPhase) = 0;
|
|
25
|
+
|
|
26
|
+
//predefined helper functions for solvers: generically using the above to setup a full waypoints and path problem
|
|
27
|
+
std::shared_ptr<KOMO> get_waypointsProblem(Configuration& C, StringAA& actionSequence);
|
|
28
|
+
std::shared_ptr<KOMO> get_fullMotionProblem(Configuration& C, StringAA& actionSequence, shared_ptr<KOMO> initWithWaypoints={});
|
|
29
|
+
};
|
|
30
|
+
|
|
31
|
+
PTR<LGP_TAMP_Abstraction> default_LGP_TAMP_Abstraction(rai::Configuration &C, const char* lgp_configfile);
|
|
32
|
+
|
|
33
|
+
}
|
|
@@ -1,30 +1,12 @@
|
|
|
1
1
|
#pragma once
|
|
2
2
|
|
|
3
3
|
#include "Motif.h"
|
|
4
|
-
|
|
5
|
-
#include <LGP/LGP_SkeletonTool.h>
|
|
6
|
-
#include <KOMO/manipTools.h>
|
|
4
|
+
#include "LGP_TAMP_Abstraction.h"
|
|
7
5
|
|
|
8
6
|
namespace rai {
|
|
9
7
|
|
|
10
8
|
//===========================================================================
|
|
11
9
|
|
|
12
|
-
struct Actions2KOMO_Translator {
|
|
13
|
-
virtual ~Actions2KOMO_Translator() {}
|
|
14
|
-
virtual std::shared_ptr<KOMO> setup_sequence(Configuration& C, uint K) = 0;
|
|
15
|
-
virtual void add_action_constraints(std::shared_ptr<KOMO>& komo, double time, const StringA& action) = 0;
|
|
16
|
-
virtual void add_action_constraints_motion(std::shared_ptr<KOMO>& komo, double time, const StringA& prev_action, const StringA& action, uint actionPhase) = 0;
|
|
17
|
-
};
|
|
18
|
-
|
|
19
|
-
struct TAMP_Provider{
|
|
20
|
-
virtual ~TAMP_Provider() {}
|
|
21
|
-
virtual Array<StringA> getNewPlan() = 0;
|
|
22
|
-
virtual Configuration& getConfig() = 0;
|
|
23
|
-
virtual StringA explicitCollisions() = 0;
|
|
24
|
-
};
|
|
25
|
-
|
|
26
|
-
//===========================================================================
|
|
27
|
-
|
|
28
10
|
struct ActionNode;
|
|
29
11
|
typedef Array<ActionNode*> ActionNodeL;
|
|
30
12
|
|
|
@@ -74,7 +56,7 @@ struct ActionNode{
|
|
|
74
56
|
ActionNode(ActionNode* _parent, StringA _action);
|
|
75
57
|
~ActionNode();
|
|
76
58
|
|
|
77
|
-
PTR<KOMO>& get_ways(Configuration& C,
|
|
59
|
+
PTR<KOMO>& get_ways(Configuration& C, LGP_TAMP_Abstraction& tamp);
|
|
78
60
|
Array<PTR<KOMO_Motif>>& getWayMotifs();
|
|
79
61
|
|
|
80
62
|
|
|
@@ -98,8 +80,7 @@ protected:
|
|
|
98
80
|
struct LGP_Tool{
|
|
99
81
|
//problem interface
|
|
100
82
|
Configuration& C;
|
|
101
|
-
|
|
102
|
-
Actions2KOMO_Translator& trans;
|
|
83
|
+
LGP_TAMP_Abstraction& tamp;
|
|
103
84
|
int verbose=1;
|
|
104
85
|
|
|
105
86
|
//internal data structures for action search and job management
|
|
@@ -113,7 +94,7 @@ struct LGP_Tool{
|
|
|
113
94
|
uint step_count=0;
|
|
114
95
|
|
|
115
96
|
LGP_Tool(const char* lgp_configfile);
|
|
116
|
-
LGP_Tool(Configuration& _C,
|
|
97
|
+
LGP_Tool(Configuration& _C, LGP_TAMP_Abstraction& _tamp);
|
|
117
98
|
~LGP_Tool();
|
|
118
99
|
|
|
119
100
|
void solve_step();
|
|
@@ -143,7 +124,5 @@ private:
|
|
|
143
124
|
//===========================================================================
|
|
144
125
|
|
|
145
126
|
MotifL analyzeMotifs(KOMO& komo, int verbose=0);
|
|
146
|
-
PTR<TAMP_Provider> default_TAMP_Provider(rai::Configuration &C, const char* lgp_configfile);
|
|
147
|
-
PTR<Actions2KOMO_Translator> default_Actions2KOMO_Translator();
|
|
148
127
|
|
|
149
128
|
} //namespace
|