placo 0.5.6__tar.gz → 0.6.0__tar.gz

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 placo might be problematic. Click here for more details.

Files changed (170) hide show
  1. {placo-0.5.6 → placo-0.6.0}/CMakeLists.txt +0 -1
  2. placo-0.6.0/PKG-INFO +56 -0
  3. placo-0.6.0/README.md +34 -0
  4. {placo-0.5.6 → placo-0.6.0}/bindings/expose-dynamics.cpp +30 -16
  5. {placo-0.5.6 → placo-0.6.0}/bindings/expose-kinematics.cpp +2 -2
  6. {placo-0.5.6 → placo-0.6.0}/bindings/expose-problem.cpp +5 -1
  7. {placo-0.5.6 → placo-0.6.0}/bindings/expose-robot-wrapper.cpp +4 -1
  8. {placo-0.5.6 → placo-0.6.0}/bindings/expose-tools.cpp +2 -0
  9. {placo-0.5.6 → placo-0.6.0}/placo.pyi +302 -238
  10. {placo-0.5.6 → placo-0.6.0}/pyproject.toml +1 -1
  11. placo-0.6.0/python/placo_utils/view.py +37 -0
  12. {placo-0.5.6 → placo-0.6.0}/python/placo_utils/visualization.py +23 -1
  13. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/avoid_self_collisions_constraint.cpp +3 -11
  14. placo-0.6.0/src/placo/dynamics/contacts.cpp +265 -0
  15. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/contacts.h +41 -24
  16. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/dynamics_solver.cpp +106 -81
  17. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/dynamics_solver.h +46 -41
  18. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/joints_task.cpp +10 -0
  19. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/joints_task.h +7 -0
  20. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/position_task.cpp +5 -6
  21. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/position_task.h +5 -0
  22. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/relative_position_task.h +1 -1
  23. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/task.cpp +1 -1
  24. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/task.h +2 -7
  25. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/walk_tasks.cpp +1 -1
  26. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/joints_task.cpp +10 -0
  27. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/joints_task.h +7 -0
  28. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/kinematics_solver.cpp +0 -17
  29. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/kinematics_solver.h +0 -7
  30. {placo-0.5.6 → placo-0.6.0}/src/placo/model/robot_wrapper.cpp +33 -3
  31. {placo-0.5.6 → placo-0.6.0}/src/placo/model/robot_wrapper.h +15 -0
  32. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/expression.cpp +34 -5
  33. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/expression.h +8 -1
  34. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/problem.cpp +1 -3
  35. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/problem.h +5 -0
  36. {placo-0.5.6 → placo-0.6.0}/src/placo/tools/cubic_spline.cpp +14 -0
  37. {placo-0.5.6 → placo-0.6.0}/src/placo/tools/cubic_spline.h +14 -1
  38. {placo-0.5.6 → placo-0.6.0}/src/placo/tools/cubic_spline_3d.cpp +5 -0
  39. {placo-0.5.6 → placo-0.6.0}/src/placo/tools/cubic_spline_3d.h +7 -0
  40. {placo-0.5.6 → placo-0.6.0}/src/placo/tools/utils.cpp +4 -0
  41. {placo-0.5.6 → placo-0.6.0}/src/placo/tools/utils.h +1 -1
  42. placo-0.5.6/PKG-INFO +0 -25
  43. placo-0.5.6/README.md +0 -3
  44. placo-0.5.6/src/placo/dynamics/contacts.cpp +0 -206
  45. placo-0.5.6/src/placo/dynamics/reaction_ratio_constraint.cpp +0 -30
  46. placo-0.5.6/src/placo/dynamics/reaction_ratio_constraint.h +0 -27
  47. {placo-0.5.6 → placo-0.6.0}/.clang-format +0 -0
  48. {placo-0.5.6 → placo-0.6.0}/.gitattributes +0 -0
  49. {placo-0.5.6 → placo-0.6.0}/.gitignore +0 -0
  50. {placo-0.5.6 → placo-0.6.0}/.readthedocs.yaml +0 -0
  51. {placo-0.5.6 → placo-0.6.0}/Doxyfile +0 -0
  52. {placo-0.5.6 → placo-0.6.0}/LICENSE +0 -0
  53. {placo-0.5.6 → placo-0.6.0}/Makefile +0 -0
  54. {placo-0.5.6 → placo-0.6.0}/bindings/expose-eigen.cpp +0 -0
  55. {placo-0.5.6 → placo-0.6.0}/bindings/expose-footsteps.cpp +0 -0
  56. {placo-0.5.6 → placo-0.6.0}/bindings/expose-parameters.cpp +0 -0
  57. {placo-0.5.6 → placo-0.6.0}/bindings/expose-utils.hpp +0 -0
  58. {placo-0.5.6 → placo-0.6.0}/bindings/expose-walk-pattern-generator.cpp +0 -0
  59. {placo-0.5.6 → placo-0.6.0}/bindings/module.cpp +0 -0
  60. {placo-0.5.6 → placo-0.6.0}/bindings/module.h +0 -0
  61. {placo-0.5.6 → placo-0.6.0}/bindings/registry.cpp +0 -0
  62. {placo-0.5.6 → placo-0.6.0}/bindings/registry.h +0 -0
  63. {placo-0.5.6 → placo-0.6.0}/doxygen_parse.py +0 -0
  64. {placo-0.5.6 → placo-0.6.0}/python/.vscode/settings.json +0 -0
  65. {placo-0.5.6 → placo-0.6.0}/python/Makefile +0 -0
  66. {placo-0.5.6 → placo-0.6.0}/python/placo_utils/__init__.py +0 -0
  67. {placo-0.5.6 → placo-0.6.0}/python/placo_utils/tf.py +0 -0
  68. {placo-0.5.6 → placo-0.6.0}/python/run_tests.sh +0 -0
  69. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/avoid_self_collisions_constraint.h +0 -0
  70. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/com_task.cpp +0 -0
  71. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/com_task.h +0 -0
  72. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/constraint.cpp +0 -0
  73. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/constraint.h +0 -0
  74. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/frame_task.cpp +0 -0
  75. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/frame_task.h +0 -0
  76. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/gear_task.cpp +0 -0
  77. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/gear_task.h +0 -0
  78. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/orientation_task.cpp +0 -0
  79. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/orientation_task.h +0 -0
  80. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/relative_frame_task.cpp +0 -0
  81. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/relative_frame_task.h +0 -0
  82. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/relative_orientation_task.cpp +0 -0
  83. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/relative_orientation_task.h +0 -0
  84. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/relative_position_task.cpp +0 -0
  85. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/torque_task.cpp +0 -0
  86. {placo-0.5.6 → placo-0.6.0}/src/placo/dynamics/torque_task.h +0 -0
  87. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/foot_trajectory.cpp +0 -0
  88. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/foot_trajectory.h +0 -0
  89. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/footsteps_planner.cpp +0 -0
  90. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/footsteps_planner.h +0 -0
  91. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/footsteps_planner_naive.cpp +0 -0
  92. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/footsteps_planner_naive.h +0 -0
  93. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/footsteps_planner_repetitive.cpp +0 -0
  94. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/footsteps_planner_repetitive.h +0 -0
  95. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/humanoid_parameters.cpp +0 -0
  96. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/humanoid_parameters.h +0 -0
  97. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/humanoid_robot.cpp +0 -0
  98. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/humanoid_robot.h +0 -0
  99. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/kick.cpp +0 -0
  100. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/kick.h +0 -0
  101. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/lipm.cpp +0 -0
  102. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/lipm.h +0 -0
  103. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/swing_foot.cpp +0 -0
  104. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/swing_foot.h +0 -0
  105. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/swing_foot_cubic.cpp +0 -0
  106. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/swing_foot_cubic.h +0 -0
  107. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/swing_foot_quintic.cpp +0 -0
  108. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/swing_foot_quintic.h +0 -0
  109. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/walk_pattern_generator.cpp +0 -0
  110. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/walk_pattern_generator.h +0 -0
  111. {placo-0.5.6 → placo-0.6.0}/src/placo/humanoid/walk_tasks.h +0 -0
  112. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/avoid_self_collisions_constraint.cpp +0 -0
  113. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/avoid_self_collisions_constraint.h +0 -0
  114. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/axis_align_task.cpp +0 -0
  115. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/axis_align_task.h +0 -0
  116. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/centroidal_momentum_task.cpp +0 -0
  117. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/centroidal_momentum_task.h +0 -0
  118. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/com_polygon_constraint.cpp +0 -0
  119. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/com_polygon_constraint.h +0 -0
  120. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/com_task.cpp +0 -0
  121. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/com_task.h +0 -0
  122. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/cone_constraint.cpp +0 -0
  123. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/cone_constraint.h +0 -0
  124. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/constraint.cpp +0 -0
  125. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/constraint.h +0 -0
  126. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/distance_task.cpp +0 -0
  127. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/distance_task.h +0 -0
  128. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/frame_task.cpp +0 -0
  129. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/frame_task.h +0 -0
  130. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/gear_task.cpp +0 -0
  131. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/gear_task.h +0 -0
  132. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/kinetic_energy_regularization_task.cpp +0 -0
  133. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/kinetic_energy_regularization_task.h +0 -0
  134. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/manipulability_task.cpp +0 -0
  135. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/manipulability_task.h +0 -0
  136. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/orientation_task.cpp +0 -0
  137. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/orientation_task.h +0 -0
  138. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/position_task.cpp +0 -0
  139. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/position_task.h +0 -0
  140. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/regularization_task.cpp +0 -0
  141. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/regularization_task.h +0 -0
  142. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/relative_frame_task.cpp +0 -0
  143. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/relative_frame_task.h +0 -0
  144. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/relative_orientation_task.cpp +0 -0
  145. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/relative_orientation_task.h +0 -0
  146. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/relative_position_task.cpp +0 -0
  147. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/relative_position_task.h +0 -0
  148. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/task.cpp +0 -0
  149. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/task.h +0 -0
  150. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/wheel_task.cpp +0 -0
  151. {placo-0.5.6 → placo-0.6.0}/src/placo/kinematics/wheel_task.h +0 -0
  152. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/constraint.cpp +0 -0
  153. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/constraint.h +0 -0
  154. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/integrator.cpp +0 -0
  155. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/integrator.h +0 -0
  156. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/polygon_constraint.cpp +0 -0
  157. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/polygon_constraint.h +0 -0
  158. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/qp_error.cpp +0 -0
  159. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/qp_error.h +0 -0
  160. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/sparsity.cpp +0 -0
  161. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/sparsity.h +0 -0
  162. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/variable.cpp +0 -0
  163. {placo-0.5.6 → placo-0.6.0}/src/placo/problem/variable.h +0 -0
  164. {placo-0.5.6 → placo-0.6.0}/src/placo/tools/axises_mask.cpp +0 -0
  165. {placo-0.5.6 → placo-0.6.0}/src/placo/tools/axises_mask.h +0 -0
  166. {placo-0.5.6 → placo-0.6.0}/src/placo/tools/prioritized.cpp +0 -0
  167. {placo-0.5.6 → placo-0.6.0}/src/placo/tools/prioritized.h +0 -0
  168. {placo-0.5.6 → placo-0.6.0}/stubs.py +0 -0
  169. {placo-0.5.6 → placo-0.6.0}/tweak_sdist.sh +0 -0
  170. {placo-0.5.6 → placo-0.6.0}/wks.yml +0 -0
