robotic 0.2.9.dev2__cp39-cp39-manylinux2014_x86_64.whl → 0.3.1__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.
- robotic/__init__.py +3 -3
- robotic/_robotic.pyi +17 -11
- robotic/_robotic.so +0 -0
- robotic/include/rai/Algo/rungeKutta.h +1 -1
- robotic/include/rai/Control/TimingMPC.h +2 -2
- robotic/include/rai/Core/array.h +64 -40
- robotic/include/rai/Core/array.ipp +244 -80
- robotic/include/rai/Core/arrayDouble.h +10 -13
- robotic/include/rai/Core/graph.h +23 -2
- robotic/include/rai/Core/h5.h +3 -1
- robotic/include/rai/Geo/fclInterface.h +3 -1
- robotic/include/rai/Geo/geo.h +4 -1
- robotic/include/rai/Geo/mesh.h +11 -5
- robotic/include/rai/Geo/pairCollision.h +4 -4
- robotic/include/rai/Gui/RenderData.h +4 -3
- robotic/include/rai/Gui/opengl.h +1 -1
- robotic/include/rai/KOMO/komo.h +1 -0
- robotic/include/rai/KOMO/manipTools.h +1 -1
- robotic/include/rai/Kin/F_forces.h +1 -1
- robotic/include/rai/Kin/dof_forceExchange.h +4 -4
- robotic/include/rai/Kin/frame.h +4 -3
- robotic/include/rai/Kin/kin.h +24 -15
- robotic/include/rai/Kin/kin_physx.h +2 -2
- robotic/include/rai/Kin/simulation.h +1 -0
- robotic/include/rai/Logic/folWorld.h +1 -1
- robotic/include/rai/Optim/testProblems_Opt.h +2 -2
- robotic/include/rai/Optim/utils.h +2 -2
- robotic/include/rai/PathAlgos/ConfigurationProblem.h +3 -2
- robotic/include/rai/PathAlgos/RRT_PathFinder.h +1 -1
- robotic/librai.so +0 -0
- robotic/meshTool +0 -0
- robotic/mujoco-import.py +5 -7
- robotic/rai-robotModels/g1/g1.g +11 -2
- robotic/rai-robotModels/g1/g1_29dof_conv.yml +64 -0
- robotic/rai-robotModels/objects/shelf.g +1 -1
- robotic/rai-robotModels/panda/panda.g +1 -1
- robotic/rai-robotModels/panda/panda_arm_hand_conv.g +22 -22
- robotic/rai-robotModels/panda/panda_arm_hand_conv.yml +24 -0
- robotic/rai-robotModels/pr2/pr2.g +6 -6
- robotic/rai-robotModels/pr2/pr2_clean.g +114 -114
- robotic/rai-robotModels/pr2/pr2_modifications.g +2 -2
- robotic/rai-robotModels/ranger/ranger.g +3 -3
- robotic/rai-robotModels/robotiq/robotiq.g +1 -1
- robotic/rai-robotModels/robotiq/robotiq_arg2f_85_model_conv.yml +19 -0
- robotic/rai-robotModels/scenarios/panda_fixRobotiq.g +3 -3
- robotic/rai-robotModels/tests/arm.g +11 -11
- robotic/rai-robotModels/ur10/ur10.g +1 -1
- robotic/rai-robotModels/ur10/ur10_clean.g +8 -8
- robotic/ry-h5info +2 -2
- robotic/ry-test +2 -1
- robotic/ry-urdfConvert.py +3 -2
- robotic/src/__init__.py +0 -0
- robotic/{cleanMeshes.py → src/cleanMeshes.py} +0 -0
- robotic/src/meshlabFilters.mlx +20 -0
- robotic/src/{config_mujoco.py → mujoco_io.py} +21 -16
- robotic/src/{config_urdf.py → urdf_io.py} +0 -0
- robotic/src/yaml_helper.py +0 -0
- robotic/test.py +15 -0
- robotic/version.py +1 -1
- {robotic-0.2.9.dev2.data → robotic-0.3.1.data}/scripts/ry-h5info +2 -2
- {robotic-0.2.9.dev2.data → robotic-0.3.1.data}/scripts/ry-test +2 -1
- robotic-0.3.1.data/scripts/ry-urdfConvert.py +74 -0
- {robotic-0.2.9.dev2.dist-info → robotic-0.3.1.dist-info}/METADATA +9 -15
- {robotic-0.2.9.dev2.dist-info → robotic-0.3.1.dist-info}/RECORD +70 -69
- {robotic-0.2.9.dev2.dist-info → robotic-0.3.1.dist-info}/WHEEL +1 -1
- robotic/rai-robotModels/g1/g1_29dof_conv.g +0 -77
- robotic/rai-robotModels/robotiq/robotiq_arg2f_85_model_conv.g +0 -21
- robotic/ry-urdf2rai +0 -222
- robotic/ry-urdf2yaml +0 -250
- robotic-0.2.9.dev2.data/scripts/ry-urdf2rai +0 -222
- robotic-0.2.9.dev2.data/scripts/ry-urdf2yaml +0 -250
- {robotic-0.2.9.dev2.data → robotic-0.3.1.data}/scripts/ry-bot +0 -0
- {robotic-0.2.9.dev2.data → robotic-0.3.1.data}/scripts/ry-info +0 -0
- {robotic-0.2.9.dev2.data → robotic-0.3.1.data}/scripts/ry-meshTool +0 -0
- {robotic-0.2.9.dev2.data → robotic-0.3.1.data}/scripts/ry-view +0 -0
- {robotic-0.2.9.dev2.dist-info → robotic-0.3.1.dist-info}/licenses/LICENSE +0 -0
- {robotic-0.2.9.dev2.dist-info → robotic-0.3.1.dist-info}/top_level.txt +0 -0
|
@@ -46,8 +46,8 @@ Edit l_gripper_r_finger_tip_joint: { gripL }
|
|
|
46
46
|
Edit laser_tilt_mount_joint: { laser }
|
|
47
47
|
|
|
48
48
|
## FT sensors
|
|
49
|
-
r_ft_sensor (r_wrist_roll_joint): { Q: "t(.01 0 0) d(-90 0 1 0) d(70.015 0 0 1)", shape: cylinder, color: [1, 0, 0], size: [.
|
|
50
|
-
l_ft_sensor (l_wrist_roll_joint): { Q: "t(.01 0 0) d(-90 0 1 0) d(70.015 0 0 1)", shape: cylinder, color: [1, 0, 0], size: [.
|
|
49
|
+
r_ft_sensor (r_wrist_roll_joint): { Q: "t(.01 0 0) d(-90 0 1 0) d(70.015 0 0 1)", shape: cylinder, color: [1, 0, 0], size: [.0356, .02] }
|
|
50
|
+
l_ft_sensor (l_wrist_roll_joint): { Q: "t(.01 0 0) d(-90 0 1 0) d(70.015 0 0 1)", shape: cylinder, color: [1, 0, 0], size: [.0356, .02] }
|
|
51
51
|
Edit r_wrist_roll_joint: { to: "t(.0356 0 0)" }
|
|
52
52
|
Edit l_wrist_roll_joint: { to: "t(.0356 0 0)" }
|
|
53
53
|
|
|
@@ -4,9 +4,9 @@ ranger_base { multibody: true, multibody_gravity: false }
|
|
|
4
4
|
|
|
5
5
|
ranger_transX(ranger_base) { joint: transX, limits: [-5 5], ctrl_H: 2., motorLambda:.02, motorMass:40 }
|
|
6
6
|
ranger_transY(ranger_transX) { joint: transY, limits: [-5 5], ctrl_H: 2., motorLambda:.02, motorMass:40 }
|
|
7
|
-
|
|
8
|
-
#ranger_rot(
|
|
9
|
-
ranger_rot(ranger_transY) { }
|
|
7
|
+
ranger_rot(ranger_transY) { joint: hingeZ, limits: [-5 5] }
|
|
8
|
+
#ranger_rot(ranger_transY) { joint: circleZ, limits: [-1.1 -1.1 1.1 1.1], ctrl_H: 2. }
|
|
9
|
+
#ranger_rot(ranger_transY) { }
|
|
10
10
|
|
|
11
11
|
Prefix: ranger_
|
|
12
12
|
Include: <ranger_mini_conv.g>
|
|
@@ -0,0 +1,19 @@
|
|
|
1
|
+
robotiq_arg2f_base_link: {shape: mesh, color: [0.1, 0.1, 0.1, 1.0], mesh: <meshes/robotiq_arg2f_85_base_link.h5>, mass: 0.22652, inertia: [0.00020005, -4.2442e-10, -2.9069e-10, 0.00017832, -3.4402e-08, 0.00013478]}
|
|
2
|
+
finger_joint_origin (robotiq_arg2f_base_link): {pose: [0.0, -0.0306011, 0.054904, 6.123233995736766e-17, 0.0, 0.0, 1.0]}
|
|
3
|
+
left_inner_knuckle_joint_origin (robotiq_arg2f_base_link): {pose: [0.0, -0.0127, 0.06142, 6.123233995736766e-17, 0.0, 0.0, 1.0]}
|
|
4
|
+
right_outer_knuckle_joint_origin (robotiq_arg2f_base_link): {pose: [0.0, 0.0306011, 0.054904]}
|
|
5
|
+
right_inner_knuckle_joint_origin (robotiq_arg2f_base_link): {pose: [0.0, 0.0127, 0.06142]}
|
|
6
|
+
finger_joint (finger_joint_origin): {joint: hingeX, limits: [0.0, 0.8], color: [0.792156862745098, 0.819607843137255, 0.933333333333333, 1.0] },
|
|
7
|
+
finger_metal_l(finger_joint): {pose: [1 -1 0 0], mesh: <meshes/robotiq_arg2f_85_outer_knuckle.h5>}
|
|
8
|
+
left_inner_knuckle_joint (left_inner_knuckle_joint_origin): {joint: hingeX, limits: [0.0, 0.8757], mimic: finger_joint, shape: mesh, color: [0.1, 0.1, 0.1, 1.0], mesh: <meshes/robotiq_arg2f_85_inner_knuckle.h5>}
|
|
9
|
+
right_outer_knuckle_joint (right_outer_knuckle_joint_origin): {joint: hingeX, limits: [0.0, 0.81], mimic: finger_joint, color: [0.792156862745098, 0.819607843137255, 0.933333333333333, 1.0]}
|
|
10
|
+
finger_metal_r(right_outer_knuckle_joint): {pose: [1 -1 0 0], mesh: <meshes/robotiq_arg2f_85_outer_knuckle.h5>}
|
|
11
|
+
right_inner_knuckle_joint (right_inner_knuckle_joint_origin): {joint: hingeX, limits: [0.0, 0.8757], mimic: finger_joint, shape: mesh, color: [0.1, 0.1, 0.1, 1.0], mesh: <meshes/robotiq_arg2f_85_inner_knuckle.h5>}
|
|
12
|
+
left_outer_finger_0 (finger_joint): {pose: [0.0, 0.0315, -0.0041], shape: mesh, color: [0.1, 0.1, 0.1, 1.0], mesh: <meshes/robotiq_arg2f_85_outer_finger.h5>}
|
|
13
|
+
left_inner_finger_joint_origin (finger_joint): {pose: [0.0, 0.0376, 0.043000000000000003]}
|
|
14
|
+
right_outer_finger_0 (right_outer_knuckle_joint): {pose: [0.0, 0.0315, -0.0041], shape: mesh, color: [0.1, 0.1, 0.1, 1.0], mesh: <meshes/robotiq_arg2f_85_outer_finger.h5>}
|
|
15
|
+
right_inner_finger_joint_origin (right_outer_knuckle_joint): {pose: [0.0, 0.0376, 0.043000000000000003]}
|
|
16
|
+
left_inner_finger_joint (left_inner_finger_joint_origin): {joint: hingeX, limits: [0.0, 0.8757], mimic: finger_joint, shape: mesh, color: [0.1, 0.1, 0.1, 1.0], mesh: <meshes/robotiq_arg2f_85_inner_finger.h5>}
|
|
17
|
+
right_inner_finger_joint (right_inner_finger_joint_origin): {joint: hingeX, limits: [0.0, 0.8757], mimic: finger_joint, shape: mesh, color: [0.1, 0.1, 0.1, 1.0], mesh: <meshes/robotiq_arg2f_85_inner_finger.h5>}
|
|
18
|
+
left_inner_finger_pad_0 (left_inner_finger_joint): {pose: [0.0, -0.0220203446692936, 0.03242], shape: box, size: [0.022, 0.00635, 0.0375], color: [0.9, 0.9, 0.9, 1.0]}
|
|
19
|
+
right_inner_finger_pad_0 (right_inner_finger_joint): {pose: [0.0, -0.0220203446692936, 0.03242], shape: box, size: [0.022, 0.00635, 0.0375], color: [0.9, 0.9, 0.9, 1.0]}
|
|
@@ -13,13 +13,13 @@ Edit panda_joint7: { q: -.5 }
|
|
|
13
13
|
|
|
14
14
|
Delete: panda_hand_joint_origin
|
|
15
15
|
Delete: panda_hand_joint
|
|
16
|
-
Delete: panda_hand
|
|
17
|
-
Delete: panda_hand_0
|
|
16
|
+
#Delete: panda_hand
|
|
17
|
+
#Delete: panda_hand_0
|
|
18
18
|
Delete: panda_finger_joint1_origin
|
|
19
19
|
Delete: panda_finger_joint2_origin
|
|
20
20
|
Delete: panda_finger_joint1
|
|
21
21
|
Delete: panda_finger_joint2
|
|
22
|
-
Delete: panda_leftfinger_0
|
|
22
|
+
#Delete: panda_leftfinger_0
|
|
23
23
|
Delete: panda_rightfinger_0
|
|
24
24
|
#Delete: panda_coll_hand
|
|
25
25
|
#Delete: panda_coll_finger1
|
|
@@ -1,13 +1,13 @@
|
|
|
1
1
|
|
|
2
|
-
stem: { X: "t(0 0 1)", shape: capsule, size: [
|
|
2
|
+
stem: { X: "t(0 0 1)", shape: capsule, size: [2, .1] }
|
|
3
3
|
|
|
4
|
-
arm1: { shape: capsule, size: [
|
|
5
|
-
arm2: { shape: capsule, size: [
|
|
6
|
-
arm3: { shape: capsule, size: [
|
|
7
|
-
arm4: { shape: capsule, size: [
|
|
8
|
-
arm5: { shape: capsule, size: [
|
|
9
|
-
arm6: { shape: capsule, size: [
|
|
10
|
-
arm7: { shape: capsule, size: [
|
|
4
|
+
arm1: { shape: capsule, size: [.4, .1], contact: -1, }
|
|
5
|
+
arm2: { shape: capsule, size: [.4, .1], contact: -1, }
|
|
6
|
+
arm3: { shape: capsule, size: [.4, .1], contact: -1, }
|
|
7
|
+
arm4: { shape: capsule, size: [.4, .1], contact: -1, }
|
|
8
|
+
arm5: { shape: capsule, size: [.4, .1], contact: -1, }
|
|
9
|
+
arm6: { shape: capsule, size: [.4, .1], contact: -1, }
|
|
10
|
+
arm7: { shape: capsule, size: [.4, .1], contact: -1, }
|
|
11
11
|
|
|
12
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
|
|
|
@@ -18,8 +18,8 @@ arm7: { shape: capsule, size: [0.1, 0.1, .4, .1], contact: -1, }
|
|
|
18
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
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
|
-
target: { X: "t(.7 -.5 1.2)", shape: sphere, size: [.
|
|
21
|
+
target: { X: "t(.7 -.5 1.2)", shape: sphere, size: [.05], color: [0, .5, 0] }
|
|
22
22
|
|
|
23
|
-
obstacle: { X: "t(1. -1.5 1.)", shape: sphere, size: [
|
|
23
|
+
obstacle: { X: "t(1. -1.5 1.)", shape: sphere, size: [.5], color: [1, 0, 0], contact, }
|
|
24
24
|
|
|
25
|
-
endeff(arm7): { shape: marker, Q: "T t(0 0 .3)", size: [.1
|
|
25
|
+
endeff(arm7): { shape: marker, Q: "T t(0 0 .3)", size: [.1] } # a marker shape at the tip of arm7
|
|
@@ -1,32 +1,32 @@
|
|
|
1
1
|
world: { }
|
|
2
|
-
world_joint_origin(world): {
|
|
2
|
+
world_joint_origin(world): { pose: [0, 0, 1, 1, 0, 0, 0] }
|
|
3
3
|
world_joint(world_joint_origin): { joint: rigid }
|
|
4
4
|
base_link(world_joint): { mass: 4, inertia: [0.00610633, 0.00610633, 0.01125] }
|
|
5
5
|
base_link_0(base_link): { shape: mesh, mesh: <ur_description/meshes/ur10/visual/Base.dae>, visual: True }
|
|
6
|
-
shoulder_pan_joint_origin(base_link): {
|
|
6
|
+
shoulder_pan_joint_origin(base_link): { pose: [0, 0, 0.1273, 1, 0, 0, 0] }
|
|
7
7
|
shoulder_pan_joint(shoulder_pan_joint_origin): { joint: hingeZ, limits: [-6.28319, 6.28319, 2.16, -1, 330], ctrl_limits: [2.16, -1, 330] }
|
|
8
8
|
shoulder_link(shoulder_pan_joint): { mass: 7.778, inertia: [0.0314743, 0.0314743, 0.0218756] }
|
|
9
9
|
shoulder_link_0(shoulder_link): { shape: mesh, mesh: <ur_description/meshes/ur10/visual/Shoulder.dae>, visual: True }
|
|
10
|
-
shoulder_lift_joint_origin(shoulder_link): {
|
|
10
|
+
shoulder_lift_joint_origin(shoulder_link): { pose: [0, 0.220941, 0, 0.707107, 0, 0.707107, 0] }
|
|
11
11
|
shoulder_lift_joint(shoulder_lift_joint_origin): { joint: hingeY, limits: [-6.28319, 6.28319, 2.16, -1, 330], ctrl_limits: [2.16, -1, 330] }
|
|
12
12
|
upper_arm_link(shoulder_lift_joint): { mass: 12.93, inertia: [0.421754, 0.421754, 0.0363656] }
|
|
13
13
|
upper_arm_link_0(upper_arm_link): { shape: mesh, mesh: <ur_description/meshes/ur10/visual/UpperArm.dae>, visual: True }
|
|
14
|
-
elbow_joint_origin(upper_arm_link): {
|
|
14
|
+
elbow_joint_origin(upper_arm_link): { pose: [0, -0.1719, 0.612, 1, 0, 0, 0] }
|
|
15
15
|
elbow_joint(elbow_joint_origin): { joint: hingeY, limits: [-6.28319, 6.28319, 3.15, -1, 150], ctrl_limits: [3.15, -1, 150] }
|
|
16
16
|
forearm_link(elbow_joint): { mass: 3.87, inertia: [0.11107, 0.11107, 0.0108844] }
|
|
17
17
|
forearm_link_0(forearm_link): { shape: mesh, mesh: <ur_description/meshes/ur10/visual/Forearm.dae>, visual: True }
|
|
18
|
-
wrist_1_joint_origin(forearm_link): {
|
|
18
|
+
wrist_1_joint_origin(forearm_link): { pose: [0, 0, 0.5723, 0.707107, 0, 0.707107, 0] }
|
|
19
19
|
wrist_1_joint(wrist_1_joint_origin): { joint: hingeY, limits: [-6.28319, 6.28319, 3.2, -1, 54], ctrl_limits: [3.2, -1, 54] }
|
|
20
20
|
wrist_1_link(wrist_1_joint): { mass: 1.96, inertia: [0.00510825, 0.00510825, 0.0055125] }
|
|
21
21
|
wrist_1_link_0(wrist_1_link): { shape: mesh, mesh: <ur_description/meshes/ur10/visual/Wrist1.dae>, visual: True }
|
|
22
|
-
wrist_2_joint_origin(wrist_1_link): {
|
|
22
|
+
wrist_2_joint_origin(wrist_1_link): { pose: [0, 0.1149, 0, 1, 0, 0, 0] }
|
|
23
23
|
wrist_2_joint(wrist_2_joint_origin): { joint: hingeZ, limits: [-6.28319, 6.28319, 3.2, -1, 54], ctrl_limits: [3.2, -1, 54] }
|
|
24
24
|
wrist_2_link(wrist_2_joint): { mass: 1.96, inertia: [0.00510825, 0.00510825, 0.0055125] }
|
|
25
25
|
wrist_2_link_0(wrist_2_link): { shape: mesh, mesh: <ur_description/meshes/ur10/visual/Wrist2.dae>, visual: True }
|
|
26
|
-
wrist_3_joint_origin(wrist_2_link): {
|
|
26
|
+
wrist_3_joint_origin(wrist_2_link): { pose: [0, 0, 0.1157, 1, 0, 0, 0] }
|
|
27
27
|
wrist_3_joint(wrist_3_joint_origin): { joint: hingeY, limits: [-6.28319, 6.28319, 3.2, -1, 54], ctrl_limits: [3.2, -1, 54] }
|
|
28
28
|
wrist_3_link(wrist_3_joint): { mass: 0.202, inertia: [0.000526462, 0.000526462, 0.000568125] }
|
|
29
29
|
wrist_3_link_0(wrist_3_link): { shape: mesh, mesh: <ur_description/meshes/ur10/visual/Wrist3.dae>, visual: True }
|
|
30
|
-
ee_fixed_joint_origin(wrist_3_link): {
|
|
30
|
+
ee_fixed_joint_origin(wrist_3_link): { pose: [0, 0.0922, 0, 0.707107, 0, 0, 0.707107] }
|
|
31
31
|
ee_fixed_joint(ee_fixed_joint_origin): { joint: rigid }
|
|
32
32
|
ee_link(ee_fixed_joint): { }
|
robotic/ry-h5info
CHANGED
|
@@ -12,9 +12,9 @@ def print_attrs(name, obj):
|
|
|
12
12
|
if isinstance(obj, h5py.Dataset):
|
|
13
13
|
print(' ', name, obj.name, obj.shape, obj.dtype, f'{obj.size*obj.dtype.itemsize/1024:.2f}kB')
|
|
14
14
|
if obj.dtype=='int8':
|
|
15
|
-
print(''.join([chr(x) for x in obj[()]]))
|
|
15
|
+
print(' ', ''.join([chr(x) for x in obj[()]]))
|
|
16
16
|
elif obj.size<20:
|
|
17
|
-
print(obj[()])
|
|
17
|
+
print(' ', obj[()])
|
|
18
18
|
else:
|
|
19
19
|
print('---', name)
|
|
20
20
|
|
robotic/ry-test
CHANGED
|
@@ -10,7 +10,8 @@ C.addFile(ry.raiPath('panda/panda.g'), 'b_').setPosition([0,0,.5])
|
|
|
10
10
|
C.addFrame('box1') .setShape(ry.ST.ssBox,[.3, .3, .3, .05]) .setPosition([1.3, 0, 2.]) .setMass(3)
|
|
11
11
|
C.addFrame('box2') .setShape(ry.ST.ssBox,[.3, .3, .3, .05]) .setPosition([.5, .0, 1.8]) .setMass(3)
|
|
12
12
|
|
|
13
|
-
|
|
13
|
+
C.view(False)
|
|
14
|
+
time.sleep(.5)
|
|
14
15
|
|
|
15
16
|
q0 = C.getJointState()
|
|
16
17
|
qT = q0
|
robotic/ry-urdfConvert.py
CHANGED
|
@@ -16,6 +16,7 @@ parser.add_argument('file', type=str, help='urdf file', nargs='?', default='none
|
|
|
16
16
|
|
|
17
17
|
parser.add_argument('-view', help='view mesh', action="store_true", default=True)
|
|
18
18
|
parser.add_argument('-flipDaeYZ', help='view mesh', action="store_true", default=False)
|
|
19
|
+
parser.add_argument('-pruneRigidJoints', help='view mesh', action="store_true")
|
|
19
20
|
parser.add_argument('-recomputeInertias', help='view mesh', action="store_true")
|
|
20
21
|
parser.add_argument('-processMeshes', help='view mesh', action="store_true", default=True)
|
|
21
22
|
parser.add_argument('-meshlab', help='apply meshlab filters', action="store_true", default=False)
|
|
@@ -39,9 +40,9 @@ def main():
|
|
|
39
40
|
|
|
40
41
|
C = ry.URDFLoader(args.file, visualsOnly=True, meshPathRemove='package://').C
|
|
41
42
|
|
|
42
|
-
C.processStructure(
|
|
43
|
+
C.processStructure(args.pruneRigidJoints, True, False, False)
|
|
43
44
|
C.processInertias(args.recomputeInertias)
|
|
44
|
-
C.processStructure(
|
|
45
|
+
C.processStructure(args.pruneRigidJoints, True, False, False)
|
|
45
46
|
|
|
46
47
|
os.system('rm -Rf meshes/')
|
|
47
48
|
C.writeMeshes('meshes/', copyTextures=True)
|
robotic/src/__init__.py
ADDED
|
File without changes
|
|
File without changes
|
|
@@ -0,0 +1,20 @@
|
|
|
1
|
+
<!DOCTYPE FilterScript>
|
|
2
|
+
<FilterScript>
|
|
3
|
+
<filter name="Repair non Manifold Edges by removing faces"/>
|
|
4
|
+
<filter name="Simplification: Quadric Edge Collapse Decimation">
|
|
5
|
+
<Param tooltip="The desired final number of faces." type="RichInt" description="Target number of faces" value="20000" name="TargetFaceNum"/>
|
|
6
|
+
<Param tooltip="If non zero, this parameter specifies the desired final size of the mesh as a percentage of the initial size." type="RichFloat" description="Percentage reduction (0..1)" value="0" name="TargetPerc"/>
|
|
7
|
+
<Param tooltip="Quality threshold for penalizing bad shaped faces.<br>The value is in the range [0..1]
 0 accept any kind of face (no penalties),
 0.5 penalize faces with quality < 0.5, proportionally to their shape
" type="RichFloat" description="Quality threshold" value="0.3" name="QualityThr"/>
|
|
8
|
+
<Param tooltip="The simplification process tries to do not affect mesh boundaries during simplification" type="RichBool" description="Preserve Boundary of the mesh" value="false" name="PreserveBoundary"/>
|
|
9
|
+
<Param tooltip="The importance of the boundary during simplification. Default (1.0) means that the boundary has the same importance of the rest. Values greater than 1.0 raise boundary importance and has the effect of removing less vertices on the border. Admitted range of values (0,+inf). " type="RichFloat" description="Boundary Preserving Weight" value="1" name="BoundaryWeight"/>
|
|
10
|
+
<Param tooltip="Try to avoid face flipping effects and try to preserve the original orientation of the surface" type="RichBool" description="Preserve Normal" value="false" name="PreserveNormal"/>
|
|
11
|
+
<Param tooltip="Avoid all the collapses that should cause a topology change in the mesh (like closing holes, squeezing handles, etc). If checked the genus of the mesh should stay unchanged." type="RichBool" description="Preserve Topology" value="false" name="PreserveTopology"/>
|
|
12
|
+
<Param tooltip="Each collapsed vertex is placed in the position minimizing the quadric error.
 It can fail (creating bad spikes) in case of very flat areas. 
If disabled edges are collapsed onto one of the two original vertices and the final mesh is composed by a subset of the original vertices. " type="RichBool" description="Optimal position of simplified vertices" value="true" name="OptimalPlacement"/>
|
|
13
|
+
<Param tooltip="Add additional simplification constraints that improves the quality of the simplification of the planar portion of the mesh, as a side effect, more triangles will be preserved in flat areas (allowing better shaped triangles)." type="RichBool" description="Planar Simplification" value="false" name="PlanarQuadric"/>
|
|
14
|
+
<Param tooltip="How much we should try to preserve the triangles in the planar regions. If you lower this value planar areas will be simplified more." type="RichFloat" description="Planar Simp. Weight" value="0.001" name="PlanarWeight"/>
|
|
15
|
+
<Param tooltip="Use the Per-Vertex quality as a weighting factor for the simplification. The weight is used as a error amplification value, so a vertex with a high quality value will not be simplified and a portion of the mesh with low quality values will be aggressively simplified." type="RichBool" description="Weighted Simplification" value="false" name="QualityWeight"/>
|
|
16
|
+
<Param tooltip="After the simplification an additional set of steps is performed to clean the mesh (unreferenced vertices, bad faces, etc)" type="RichBool" description="Post-simplification cleaning" value="true" name="AutoClean"/>
|
|
17
|
+
<Param tooltip="The simplification is applied only to the selected set of faces.
 Take care of the target number of faces!" type="RichBool" description="Simplify only selected faces" value="false" name="Selected"/>
|
|
18
|
+
</filter>
|
|
19
|
+
<filter name="Repair non Manifold Edges by removing faces"/>
|
|
20
|
+
</FilterScript>
|
|
@@ -7,8 +7,11 @@ from copy import copy
|
|
|
7
7
|
|
|
8
8
|
class MujocoLoader():
|
|
9
9
|
|
|
10
|
-
def __init__(self, file, visualsOnly=True):
|
|
10
|
+
def __init__(self, file, visualsOnly=True, defaultConType='0', basePos=[0,0,0], baseQuat=[0,0,0,1]):
|
|
11
|
+
ry.params_add({'cd_into_mesh_files': False})
|
|
12
|
+
|
|
11
13
|
self.visualsOnly = visualsOnly
|
|
14
|
+
self.defaultConType = defaultConType
|
|
12
15
|
self.debug_counter = 0
|
|
13
16
|
self.muj2rai_joint_map = {
|
|
14
17
|
'1 0 0': ry.JT.hingeX,
|
|
@@ -32,7 +35,8 @@ class MujocoLoader():
|
|
|
32
35
|
self.C = ry.Config()
|
|
33
36
|
self.base = self.C.addFrame('base')
|
|
34
37
|
self.base.addAttributes({'multibody':True})
|
|
35
|
-
self.base.
|
|
38
|
+
self.base.setPosition(basePos)
|
|
39
|
+
self.base.setQuaternion(baseQuat)
|
|
36
40
|
self.add_node(root, self.base, path, 0)
|
|
37
41
|
|
|
38
42
|
def as_floats(self, input_string):
|
|
@@ -104,7 +108,7 @@ class MujocoLoader():
|
|
|
104
108
|
for i, joint in enumerate(body.findall('./joint')):
|
|
105
109
|
axis = joint.attrib.get('axis', None)
|
|
106
110
|
limits = joint.attrib.get('range', None)
|
|
107
|
-
joint_name = joint.attrib.get('name', f'{body_name}_joint{i*
|
|
111
|
+
joint_name = joint.attrib.get('name', f'{body_name}_joint{i*"_"}')
|
|
108
112
|
f_origin = self.C.addFrame(f'{joint_name}_origin')
|
|
109
113
|
f_origin.setParent(f_body)
|
|
110
114
|
self.setRelativePose(f_origin, joint.attrib)
|
|
@@ -117,7 +121,7 @@ class MujocoLoader():
|
|
|
117
121
|
else:
|
|
118
122
|
vec1 = np.array([0., 0., 1.])
|
|
119
123
|
vec2 = np.array(self.as_floats(axis))
|
|
120
|
-
quat = ry.Quaternion().setDiff(vec1, vec2).
|
|
124
|
+
quat = ry.Quaternion().setDiff(vec1, vec2).asArr()
|
|
121
125
|
f_origin.setRelativeQuaternion(quat)
|
|
122
126
|
axis = ry.JT.hingeZ
|
|
123
127
|
else:
|
|
@@ -145,7 +149,7 @@ class MujocoLoader():
|
|
|
145
149
|
f_body.setParent(f_parent, True)
|
|
146
150
|
|
|
147
151
|
for i, geom in enumerate(body.findall('./geom')):
|
|
148
|
-
isColl =
|
|
152
|
+
isColl = geom.attrib.get('contype', self.defaultConType)!='0' or 'coll' in geom.attrib.get('class','')
|
|
149
153
|
if self.visualsOnly and isColl:
|
|
150
154
|
continue
|
|
151
155
|
|
|
@@ -174,7 +178,7 @@ class MujocoLoader():
|
|
|
174
178
|
l = np.linalg.norm(b-a)
|
|
175
179
|
q = ry.Quaternion().setDiff([0,0,1],(b-a)/l)
|
|
176
180
|
f_shape.setRelativePosition(0.5*(a+b))
|
|
177
|
-
f_shape.setRelativeQuaternion(q.
|
|
181
|
+
f_shape.setRelativeQuaternion(q.asArr())
|
|
178
182
|
f_shape.setShape(ry.ST.capsule, [l, size[0]])
|
|
179
183
|
elif len(size)==2:
|
|
180
184
|
f_shape.setShape(ry.ST.capsule, [2.*size[1], size[0]])
|
|
@@ -185,23 +189,24 @@ class MujocoLoader():
|
|
|
185
189
|
|
|
186
190
|
elif geom.attrib['type']=='box':
|
|
187
191
|
assert len(size)==3
|
|
188
|
-
|
|
192
|
+
size = [2.*f for f in size]
|
|
193
|
+
f_shape.setShape(ry.ST.box, size)
|
|
189
194
|
if geom.attrib.get('material', None):
|
|
190
195
|
texture_path = self.materials[geom.attrib.get('material', None)]
|
|
191
196
|
if len(texture_path.split()) == 4: # Is a color rgba
|
|
192
197
|
f_shape.setColor(self.as_floats(texture_path))
|
|
193
198
|
else:
|
|
194
199
|
print('applying to box:', texture_path)
|
|
195
|
-
#TODO incorperate <texrepeat> tag correctly
|
|
200
|
+
#TODO incorperate <texrepeat> tag correctly
|
|
196
201
|
uv_coords = np.array([
|
|
197
202
|
[0, 0], # vertex 0
|
|
198
|
-
[
|
|
199
|
-
[
|
|
200
|
-
[0, 1], # vertex 3
|
|
201
|
-
[0, 0], # vertex
|
|
202
|
-
[
|
|
203
|
-
[
|
|
204
|
-
[0, 1]
|
|
203
|
+
[size[0], 0], # vertex 1
|
|
204
|
+
[size[0], size[1]], # vertex 2
|
|
205
|
+
[0, size[1]], # vertex 3
|
|
206
|
+
[0, 0], # vertex 0
|
|
207
|
+
[size[0], 0], # vertex 1
|
|
208
|
+
[size[0], size[1]], # vertex 2
|
|
209
|
+
[0, size[1]], # vertex 3
|
|
205
210
|
])
|
|
206
211
|
|
|
207
212
|
f_shape.setTextureFile(texture_path, uv_coords)
|
|
@@ -234,4 +239,4 @@ class MujocoLoader():
|
|
|
234
239
|
if rpy:
|
|
235
240
|
q = ry.Quaternion()
|
|
236
241
|
q.setRollPitchYaw(self.as_floats(rpy))
|
|
237
|
-
f.setRelativeQuaternion(q.
|
|
242
|
+
f.setRelativeQuaternion(q.asArr())
|
|
File without changes
|
robotic/src/yaml_helper.py
CHANGED
|
File without changes
|
robotic/test.py
ADDED
|
@@ -0,0 +1,15 @@
|
|
|
1
|
+
import point_cloud_utils as pcu
|
|
2
|
+
|
|
3
|
+
# v is a [n, 3] shaped NumPy array of vertices
|
|
4
|
+
# f is a [m, 3] shaped integer NumPy array of indices into v
|
|
5
|
+
# n is a [n, 3] shaped NumPy array of vertex normals
|
|
6
|
+
v, f, n = pcu.load_mesh_vfn("bunny.ply")
|
|
7
|
+
|
|
8
|
+
# Generate barycentric coordinates of random samples
|
|
9
|
+
num_samples = 1000
|
|
10
|
+
fid, bc = pcu.sample_mesh_random(v, f, num_samples)
|
|
11
|
+
|
|
12
|
+
# Interpolate the vertex positions and normals using the returned barycentric coordinates
|
|
13
|
+
# to get sample positions and normals
|
|
14
|
+
rand_positions = pcu.interpolate_barycentric_coords(f, fid, bc, v)
|
|
15
|
+
rand_normals = pcu.interpolate_barycentric_coords(f, fid, bc, n)
|
robotic/version.py
CHANGED
|
@@ -1 +1 @@
|
|
|
1
|
-
__version__ = '0.
|
|
1
|
+
__version__ = '0.3.1'
|
|
@@ -12,9 +12,9 @@ def print_attrs(name, obj):
|
|
|
12
12
|
if isinstance(obj, h5py.Dataset):
|
|
13
13
|
print(' ', name, obj.name, obj.shape, obj.dtype, f'{obj.size*obj.dtype.itemsize/1024:.2f}kB')
|
|
14
14
|
if obj.dtype=='int8':
|
|
15
|
-
print(''.join([chr(x) for x in obj[()]]))
|
|
15
|
+
print(' ', ''.join([chr(x) for x in obj[()]]))
|
|
16
16
|
elif obj.size<20:
|
|
17
|
-
print(obj[()])
|
|
17
|
+
print(' ', obj[()])
|
|
18
18
|
else:
|
|
19
19
|
print('---', name)
|
|
20
20
|
|
|
@@ -10,7 +10,8 @@ C.addFile(ry.raiPath('panda/panda.g'), 'b_').setPosition([0,0,.5])
|
|
|
10
10
|
C.addFrame('box1') .setShape(ry.ST.ssBox,[.3, .3, .3, .05]) .setPosition([1.3, 0, 2.]) .setMass(3)
|
|
11
11
|
C.addFrame('box2') .setShape(ry.ST.ssBox,[.3, .3, .3, .05]) .setPosition([.5, .0, 1.8]) .setMass(3)
|
|
12
12
|
|
|
13
|
-
|
|
13
|
+
C.view(False)
|
|
14
|
+
time.sleep(.5)
|
|
14
15
|
|
|
15
16
|
q0 = C.getJointState()
|
|
16
17
|
qT = q0
|
|
@@ -0,0 +1,74 @@
|
|
|
1
|
+
#!python
|
|
2
|
+
|
|
3
|
+
# from config_mujoco import *
|
|
4
|
+
# from config_urdf import *
|
|
5
|
+
# from mesh_helper import *
|
|
6
|
+
from robotic.src.yaml_helper import *
|
|
7
|
+
import robotic as ry
|
|
8
|
+
import argparse
|
|
9
|
+
import glob
|
|
10
|
+
import os
|
|
11
|
+
|
|
12
|
+
parser = argparse.ArgumentParser(
|
|
13
|
+
description='Utility to clean meshes in meshes/')
|
|
14
|
+
|
|
15
|
+
parser.add_argument('file', type=str, help='urdf file', nargs='?', default='none')
|
|
16
|
+
|
|
17
|
+
parser.add_argument('-view', help='view mesh', action="store_true", default=True)
|
|
18
|
+
parser.add_argument('-flipDaeYZ', help='view mesh', action="store_true", default=False)
|
|
19
|
+
parser.add_argument('-pruneRigidJoints', help='view mesh', action="store_true")
|
|
20
|
+
parser.add_argument('-recomputeInertias', help='view mesh', action="store_true")
|
|
21
|
+
parser.add_argument('-processMeshes', help='view mesh', action="store_true", default=True)
|
|
22
|
+
parser.add_argument('-meshlab', help='apply meshlab filters', action="store_true", default=False)
|
|
23
|
+
|
|
24
|
+
def main():
|
|
25
|
+
args = parser.parse_args()
|
|
26
|
+
|
|
27
|
+
if args.file=='none':
|
|
28
|
+
# args.file = '/home/mtoussai/git/rai-robotModels/pr2/pr2.urdf'
|
|
29
|
+
args.file = '/home/mtoussai/git/rai-robotModels/panda/panda_arm_hand.urdf'
|
|
30
|
+
# args.file = '/home/mtoussai/git/rai-robotModels/g1/g1_description/g1_29dof.urdf'
|
|
31
|
+
# args.file = '/home/mtoussai/git/rai-robotModels/ranger/ranger_mini.urdf'
|
|
32
|
+
|
|
33
|
+
print('=== URDF CONVERT ===', args.file)
|
|
34
|
+
|
|
35
|
+
path, file = os.path.split(args.file)
|
|
36
|
+
filebase, _ = os.path.splitext(file)
|
|
37
|
+
|
|
38
|
+
if args.flipDaeYZ:
|
|
39
|
+
ry.params_add({'assimp/daeFlipYZ': False})
|
|
40
|
+
|
|
41
|
+
C = ry.URDFLoader(args.file, visualsOnly=True, meshPathRemove='package://').C
|
|
42
|
+
|
|
43
|
+
C.processStructure(args.pruneRigidJoints, True, False, False)
|
|
44
|
+
C.processInertias(args.recomputeInertias)
|
|
45
|
+
C.processStructure(args.pruneRigidJoints, True, False, False)
|
|
46
|
+
|
|
47
|
+
os.system('rm -Rf meshes/')
|
|
48
|
+
C.writeMeshes('meshes/', copyTextures=True)
|
|
49
|
+
|
|
50
|
+
print('#frames: ', C.getFrameDimension())
|
|
51
|
+
with open(f'{filebase}_conv.g', 'w') as fil:
|
|
52
|
+
#yaml.dump(C.asDict(), file, default_flow_style=False)
|
|
53
|
+
fil.write(C.write())
|
|
54
|
+
|
|
55
|
+
yaml_write_dict(C.asDict(), f'{filebase}_conv.yml')
|
|
56
|
+
|
|
57
|
+
C.view(True)
|
|
58
|
+
# C.animate()
|
|
59
|
+
|
|
60
|
+
if args.processMeshes:
|
|
61
|
+
for file in sorted(glob.glob('meshes/*.h5')):
|
|
62
|
+
|
|
63
|
+
M = ry.MeshHelper(file)
|
|
64
|
+
if M.mesh is None:
|
|
65
|
+
continue
|
|
66
|
+
|
|
67
|
+
M.repair(mergeTolerance=1e-4)
|
|
68
|
+
print(' watertight:', M.mesh.is_watertight)
|
|
69
|
+
print(' oriented:', M.mesh.is_winding_consistent)
|
|
70
|
+
M.report()
|
|
71
|
+
M.export_h5()
|
|
72
|
+
|
|
73
|
+
if __name__ == "__main__":
|
|
74
|
+
main()
|
|
@@ -1,6 +1,6 @@
|
|
|
1
1
|
Metadata-Version: 2.4
|
|
2
2
|
Name: robotic
|
|
3
|
-
Version: 0.
|
|
3
|
+
Version: 0.3.1
|
|
4
4
|
Summary: Robotic Control Interface & Manipulation Planning Library
|
|
5
5
|
Home-page: https://github.com/MarcToussaint/robotic/
|
|
6
6
|
Author: Marc Toussaint
|
|
@@ -46,35 +46,29 @@ Lab](https://argmin.lis.tu-berlin.de/)) operate our robots.
|
|
|
46
46
|
* Tests:
|
|
47
47
|
|
|
48
48
|
ry-info
|
|
49
|
-
|
|
50
49
|
ry-test
|
|
51
50
|
|
|
52
|
-
|
|
53
|
-
|
|
54
|
-
ry-view `python3 -m site --user-site`/robotic/rai-robotModels/scenarios/pandaSingle.g
|
|
55
|
-
|
|
56
|
-
* Run all tutorial notebooks as a test and showcase (takes long):
|
|
51
|
+
* Run all tutorial notebooks as a test and showcase:
|
|
57
52
|
|
|
58
53
|
pip install jupyter nbconvert matplotlib ipympl
|
|
59
54
|
git clone https://github.com/MarcToussaint/rai-tutorials.git
|
|
60
55
|
cd rai-tutorials
|
|
61
56
|
make run -j1
|
|
57
|
+
make run_demos -j1
|
|
62
58
|
|
|
63
59
|
* Tested in latest ubuntu docker (using a venv):
|
|
64
60
|
|
|
65
|
-
|
|
66
|
-
|
|
67
|
-
cd /usr/lib/x86_64-linux-gnu/ && sudo ln -s libglut.so.3.12 libglut.so.3
|
|
61
|
+
apt install --yes liblapack3 xorg freeglut3-dev libglu1-mesa libfreetype6 fonts-ubuntu python3 python3-pip python3-venv
|
|
62
|
+
cd /usr/lib/x86_64-linux-gnu/ && ln -s libglut.so.3.12 libglut.so.3
|
|
68
63
|
cd
|
|
69
|
-
|
|
70
|
-
|
|
71
|
-
source ~/.local/venv/bin/activate
|
|
64
|
+
python3 -m venv ~/venv
|
|
65
|
+
source ~/venv/bin/activate
|
|
72
66
|
pip install robotic numpy
|
|
73
67
|
ry-test
|
|
74
68
|
|
|
75
69
|
## Installation from source with real Franka & realsense support
|
|
76
70
|
|
|
77
|
-
This assumes a standard Ubuntu
|
|
71
|
+
This assumes a standard Ubuntu 24.04 (or 22.04, 20.04) machine.
|
|
78
72
|
|
|
79
73
|
* Install Ubuntu and python packages:
|
|
80
74
|
|
|
@@ -107,7 +101,7 @@ This assumes a standard Ubuntu 22.04 (or 20.04, 18.04) machine.
|
|
|
107
101
|
cd $HOME/git
|
|
108
102
|
git clone --recursive https://github.com/MarcToussaint/robotic.git
|
|
109
103
|
cd robotic
|
|
110
|
-
cp
|
|
104
|
+
cp _make/CMakeLists-ubuntu.txt CMakeLists.txt
|
|
111
105
|
export PY_VERSION=`python3 -c "import sys; print(str(sys.version_info[0])+'.'+str(sys.version_info[1]))"`
|
|
112
106
|
cmake -DPY_VERSION=$PY_VERSION -DUSE_REALSENSE=ON -DUSE_LIBFRANKA=ON . -B build
|
|
113
107
|
make -C build _robotic install
|