@@ -102,7 +102,6 @@ add_library(libplaco SHARED
102
102
  src/placo/dynamics/dynamics_solver.cpp
103
103
  src/placo/dynamics/constraint.cpp
104
104
  src/placo/dynamics/avoid_self_collisions_constraint.cpp
105
- src/placo/dynamics/reaction_ratio_constraint.cpp
106
105
 
107
106
  ${PROTO_SRCS}
108
107
  ${PROTO_HDRS}
placo-0.6.0/PKG-INFO ADDED
@@ -0,0 +1,56 @@
1
+ Metadata-Version: 2.1
2
+ Name: placo
3
+ Version: 0.6.0
4
+ Summary: PlaCo: Rhoban Planning and Control
5
+ Requires-Python: >= 3.8
6
+ License-Expression: MIT
7
+ Author-email: Rhoban team <team@rhoban.com>
8
+ Project-URL: Changelog, https://github.com/rhoban/placo/blob/main/CHANGELOG.md
9
+ Home-page: https://placo.readthedocs.io/en/latest/
10
+ Project-URL: Repository, https://github.com/rhoban/placo.git
11
+ Requires-Dist: cmeel
12
+ Requires-Dist: eiquadprog >= 1.2.6, < 2
13
+ Requires-Dist: pin >= 2.6.18, < 3
14
+ Requires-Dist: rhoban-cmeel-jsoncpp
15
+ Requires-Dist: meshcat
16
+ Requires-Dist: numpy<2
17
+ Requires-Dist: ischedule
18
+ Provides-Extra: build
19
+ Requires-Dist: pin[build] >= 2.6.18, < 3 ; extra == "build"
20
+ Requires-Dist: cmeel-urdfdom[build] ; extra == "build"
21
+ Description-Content-Type: text/markdown
22
+
23
+ # PlaCo
24
+
25
+ PlaCo is Rhoban's planning and control library.
26
+ Its main features are:
27
+
28
+ * Task-space Inverse Kinematics with constraints,
29
+ * Task-space Inverse Dynamics with constraints,
30
+ * QP problem formulation,
31
+ * Built on the top of [pinocchio](https://github.com/stack-of-tasks/pinocchio)
32
+ * Written in C++ with Python bindings
33
+
34
+ [![Megabot demo](https://github.com/Rhoban/placo-examples/blob/master/kinematics/videos/quadruped_targets.gif?raw=true)](https://github.com/Rhoban/placo-examples/blob/master/kinematics/videos/quadruped_targets.mp4?raw=true)
35
+
36
+ *Inverse Kinematics Example: a quadruped robot hitting targets with a leg while keeping its three legs on the ground*
37
+
38
+ [source code (quadruped_targets.py)](https://github.com/Rhoban/placo-examples/blob/master/kinematics/quadruped_targets.py) / [more kinematics examples](https://placo.readthedocs.io/en/latest/kinematics/examples_gallery.html)
39
+
40
+ [![Megabot demo](https://github.com/Rhoban/placo-examples/blob/master/dynamics/videos/megabot.gif?raw=true)](https://github.com/Rhoban/placo-examples/blob/master/dynamics/videos/megabot.mp4?raw=true)
41
+
42
+ *Inverse Dynamics Example: a quadruped with many loop closure joints*
43
+
44
+ [source code (megabot.py)](https://github.com/Rhoban/placo-examples/blob/master/dynamics/megabot.py) / [more dynamics examples](https://placo.readthedocs.io/en/latest/dynamics/examples_gallery.html)
45
+
46
+ ## Installing
47
+
48
+ PlaCo is available from [pip](https://placo.readthedocs.io/en/latest/basics/installation_pip.html),
49
+ or can be [built from sources](https://placo.readthedocs.io/en/latest/basics/installation_source.html).
50
+
51
+ ## Documentation
52
+
53
+ Here is the [official documentation](https://placo.readthedocs.io/en/latest/)
54
+
55
+ You can also find many examples in the [placo-examples](https://github.com/rhoban/placo-examples)
56
+ repository.
placo-0.6.0/README.md ADDED
@@ -0,0 +1,34 @@
1
+ # PlaCo
2
+
3
+ PlaCo is Rhoban's planning and control library.
4
+ Its main features are:
5
+
6
+ * Task-space Inverse Kinematics with constraints,
7
+ * Task-space Inverse Dynamics with constraints,
8
+ * QP problem formulation,
9
+ * Built on the top of [pinocchio](https://github.com/stack-of-tasks/pinocchio)
10
+ * Written in C++ with Python bindings
11
+
12
+ [![Megabot demo](https://github.com/Rhoban/placo-examples/blob/master/kinematics/videos/quadruped_targets.gif?raw=true)](https://github.com/Rhoban/placo-examples/blob/master/kinematics/videos/quadruped_targets.mp4?raw=true)
13
+
14
+ *Inverse Kinematics Example: a quadruped robot hitting targets with a leg while keeping its three legs on the ground*
15
+
16
+ [source code (quadruped_targets.py)](https://github.com/Rhoban/placo-examples/blob/master/kinematics/quadruped_targets.py) / [more kinematics examples](https://placo.readthedocs.io/en/latest/kinematics/examples_gallery.html)
17
+
18
+ [![Megabot demo](https://github.com/Rhoban/placo-examples/blob/master/dynamics/videos/megabot.gif?raw=true)](https://github.com/Rhoban/placo-examples/blob/master/dynamics/videos/megabot.mp4?raw=true)
19
+
20
+ *Inverse Dynamics Example: a quadruped with many loop closure joints*
21
+
22
+ [source code (megabot.py)](https://github.com/Rhoban/placo-examples/blob/master/dynamics/megabot.py) / [more dynamics examples](https://placo.readthedocs.io/en/latest/dynamics/examples_gallery.html)
23
+
24
+ ## Installing
25
+
26
+ PlaCo is available from [pip](https://placo.readthedocs.io/en/latest/basics/installation_pip.html),
27
+ or can be [built from sources](https://placo.readthedocs.io/en/latest/basics/installation_source.html).
28
+
29
+ ## Documentation
30
+
31
+ Here is the [official documentation](https://placo.readthedocs.io/en/latest/)
32
+
33
+ You can also find many examples in the [placo-examples](https://github.com/rhoban/placo-examples)
34
+ repository.
@@ -13,8 +13,10 @@ using namespace placo::dynamics;
13
13
  using namespace placo::model;
14
14
 
15
15
  // Overloads
16
+ BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(frame_configure_overloads, configure, 2, 4);
16
17
  BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(solve_overloads, solve, 0, 1);
17
18
  BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(set_torque_overloads, set_torque, 2, 4);
19
+ BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(set_joint_overloads, set_joint, 2, 4);
18
20
 
19
21
  void exposeDynamics()
20
22
  {
@@ -42,6 +44,7 @@ void exposeDynamics()
42
44
  .def_readwrite("active", &Contact::active)
43
45
  .def_readwrite("mu", &Contact::mu)
44
46
  .def_readwrite("weight_forces", &Contact::weight_forces)
47
+ .def_readwrite("weight_tangentials", &Contact::weight_tangentials)
45
48
  .def_readwrite("weight_moments", &Contact::weight_moments)
46
49
  .add_property(
47
50
  "wrench", +[](Contact& contact) { return contact.wrench; });
@@ -50,7 +53,10 @@ void exposeDynamics()
50
53
  .def(
51
54
  "position_task", +[](PointContact& contact) -> PositionTask& { return *contact.position_task; },
52
55
  return_internal_reference<>())
53
- .def_readwrite("unilateral", &PointContact::unilateral);
56
+ .def_readwrite("unilateral", &PointContact::unilateral)
57
+ .add_property(
58
+ "R_world_surface", +[](PointContact& contact) { return contact.R_world_surface; },
59
+ +[](PointContact& contact, Eigen::Matrix3d R) { contact.R_world_surface = R; });
54
60
 
55
61
  class__<Contact6D, bases<Contact>>("Contact6D", init<FrameTask&, bool>())
56
62
  .def(
@@ -64,9 +70,19 @@ void exposeDynamics()
64
70
  .def_readwrite("width", &Contact6D::width)
65
71
  .def("zmp", &Contact6D::zmp);
66
72
 
67
- class__<RelativePointContact, bases<Contact>>("RelativePointContact", init<RelativePositionTask&>());
68
-
69
- class__<Relative6DContact, bases<Contact>>("Relative6DContact", init<RelativeFrameTask&>());
73
+ class__<LineContact, bases<Contact>>("LineContact", init<FrameTask&, bool>())
74
+ .def(
75
+ "position_task", +[](LineContact& contact) -> PositionTask& { return *contact.position_task; },
76
+ return_internal_reference<>())
77
+ .def(
78
+ "orientation_task", +[](LineContact& contact) -> OrientationTask& { return *contact.orientation_task; },
79
+ return_internal_reference<>())
80
+ .def_readwrite("unilateral", &LineContact::unilateral)
81
+ .def_readwrite("length", &LineContact::length)
82
+ .def("zmp", &LineContact::zmp)
83
+ .add_property(
84
+ "R_world_surface", +[](PointContact& contact) { return contact.R_world_surface; },
85
+ +[](PointContact& contact, Eigen::Matrix3d R) { contact.R_world_surface = R; });
70
86
 
71
87
  class__<ExternalWrenchContact, bases<Contact>>("ExternalWrenchContact", init<RobotWrapper::FrameIndex>())
72
88
  .add_property("frame_index", &ExternalWrenchContact::frame_index)
@@ -81,24 +97,23 @@ void exposeDynamics()
81
97
  .add_property("problem", &DynamicsSolver::problem)
82
98
  .def_readwrite("damping", &DynamicsSolver::damping)
83
99
  .def_readwrite("dt", &DynamicsSolver::dt)
84
- .def_readwrite("qdd_safe", &DynamicsSolver::qdd_safe)
100
+ .def("set_qdd_safe", &DynamicsSolver::set_qdd_safe)
101
+ .def("set_torque_limit", &DynamicsSolver::set_torque_limit)
85
102
  .def_readwrite("gravity_only", &DynamicsSolver::gravity_only)
86
103
  .def_readwrite("torque_cost", &DynamicsSolver::torque_cost)
87
104
  .def("mask_fbase", &DynamicsSolver::mask_fbase)
88
105
  .def("add_point_contact", &DynamicsSolver::add_point_contact, return_internal_reference<>())
89
106
  .def("add_unilateral_point_contact", &DynamicsSolver::add_unilateral_point_contact, return_internal_reference<>())
90
- .def("add_relative_point_contact", &DynamicsSolver::add_relative_point_contact, return_internal_reference<>())
91
- .def("add_relative_fixed_contact", &DynamicsSolver::add_relative_fixed_contact, return_internal_reference<>())
92
107
  .def("add_planar_contact", &DynamicsSolver::add_planar_contact, return_internal_reference<>())
93
108
  .def("add_fixed_contact", &DynamicsSolver::add_fixed_contact, return_internal_reference<>())
94
- .def<ExternalWrenchContact& (DynamicsSolver::*)(std::string)>(
109
+ .def("add_line_contact", &DynamicsSolver::add_line_contact, return_internal_reference<>())
110
+ .def("add_unilateral_line_contact", &DynamicsSolver::add_unilateral_line_contact, return_internal_reference<>())
111
+ .def<ExternalWrenchContact& (DynamicsSolver::*)(std::string, std::string)>(
95
112
  "add_external_wrench_contact", &DynamicsSolver::add_external_wrench_contact, return_internal_reference<>())
96
113
  .def("add_puppet_contact", &DynamicsSolver::add_puppet_contact, return_internal_reference<>())
97
114
  .def("add_task_contact", &DynamicsSolver::add_task_contact, return_internal_reference<>())
98
115
  .def("add_avoid_self_collisions_constraint", &DynamicsSolver::add_avoid_self_collisions_constraint,
99
116
  return_internal_reference<>())
100
- .def("add_reaction_ratio_constraint", &DynamicsSolver::add_reaction_ratio_constraint,
101
- return_internal_reference<>())
102
117
  .def("enable_velocity_limits", &DynamicsSolver::enable_velocity_limits)
103
118
  .def("enable_velocity_vs_torque_limits", &DynamicsSolver::enable_velocity_vs_torque_limits)
104
119
  .def("enable_joint_limits", &DynamicsSolver::enable_joint_limits)
@@ -152,7 +167,6 @@ void exposeDynamics()
152
167
  "b", +[](const Task& task) { return task.b; })
153
168
  .add_property("kp", &Task::kp, &Task::kp)
154
169
  .add_property("kd", &Task::kd, &Task::kd)
155
- .add_property("critically_damped", &Task::critically_damped, &Task::critically_damped)
156
170
  .add_property("error", &Task::error)
157
171
  .add_property("derror", &Task::derror);
158
172
 
@@ -162,6 +176,8 @@ void exposeDynamics()
162
176
  "target_world", +[](const PositionTask& task) { return task.target_world; }, &PositionTask::target_world)
163
177
  .add_property(
164
178
  "dtarget_world", +[](const PositionTask& task) { return task.dtarget_world; }, &PositionTask::dtarget_world)
179
+ .add_property(
180
+ "ddtarget_world", +[](const PositionTask& task) { return task.dtarget_world; }, &PositionTask::ddtarget_world)
165
181
  .add_property("mask", &PositionTask::mask, &PositionTask::mask);
166
182
 
167
183
  class__<CoMTask, bases<Task>>("DynamicsCoMTask", init<Eigen::Vector3d>())
@@ -214,7 +230,7 @@ void exposeDynamics()
214
230
  .def(
215
231
  "orientation", +[](const FrameTask& task) -> OrientationTask& { return *task.orientation; },
216
232
  return_internal_reference<>())
217
- .def("configure", &FrameTask::configure)
233
+ .def("configure", &FrameTask::configure, frame_configure_overloads())
218
234
  .add_property("T_world_frame", &FrameTask::get_T_world_frame, &FrameTask::set_T_world_frame);
219
235
 
220
236
  class__<RelativeFrameTask>("DynamicsRelativeFrameTask", init<>())
@@ -229,7 +245,8 @@ void exposeDynamics()
229
245
  .add_property("T_a_b", &RelativeFrameTask::get_T_a_b, &RelativeFrameTask::set_T_a_b);
230
246
 
231
247
  class__<JointsTask, bases<Task>>("DynamicsJointsTask", init<>())
232
- .def("set_joint", &JointsTask::set_joint)
248
+ .def("set_joint", &JointsTask::set_joint, set_joint_overloads())
249
+ .def("get_joint", &JointsTask::get_joint)
233
250
  .def(
234
251
  "set_joints", +[](JointsTask& task,
235
252
  boost::python::dict& py_dict) { update_map<std::string, double>(task.joints, py_dict); })
@@ -251,7 +268,4 @@ void exposeDynamics()
251
268
  class__<AvoidSelfCollisionsConstraint, bases<Constraint>>("AvoidSelfCollisionsDynamicsConstraint", init<>())
252
269
  .def_readwrite("self_collisions_margin", &AvoidSelfCollisionsConstraint::self_collisions_margin)
253
270
  .def_readwrite("self_collisions_trigger", &AvoidSelfCollisionsConstraint::self_collisions_trigger);
254
-
255
- class__<ReactionRatioConstraint, bases<Constraint>>("DynamicsReactionRatioConstraint", init<Contact&, double>())
256
- .def_readwrite("reaction_ratio", &ReactionRatioConstraint::reaction_ratio);
257
271
  }
@@ -114,8 +114,7 @@ void exposeKinematics()
114
114
  .def<void (KinematicsSolver::*)(Task&)>("remove_task", &KinematicsSolver::remove_task)
115
115
  .def<void (KinematicsSolver::*)(FrameTask&)>("remove_task", &KinematicsSolver::remove_task)
116
116
  .def("remove_constraint", &KinematicsSolver::remove_constraint)
117
- .def("solve", &KinematicsSolver::solve)
118
- .def("add_q_noise", &KinematicsSolver::add_q_noise);
117
+ .def("solve", &KinematicsSolver::solve);
119
118
 
120
119
  class__<Task, bases<tools::Prioritized>, boost::noncopyable>("Task", no_init)
121
120
  .add_property(
@@ -193,6 +192,7 @@ void exposeKinematics()
193
192
 
194
193
  class__<JointsTask, bases<Task>>("JointsTask", init<>())
195
194
  .def("set_joint", &JointsTask::set_joint)
195
+ .def("get_joint", &JointsTask::get_joint)
196
196
  .def(
197
197
  "set_joints", +[](JointsTask& task, boost::python::dict& py_dict) {
198
198
  update_map<std::string, double>(task.joints, py_dict);
@@ -109,6 +109,7 @@ void exposeProblem()
109
109
  .def("clear_variables", &Problem::clear_variables)
110
110
  .def("clear_constraints", &Problem::clear_constraints)
111
111
  .def("dump_status", &Problem::dump_status)
112
+ .add_property("x", &Problem::x)
112
113
  .add_property("n_variables", &Problem::n_variables, &Problem::n_variables)
113
114
  .add_property("n_inequalities", &Problem::n_inequalities, &Problem::n_inequalities)
114
115
  .add_property("n_equalities", &Problem::n_equalities, &Problem::n_equalities)
@@ -117,6 +118,7 @@ void exposeProblem()
117
118
  .add_property("slack_variables", &Problem::slack_variables, &Problem::slack_variables)
118
119
  .add_property("use_sparsity", &Problem::use_sparsity, &Problem::use_sparsity)
119
120
  .add_property("rewrite_equalities", &Problem::rewrite_equalities, &Problem::rewrite_equalities)
121
+ .add_property("regularization", &Problem::regularization, &Problem::regularization)
120
122
  .add_property(
121
123
  "slacks", +[](const Problem& problem) { return problem.slacks; });
122
124
 
@@ -133,6 +135,7 @@ void exposeProblem()
133
135
  "b", +[](Expression& e) { return e.b; })
134
136
  .def("__len__", &Expression::rows)
135
137
  .def("is_scalar", &Expression::is_scalar)
138
+ .def("is_constant", &Expression::is_constant)
136
139
  .def("slice", &Expression::slice)
137
140
  .def("rows", &Expression::rows)
138
141
  .def("cols", &Expression::cols)
@@ -149,6 +152,7 @@ void exposeProblem()
149
152
  .def(self - self)
150
153
  .def(self * float())
151
154
  .def(float() * self)
155
+ .def(self * self)
152
156
  .def(self + other<Eigen::VectorXd>())
153
157
  .def(other<Eigen::VectorXd>() + self)
154
158
  .def(self - other<Eigen::VectorXd>())
@@ -158,7 +162,7 @@ void exposeProblem()
158
162
  .def(self - float())
159
163
  .def(float() - self)
160
164
  .def(other<Eigen::MatrixXd>() * self)
161
- .def("multiply", &Expression::multiply)
165
+ .def("left_multiply", &Expression::left_multiply)
162
166
  // Compare to build constraints
163
167
  .def(self >= self)
164
168
  .def(self <= self)
@@ -61,6 +61,8 @@ void exposeRobotType(class_<RobotType, W1>& type)
61
61
  .def("com_jacobian_time_variation", &RobotType::com_jacobian_time_variation)
62
62
  .def("generalized_gravity", &RobotType::generalized_gravity)
63
63
  .def("non_linear_effects", &RobotType::non_linear_effects)
64
+ .def("set_rotor_inertia", &RobotType::set_rotor_inertia)
65
+ .def("set_gear_ratio", &RobotType::set_gear_ratio)
64
66
  .def("mass_matrix", &RobotType::mass_matrix)
65
67
  .def("set_gravity", &RobotType::set_gravity)
66
68
  .def("total_mass", &RobotType::total_mass)
@@ -125,7 +127,8 @@ void exposeRobotType(class_<RobotType, W1>& type)
125
127
  "joint_jacobian", +[](RobotType& robot, const std::string& joint,
126
128
  const std::string& reference) { return robot.joint_jacobian(joint, reference); })
127
129
  .def(
128
- "make_solver", +[](RobotType& robot) { return placo::kinematics::KinematicsSolver(robot); });
130
+ "make_solver", +[](RobotType& robot) { return placo::kinematics::KinematicsSolver(robot); })
131
+ .def("add_q_noise", &RobotType::add_q_noise);
129
132
  }
130
133
 
131
134
  void exposeRobotWrapper()
@@ -63,6 +63,7 @@ void exposeTools()
63
63
  class__<CubicSpline>("CubicSpline", init<optional<bool>>())
64
64
  .def("pos", &CubicSpline::pos)
65
65
  .def("vel", &CubicSpline::vel)
66
+ .def("acc", &CubicSpline::acc)
66
67
  .def("add_point", &CubicSpline::add_point)
67
68
  .def("clear", &CubicSpline::clear)
68
69
  .def("duration", &CubicSpline::duration);
@@ -70,6 +71,7 @@ void exposeTools()
70
71
  class__<CubicSpline3D>("CubicSpline3D")
71
72
  .def("pos", &CubicSpline3D::pos)
72
73
  .def("vel", &CubicSpline3D::vel)
74
+ .def("acc", &CubicSpline3D::acc)
73
75
  .def("add_point", &CubicSpline3D::add_point)
74
76
  .def("clear", &CubicSpline3D::clear)
75
77
  .def("duration", &CubicSpline3D::duration);