placo 0.6.4__tar.gz → 0.6.5__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.
- placo-0.6.5/PKG-INFO +61 -0
- placo-0.6.5/README.md +39 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/expose-footsteps.cpp +2 -5
- {placo-0.6.4 → placo-0.6.5}/bindings/expose-tools.cpp +1 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/expose-walk-pattern-generator.cpp +2 -1
- {placo-0.6.4 → placo-0.6.5}/placo.pyi +41 -16
- {placo-0.6.4 → placo-0.6.5}/pyproject.toml +1 -1
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/footsteps_planner.cpp +19 -16
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/footsteps_planner.h +3 -5
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/footsteps_planner_naive.cpp +2 -2
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/walk_pattern_generator.cpp +3 -3
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/walk_pattern_generator.h +1 -1
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/segment.cpp +17 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/segment.h +8 -0
- {placo-0.6.4 → placo-0.6.5}/stubs.py +12 -7
- placo-0.6.4/PKG-INFO +0 -56
- placo-0.6.4/README.md +0 -34
- {placo-0.6.4 → placo-0.6.5}/.clang-format +0 -0
- {placo-0.6.4 → placo-0.6.5}/.gitattributes +0 -0
- {placo-0.6.4 → placo-0.6.5}/.gitignore +0 -0
- {placo-0.6.4 → placo-0.6.5}/.readthedocs.yaml +0 -0
- {placo-0.6.4 → placo-0.6.5}/CMakeLists.txt +0 -0
- {placo-0.6.4 → placo-0.6.5}/Doxyfile +0 -0
- {placo-0.6.4 → placo-0.6.5}/LICENSE +0 -0
- {placo-0.6.4 → placo-0.6.5}/Makefile +0 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/expose-dynamics.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/expose-eigen.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/expose-kinematics.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/expose-parameters.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/expose-problem.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/expose-robot-wrapper.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/expose-utils.hpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/module.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/module.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/registry.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/bindings/registry.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/doxygen_parse.py +0 -0
- {placo-0.6.4 → placo-0.6.5}/python/.vscode/settings.json +0 -0
- {placo-0.6.4 → placo-0.6.5}/python/Makefile +0 -0
- {placo-0.6.4 → placo-0.6.5}/python/placo_utils/__init__.py +0 -0
- {placo-0.6.4 → placo-0.6.5}/python/placo_utils/tf.py +0 -0
- {placo-0.6.4 → placo-0.6.5}/python/placo_utils/view.py +0 -0
- {placo-0.6.4 → placo-0.6.5}/python/placo_utils/visualization.py +0 -0
- {placo-0.6.4 → placo-0.6.5}/python/run_tests.sh +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/avoid_self_collisions_constraint.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/avoid_self_collisions_constraint.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/com_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/com_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/constraint.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/constraint.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/contacts.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/contacts.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/dynamics_solver.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/dynamics_solver.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/frame_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/frame_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/gear_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/gear_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/joints_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/joints_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/orientation_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/orientation_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/position_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/position_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/relative_frame_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/relative_frame_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/relative_orientation_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/relative_orientation_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/relative_position_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/relative_position_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/torque_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/dynamics/torque_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/foot_trajectory.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/foot_trajectory.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/footsteps_planner_naive.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/footsteps_planner_repetitive.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/footsteps_planner_repetitive.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/humanoid_parameters.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/humanoid_parameters.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/humanoid_robot.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/humanoid_robot.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/kick.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/kick.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/lipm.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/lipm.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/swing_foot.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/swing_foot.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/swing_foot_cubic.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/swing_foot_cubic.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/swing_foot_quintic.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/swing_foot_quintic.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/walk_tasks.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/humanoid/walk_tasks.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/avoid_self_collisions_constraint.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/avoid_self_collisions_constraint.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/axis_align_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/axis_align_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/centroidal_momentum_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/centroidal_momentum_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/com_polygon_constraint.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/com_polygon_constraint.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/com_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/com_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/cone_constraint.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/cone_constraint.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/constraint.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/constraint.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/distance_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/distance_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/frame_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/frame_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/gear_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/gear_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/joint_space_half_spaces_constraint.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/joint_space_half_spaces_constraint.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/joints_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/joints_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/kinematics_solver.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/kinematics_solver.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/kinetic_energy_regularization_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/kinetic_energy_regularization_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/manipulability_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/manipulability_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/orientation_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/orientation_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/position_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/position_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/regularization_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/regularization_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/relative_frame_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/relative_frame_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/relative_orientation_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/relative_orientation_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/relative_position_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/relative_position_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/wheel_task.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/kinematics/wheel_task.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/model/robot_wrapper.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/model/robot_wrapper.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/constraint.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/constraint.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/expression.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/expression.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/integrator.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/integrator.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/polygon_constraint.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/polygon_constraint.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/problem.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/problem.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/problem_polynom.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/problem_polynom.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/qp_error.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/qp_error.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/sparsity.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/sparsity.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/variable.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/problem/variable.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/axises_mask.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/axises_mask.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/cubic_spline.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/cubic_spline.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/cubic_spline_3d.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/cubic_spline_3d.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/directions.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/directions.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/polynom.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/polynom.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/prioritized.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/prioritized.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/utils.cpp +0 -0
- {placo-0.6.4 → placo-0.6.5}/src/placo/tools/utils.h +0 -0
- {placo-0.6.4 → placo-0.6.5}/tweak_sdist.sh +0 -0
- {placo-0.6.4 → placo-0.6.5}/wks.yml +0 -0
placo-0.6.5/PKG-INFO
ADDED
|
@@ -0,0 +1,61 @@
|
|
|
1
|
+
Metadata-Version: 2.4
|
|
2
|
+
Name: placo
|
|
3
|
+
Version: 0.6.5
|
|
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
|
+
<img width="400" src="https://placo.readthedocs.io/en/latest/_static/placo.png" />
|
|
24
|
+
|
|
25
|
+
## Planning & Control
|
|
26
|
+
|
|
27
|
+
PlaCo is Rhoban's planning and control library. It is built on the top of [pinocchio](https://github.com/stack-of-tasks/pinocchio), [eiquadprog](https://github.com/stack-of-tasks/eiquadprog) QP solver, and fully written in C++ with Python bindings, allowing fast prototyping with good runtime performances. It features task-space inverse kinematics and dynamics (see below) high-level API for whole-body control tasks.
|
|
28
|
+
|
|
29
|
+
### Task-Space Inverse Kinematics
|
|
30
|
+
|
|
31
|
+
[](https://github.com/Rhoban/placo-examples/blob/master/kinematics/videos/quadruped_targets.mp4?raw=true)
|
|
32
|
+
|
|
33
|
+
High-level API to specify tasks for constrained inverse kinematics (IK).
|
|
34
|
+
|
|
35
|
+
- [See documentation](https://placo.readthedocs.io/en/latest/kinematics/getting_started.html)
|
|
36
|
+
- [Examples](https://placo.readthedocs.io/en/latest/kinematics/examples_gallery.html)
|
|
37
|
+
|
|
38
|
+
### Task-Space Inverse Dynamics
|
|
39
|
+
|
|
40
|
+
[](https://github.com/Rhoban/placo-examples/blob/master/dynamics/videos/megabot.mp4?raw=true)
|
|
41
|
+
|
|
42
|
+
High-level API to specify tasks for constrained inverse dynamics (ID).
|
|
43
|
+
|
|
44
|
+
- [See documentation](https://placo.readthedocs.io/en/latest/dynamics/getting_started.html)
|
|
45
|
+
- [Examples](https://placo.readthedocs.io/en/latest/dynamics/examples_gallery.html)
|
|
46
|
+
|
|
47
|
+
|
|
48
|
+
## Installing
|
|
49
|
+
|
|
50
|
+
PlaCo can be installed from ``pip``
|
|
51
|
+
|
|
52
|
+
```
|
|
53
|
+
pip install placo
|
|
54
|
+
```
|
|
55
|
+
|
|
56
|
+
Or [built from sources](https://placo.readthedocs.io/en/latest/basics/installation_source.html)
|
|
57
|
+
|
|
58
|
+
## Resources
|
|
59
|
+
|
|
60
|
+
* [Documentation](https://placo.readthedocs.io/en/latest/)
|
|
61
|
+
* [Examples](https://github.com/rhoban/placo-examples) repository
|
placo-0.6.5/README.md
ADDED
|
@@ -0,0 +1,39 @@
|
|
|
1
|
+
<img width="400" src="https://placo.readthedocs.io/en/latest/_static/placo.png" />
|
|
2
|
+
|
|
3
|
+
## Planning & Control
|
|
4
|
+
|
|
5
|
+
PlaCo is Rhoban's planning and control library. It is built on the top of [pinocchio](https://github.com/stack-of-tasks/pinocchio), [eiquadprog](https://github.com/stack-of-tasks/eiquadprog) QP solver, and fully written in C++ with Python bindings, allowing fast prototyping with good runtime performances. It features task-space inverse kinematics and dynamics (see below) high-level API for whole-body control tasks.
|
|
6
|
+
|
|
7
|
+
### Task-Space Inverse Kinematics
|
|
8
|
+
|
|
9
|
+
[](https://github.com/Rhoban/placo-examples/blob/master/kinematics/videos/quadruped_targets.mp4?raw=true)
|
|
10
|
+
|
|
11
|
+
High-level API to specify tasks for constrained inverse kinematics (IK).
|
|
12
|
+
|
|
13
|
+
- [See documentation](https://placo.readthedocs.io/en/latest/kinematics/getting_started.html)
|
|
14
|
+
- [Examples](https://placo.readthedocs.io/en/latest/kinematics/examples_gallery.html)
|
|
15
|
+
|
|
16
|
+
### Task-Space Inverse Dynamics
|
|
17
|
+
|
|
18
|
+
[](https://github.com/Rhoban/placo-examples/blob/master/dynamics/videos/megabot.mp4?raw=true)
|
|
19
|
+
|
|
20
|
+
High-level API to specify tasks for constrained inverse dynamics (ID).
|
|
21
|
+
|
|
22
|
+
- [See documentation](https://placo.readthedocs.io/en/latest/dynamics/getting_started.html)
|
|
23
|
+
- [Examples](https://placo.readthedocs.io/en/latest/dynamics/examples_gallery.html)
|
|
24
|
+
|
|
25
|
+
|
|
26
|
+
## Installing
|
|
27
|
+
|
|
28
|
+
PlaCo can be installed from ``pip``
|
|
29
|
+
|
|
30
|
+
```
|
|
31
|
+
pip install placo
|
|
32
|
+
```
|
|
33
|
+
|
|
34
|
+
Or [built from sources](https://placo.readthedocs.io/en/latest/basics/installation_source.html)
|
|
35
|
+
|
|
36
|
+
## Resources
|
|
37
|
+
|
|
38
|
+
* [Documentation](https://placo.readthedocs.io/en/latest/)
|
|
39
|
+
* [Examples](https://github.com/rhoban/placo-examples) repository
|
|
@@ -21,23 +21,20 @@ void exposeFootsteps()
|
|
|
21
21
|
.value("right", HumanoidRobot::Side::Right);
|
|
22
22
|
|
|
23
23
|
class__<FootstepsPlanner::Footstep>("Footstep", init<double, double>())
|
|
24
|
-
.def("support_polygon", &FootstepsPlanner::Footstep::support_polygon)
|
|
25
24
|
.add_property("side", &FootstepsPlanner::Footstep::side, &FootstepsPlanner::Footstep::side)
|
|
26
|
-
.def_readwrite("raw_frame", &FootstepsPlanner::Footstep::raw_frame)
|
|
27
|
-
.add_property("dx", &FootstepsPlanner::Footstep::dx, &FootstepsPlanner::Footstep::dx)
|
|
28
|
-
.add_property("dy", &FootstepsPlanner::Footstep::dy, &FootstepsPlanner::Footstep::dy)
|
|
29
25
|
.add_property("foot_length", &FootstepsPlanner::Footstep::foot_length, &FootstepsPlanner::Footstep::foot_length)
|
|
30
26
|
.add_property("foot_width", &FootstepsPlanner::Footstep::foot_width, &FootstepsPlanner::Footstep::foot_width)
|
|
27
|
+
.add_property("frame", &FootstepsPlanner::Footstep::frame, &FootstepsPlanner::Footstep::frame)
|
|
31
28
|
.def("support_polygon", &FootstepsPlanner::Footstep::support_polygon)
|
|
32
29
|
.def("overlap", &FootstepsPlanner::Footstep::overlap)
|
|
33
30
|
.def("polygon_contains", &FootstepsPlanner::Footstep::polygon_contains)
|
|
34
|
-
.def("frame", &FootstepsPlanner::Footstep::frame)
|
|
35
31
|
.staticmethod("polygon_contains");
|
|
36
32
|
|
|
37
33
|
class__<FootstepsPlanner::Support>("Support", init<>())
|
|
38
34
|
.def("support_polygon", &FootstepsPlanner::Support::support_polygon)
|
|
39
35
|
.def("frame", &FootstepsPlanner::Support::frame)
|
|
40
36
|
.def("footstep_frame", &FootstepsPlanner::Support::footstep_frame)
|
|
37
|
+
.def("apply_offset", &FootstepsPlanner::Support::apply_offset)
|
|
41
38
|
.def("side", &FootstepsPlanner::Support::side)
|
|
42
39
|
.def("is_both", &FootstepsPlanner::Support::is_both)
|
|
43
40
|
.def(
|
|
@@ -95,6 +95,7 @@ void exposeTools()
|
|
|
95
95
|
.def("is_point_in_segment", +[](Segment& s, const Eigen::Vector2d& point) { return s.is_point_in_segment(point); })
|
|
96
96
|
.def("intersects", &Segment::intersects)
|
|
97
97
|
.def("line_pass_through", &Segment::line_pass_through)
|
|
98
|
+
.def("half_line_pass_through", &Segment::half_line_pass_through)
|
|
98
99
|
.def("lines_intersection", &Segment::lines_intersection);
|
|
99
100
|
|
|
100
101
|
#ifdef HAVE_RHOBAN_UTILS
|
|
@@ -59,7 +59,8 @@ void exposeWalkPatternGenerator()
|
|
|
59
59
|
.def("plan", &WalkPatternGenerator::plan)
|
|
60
60
|
.def("replan", &WalkPatternGenerator::replan)
|
|
61
61
|
.def("can_replan_supports", &WalkPatternGenerator::can_replan_supports)
|
|
62
|
-
.def("replan_supports", &WalkPatternGenerator::replan_supports)
|
|
62
|
+
.def("replan_supports", &WalkPatternGenerator::replan_supports)
|
|
63
|
+
.def("compute_next_support", &WalkPatternGenerator::compute_next_support);
|
|
63
64
|
|
|
64
65
|
class__<SwingFoot>("SwingFoot", init<>())
|
|
65
66
|
.def("make_trajectory", &SwingFoot::make_trajectory)
|
|
@@ -2534,7 +2534,7 @@ class ExternalWrenchContact:
|
|
|
2534
2534
|
def __init__(
|
|
2535
2535
|
self: ExternalWrenchContact,
|
|
2536
2536
|
frame_index: any, # pinocchio::FrameIndex
|
|
2537
|
-
reference: any, # pinocchio::ReferenceFrame
|
|
2537
|
+
reference: any = None, # pinocchio::ReferenceFrame (default: pinocchio::LOCAL_WORLD_ALIGNED)
|
|
2538
2538
|
|
|
2539
2539
|
) -> any:
|
|
2540
2540
|
"""see DynamicsSolver::add_external_wrench_contact"""
|
|
@@ -2635,19 +2635,11 @@ class Footstep:
|
|
|
2635
2635
|
) -> any:
|
|
2636
2636
|
...
|
|
2637
2637
|
|
|
2638
|
-
dx: float # double
|
|
2639
|
-
|
|
2640
|
-
dy: float # double
|
|
2641
|
-
|
|
2642
2638
|
foot_length: float # double
|
|
2643
2639
|
|
|
2644
2640
|
foot_width: float # double
|
|
2645
2641
|
|
|
2646
|
-
|
|
2647
|
-
self: Footstep,
|
|
2648
|
-
|
|
2649
|
-
) -> numpy.ndarray:
|
|
2650
|
-
...
|
|
2642
|
+
frame: numpy.ndarray # Eigen::Affine3d
|
|
2651
2643
|
|
|
2652
2644
|
def overlap(
|
|
2653
2645
|
self: Footstep,
|
|
@@ -2665,8 +2657,6 @@ class Footstep:
|
|
|
2665
2657
|
) -> bool:
|
|
2666
2658
|
...
|
|
2667
2659
|
|
|
2668
|
-
raw_frame: numpy.ndarray # Eigen::Affine3d
|
|
2669
|
-
|
|
2670
2660
|
side: any # placo::humanoid::HumanoidRobot::Side
|
|
2671
2661
|
|
|
2672
2662
|
def support_polygon(
|
|
@@ -4392,7 +4382,7 @@ class KinematicsSolver:
|
|
|
4392
4382
|
def add_frame_task(
|
|
4393
4383
|
self: KinematicsSolver,
|
|
4394
4384
|
frame: str, # std::string
|
|
4395
|
-
T_world_frame: numpy.ndarray, # Eigen::Affine3d
|
|
4385
|
+
T_world_frame: numpy.ndarray = None, # Eigen::Affine3d (default: Eigen::Affine3d::Identity())
|
|
4396
4386
|
|
|
4397
4387
|
) -> FrameTask:
|
|
4398
4388
|
"""Adds a frame task, this is equivalent to a position + orientation task, resulting in decoupled tasks for a given frame.
|
|
@@ -4798,8 +4788,8 @@ class LIPM:
|
|
|
4798
4788
|
timesteps: int, # int
|
|
4799
4789
|
t_start: float, # double
|
|
4800
4790
|
initial_pos: numpy.ndarray, # Eigen::Vector2d
|
|
4801
|
-
initial_vel: numpy.ndarray, # Eigen::Vector2d
|
|
4802
|
-
initial_acc: numpy.ndarray, # Eigen::Vector2d
|
|
4791
|
+
initial_vel: numpy.ndarray = None, # Eigen::Vector2d (default: Eigen::Vector2d::Zero())
|
|
4792
|
+
initial_acc: numpy.ndarray = None, # Eigen::Vector2d (default: Eigen::Vector2d::Zero())
|
|
4803
4793
|
|
|
4804
4794
|
) -> any:
|
|
4805
4795
|
...
|
|
@@ -6569,6 +6559,19 @@ class Segment:
|
|
|
6569
6559
|
|
|
6570
6560
|
end: numpy.ndarray # Eigen::Vector2d
|
|
6571
6561
|
|
|
6562
|
+
def half_line_pass_through(
|
|
6563
|
+
self: Segment,
|
|
6564
|
+
s: Segment, # placo::tools::Segment
|
|
6565
|
+
|
|
6566
|
+
) -> bool:
|
|
6567
|
+
"""Checks if the half-line starting from the start of this segment and going through its end pass through another segment.
|
|
6568
|
+
|
|
6569
|
+
|
|
6570
|
+
:param s: The other segment.
|
|
6571
|
+
|
|
6572
|
+
:return: True if the intersection is a point of the other segment."""
|
|
6573
|
+
...
|
|
6574
|
+
|
|
6572
6575
|
def intersects(
|
|
6573
6576
|
self: Segment,
|
|
6574
6577
|
s: Segment, # placo::tools::Segment
|
|
@@ -6751,6 +6754,13 @@ class Support:
|
|
|
6751
6754
|
) -> any:
|
|
6752
6755
|
...
|
|
6753
6756
|
|
|
6757
|
+
def apply_offset(
|
|
6758
|
+
self: Support,
|
|
6759
|
+
offset: numpy.ndarray, # Eigen::Vector2d
|
|
6760
|
+
|
|
6761
|
+
) -> None:
|
|
6762
|
+
...
|
|
6763
|
+
|
|
6754
6764
|
elapsed_ratio: float # double
|
|
6755
6765
|
|
|
6756
6766
|
end: bool # bool
|
|
@@ -6893,7 +6903,7 @@ class SwingFootCubic:
|
|
|
6893
6903
|
start: numpy.ndarray, # Eigen::Vector3d
|
|
6894
6904
|
target: numpy.ndarray, # Eigen::Vector3d
|
|
6895
6905
|
elapsed_ratio: float = 0., # double
|
|
6896
|
-
start_vel: numpy.ndarray, # Eigen::Vector3d
|
|
6906
|
+
start_vel: numpy.ndarray = None, # Eigen::Vector3d (default: Eigen::Vector3d::Zero())
|
|
6897
6907
|
|
|
6898
6908
|
) -> SwingFootCubicTrajectory:
|
|
6899
6909
|
...
|
|
@@ -7332,6 +7342,21 @@ class WalkPatternGenerator:
|
|
|
7332
7342
|
"""Checks if a trajectory can be replanned for supports."""
|
|
7333
7343
|
...
|
|
7334
7344
|
|
|
7345
|
+
def compute_next_support(
|
|
7346
|
+
self: WalkPatternGenerator,
|
|
7347
|
+
t: float, # double
|
|
7348
|
+
current_support: Support, # placo::humanoid::FootstepsPlanner::Support
|
|
7349
|
+
next_support: Support, # placo::humanoid::FootstepsPlanner::Support
|
|
7350
|
+
world_measured_dcm: numpy.ndarray, # Eigen::Vector2d
|
|
7351
|
+
world_initial_dcm: numpy.ndarray, # Eigen::Vector2d
|
|
7352
|
+
|
|
7353
|
+
) -> any:
|
|
7354
|
+
"""Computes the position and time of the next support ensuring the DCM viability based on the measured DCM.
|
|
7355
|
+
|
|
7356
|
+
|
|
7357
|
+
:param TODO:"""
|
|
7358
|
+
...
|
|
7359
|
+
|
|
7335
7360
|
def plan(
|
|
7336
7361
|
self: WalkPatternGenerator,
|
|
7337
7362
|
supports: list[Support], # std::vector<placo::humanoid::FootstepsPlanner::Support>
|
|
@@ -31,7 +31,7 @@ std::vector<Eigen::Vector2d> FootstepsPlanner::Footstep::compute_polygon(double
|
|
|
31
31
|
for (auto sxsy : contour)
|
|
32
32
|
{
|
|
33
33
|
Eigen::Vector3d corner =
|
|
34
|
-
frame
|
|
34
|
+
frame * Eigen::Vector3d(sxsy.first * (margin + foot_length / 2), sxsy.second * (margin + foot_width / 2), 0.);
|
|
35
35
|
Eigen::Vector2d point(corner.x(), corner.y());
|
|
36
36
|
polygon.push_back(point);
|
|
37
37
|
}
|
|
@@ -93,17 +93,9 @@ bool FootstepsPlanner::Footstep::overlap(Footstep& other, double margin)
|
|
|
93
93
|
return false;
|
|
94
94
|
}
|
|
95
95
|
|
|
96
|
-
Eigen::Affine3d FootstepsPlanner::Footstep::frame()
|
|
97
|
-
{
|
|
98
|
-
Eigen::Affine3d f = raw_frame;
|
|
99
|
-
f.translation().x() += dx;
|
|
100
|
-
f.translation().y() += dy;
|
|
101
|
-
return f;
|
|
102
|
-
}
|
|
103
|
-
|
|
104
96
|
bool FootstepsPlanner::Footstep::operator==(const Footstep& other)
|
|
105
97
|
{
|
|
106
|
-
return side == other.side &&
|
|
98
|
+
return side == other.side && frame.isApprox(other.frame);
|
|
107
99
|
}
|
|
108
100
|
|
|
109
101
|
FootstepsPlanner::Support::Support()
|
|
@@ -153,11 +145,11 @@ Eigen::Affine3d FootstepsPlanner::Support::frame()
|
|
|
153
145
|
{
|
|
154
146
|
if (n == 1)
|
|
155
147
|
{
|
|
156
|
-
f = footstep.frame
|
|
148
|
+
f = footstep.frame;
|
|
157
149
|
}
|
|
158
150
|
else
|
|
159
151
|
{
|
|
160
|
-
f = tools::interpolate_frames(f, footstep.frame
|
|
152
|
+
f = tools::interpolate_frames(f, footstep.frame, 1. / n);
|
|
161
153
|
}
|
|
162
154
|
|
|
163
155
|
n += 1;
|
|
@@ -171,13 +163,24 @@ Eigen::Affine3d FootstepsPlanner::Support::footstep_frame(HumanoidRobot::Side si
|
|
|
171
163
|
{
|
|
172
164
|
if (footstep.side == side)
|
|
173
165
|
{
|
|
174
|
-
return footstep.frame
|
|
166
|
+
return footstep.frame;
|
|
175
167
|
}
|
|
176
168
|
}
|
|
177
169
|
|
|
178
170
|
throw std::logic_error("Asked for a frame that doesn't exist");
|
|
179
171
|
}
|
|
180
172
|
|
|
173
|
+
void FootstepsPlanner::Support::apply_offset(Eigen::Vector2d offset)
|
|
174
|
+
{
|
|
175
|
+
for (auto& footstep : footsteps)
|
|
176
|
+
{
|
|
177
|
+
footstep.frame.translation().x() += offset.x();
|
|
178
|
+
footstep.frame.translation().y() += offset.y();
|
|
179
|
+
footstep.computed_polygon = false;
|
|
180
|
+
}
|
|
181
|
+
computed_polygon = false;
|
|
182
|
+
}
|
|
183
|
+
|
|
181
184
|
HumanoidRobot::Side FootstepsPlanner::Support::side()
|
|
182
185
|
{
|
|
183
186
|
if (footsteps.size() > 1)
|
|
@@ -199,7 +202,7 @@ FootstepsPlanner::Support operator*(Eigen::Affine3d T, const FootstepsPlanner::S
|
|
|
199
202
|
|
|
200
203
|
for (auto& footstep : new_support.footsteps)
|
|
201
204
|
{
|
|
202
|
-
footstep.
|
|
205
|
+
footstep.frame = T * footstep.frame;
|
|
203
206
|
footstep.computed_polygon = false;
|
|
204
207
|
}
|
|
205
208
|
new_support.computed_polygon = false;
|
|
@@ -289,7 +292,7 @@ FootstepsPlanner::Footstep FootstepsPlanner::create_footstep(HumanoidRobot::Side
|
|
|
289
292
|
FootstepsPlanner::Footstep footstep(parameters.foot_width, parameters.foot_length);
|
|
290
293
|
|
|
291
294
|
footstep.side = side;
|
|
292
|
-
footstep.
|
|
295
|
+
footstep.frame = T_world_foot;
|
|
293
296
|
|
|
294
297
|
return footstep;
|
|
295
298
|
}
|
|
@@ -297,7 +300,7 @@ FootstepsPlanner::Footstep FootstepsPlanner::create_footstep(HumanoidRobot::Side
|
|
|
297
300
|
FootstepsPlanner::Footstep FootstepsPlanner::opposite_footstep(FootstepsPlanner::Footstep footstep, double d_x,
|
|
298
301
|
double d_y, double d_theta)
|
|
299
302
|
{
|
|
300
|
-
footstep.
|
|
303
|
+
footstep.frame = parameters.opposite_frame(footstep.side, footstep.frame, d_x, d_y, d_theta);
|
|
301
304
|
footstep.side = HumanoidRobot::other_side(footstep.side);
|
|
302
305
|
|
|
303
306
|
return footstep;
|
|
@@ -22,11 +22,7 @@ public:
|
|
|
22
22
|
double foot_length;
|
|
23
23
|
|
|
24
24
|
HumanoidRobot::Side side;
|
|
25
|
-
Eigen::Affine3d
|
|
26
|
-
Eigen::Affine3d frame();
|
|
27
|
-
|
|
28
|
-
double dx = 0.; // Footstep offset in x (m)
|
|
29
|
-
double dy = 0.; // Footstep offset in y (m)
|
|
25
|
+
Eigen::Affine3d frame;
|
|
30
26
|
|
|
31
27
|
std::vector<Eigen::Vector2d> polygon;
|
|
32
28
|
bool computed_polygon = false;
|
|
@@ -80,6 +76,8 @@ public:
|
|
|
80
76
|
*/
|
|
81
77
|
Eigen::Affine3d footstep_frame(HumanoidRobot::Side side);
|
|
82
78
|
|
|
79
|
+
void apply_offset(Eigen::Vector2d offset);
|
|
80
|
+
|
|
83
81
|
bool operator==(const Support& other);
|
|
84
82
|
|
|
85
83
|
/**
|
|
@@ -137,13 +137,13 @@ void FootstepsPlannerNaive::plan_impl(std::vector<FootstepsPlanner::Footstep>& f
|
|
|
137
137
|
if (current_support_side == HumanoidRobot::Side::Left)
|
|
138
138
|
{
|
|
139
139
|
right_arrived = arrived;
|
|
140
|
-
T_world_currentRight = footstep.frame
|
|
140
|
+
T_world_currentRight = footstep.frame;
|
|
141
141
|
current_support_side = HumanoidRobot::Side::Right;
|
|
142
142
|
}
|
|
143
143
|
else
|
|
144
144
|
{
|
|
145
145
|
left_arrived = arrived;
|
|
146
|
-
T_world_currentLeft = footstep.frame
|
|
146
|
+
T_world_currentLeft = footstep.frame;
|
|
147
147
|
current_support_side = HumanoidRobot::Side::Left;
|
|
148
148
|
}
|
|
149
149
|
}
|
|
@@ -283,7 +283,7 @@ void WalkPatternGenerator::Trajectory::add_supports(double t, FootstepsPlanner::
|
|
|
283
283
|
{
|
|
284
284
|
for (auto footstep : support.footsteps)
|
|
285
285
|
{
|
|
286
|
-
auto T_world_foot = footstep.frame
|
|
286
|
+
auto T_world_foot = footstep.frame;
|
|
287
287
|
foot_yaw(footstep.side).add_point(t, frame_yaw(T_world_foot.rotation()), 0);
|
|
288
288
|
}
|
|
289
289
|
}
|
|
@@ -570,7 +570,7 @@ void WalkPatternGenerator::Trajectory::print_parts_timings()
|
|
|
570
570
|
}
|
|
571
571
|
|
|
572
572
|
std::pair<Eigen::Vector2d, double> WalkPatternGenerator::compute_next_support(double t, FootstepsPlanner::Support& current_support,
|
|
573
|
-
FootstepsPlanner::Support& next_support, Eigen::Vector2d world_measured_dcm, Eigen::Vector2d world_initial_dcm
|
|
573
|
+
FootstepsPlanner::Support& next_support, Eigen::Vector2d world_measured_dcm, Eigen::Vector2d world_initial_dcm)
|
|
574
574
|
{
|
|
575
575
|
if (current_support.is_both())
|
|
576
576
|
{
|
|
@@ -625,7 +625,7 @@ std::pair<Eigen::Vector2d, double> WalkPatternGenerator::compute_next_support(do
|
|
|
625
625
|
}
|
|
626
626
|
|
|
627
627
|
// Time constraints
|
|
628
|
-
double T_min = t; // Should probably add an offset
|
|
628
|
+
double T_min = std::max(0.15, t); // Should probably add an offset to t
|
|
629
629
|
double T_max = 3; // Arbitrary value of 3s
|
|
630
630
|
problem.add_constraint(tau.expr() >= exp(omega * (T_min))).configure(ProblemConstraint::Hard);
|
|
631
631
|
problem.add_constraint(tau.expr() <= exp(omega * (T_max))).configure(ProblemConstraint::Hard);
|
|
@@ -176,7 +176,7 @@ public:
|
|
|
176
176
|
* @param TODO
|
|
177
177
|
*/
|
|
178
178
|
std::pair<Eigen::Vector2d, double> compute_next_support(double t, FootstepsPlanner::Support& current_support,
|
|
179
|
-
FootstepsPlanner::Support& next_support, Eigen::Vector2d world_measured_dcm, Eigen::Vector2d world_initial_dcm
|
|
179
|
+
FootstepsPlanner::Support& next_support, Eigen::Vector2d world_measured_dcm, Eigen::Vector2d world_initial_dcm);
|
|
180
180
|
|
|
181
181
|
protected:
|
|
182
182
|
// Robot associated to the WPG
|
|
@@ -67,6 +67,23 @@ bool Segment::line_pass_through(const Segment& s)
|
|
|
67
67
|
return t >= 0 && t <= 1;
|
|
68
68
|
}
|
|
69
69
|
|
|
70
|
+
bool Segment::half_line_pass_through(const Segment& s)
|
|
71
|
+
{
|
|
72
|
+
if (is_parallel(s))
|
|
73
|
+
{
|
|
74
|
+
throw std::runtime_error("Can't compute intersection of parallels");
|
|
75
|
+
}
|
|
76
|
+
|
|
77
|
+
Eigen::Vector2d v1 = end - start;
|
|
78
|
+
Eigen::Vector2d v2 = s.end - s.start;
|
|
79
|
+
Eigen::Vector2d p1 = start;
|
|
80
|
+
Eigen::Vector2d p2 = s.start;
|
|
81
|
+
double det = v1.x() * v2.y() - v1.y() * v2.x();
|
|
82
|
+
double t_1 = (v2.y() * (p2.x() - p1.x()) + v2.x() * (p1.y() - p2.y())) / det;
|
|
83
|
+
double t_2 = (v1.y() * (p2.x() - p1.x()) + v1.x() * (p1.y() - p2.y())) / det;
|
|
84
|
+
return t_1 >= 0 && t_1 <= 1 && t_2 >= 0;
|
|
85
|
+
}
|
|
86
|
+
|
|
70
87
|
Eigen::Vector2d Segment::lines_intersection(const Segment& s)
|
|
71
88
|
{
|
|
72
89
|
if (is_parallel(s))
|
|
@@ -61,6 +61,14 @@ public:
|
|
|
61
61
|
*/
|
|
62
62
|
bool line_pass_through(const Segment& s);
|
|
63
63
|
|
|
64
|
+
/**
|
|
65
|
+
* @brief Checks if the half-line starting from the start of this segment and
|
|
66
|
+
* going through its end pass through another segment.
|
|
67
|
+
* @param s The other segment.
|
|
68
|
+
* @return True if the intersection is a point of the other segment.
|
|
69
|
+
*/
|
|
70
|
+
bool half_line_pass_through(const Segment& s);
|
|
71
|
+
|
|
64
72
|
/**
|
|
65
73
|
* @brief Return the intersection between the guiding lines of this segment and another one.
|
|
66
74
|
* @param s The other segment.
|
|
@@ -59,6 +59,7 @@ for entry in cxx_registry:
|
|
|
59
59
|
rewrite_types[entry] = cxx_registry[entry]
|
|
60
60
|
py_registry[cxx_registry[entry]] = entry
|
|
61
61
|
|
|
62
|
+
|
|
62
63
|
def get_member(class_name: str, member_name: str):
|
|
63
64
|
if class_name in py_registry:
|
|
64
65
|
cxx_name = py_registry[class_name]
|
|
@@ -131,13 +132,17 @@ def print_def_prototype(
|
|
|
131
132
|
|
|
132
133
|
str_definition += f"{prefix}def {method_name}(\n"
|
|
133
134
|
for arg_name, arg_type, defvalue, comment in args:
|
|
135
|
+
extra_comment = ""
|
|
134
136
|
str_definition += f"{prefix} {arg_name}: {arg_type}"
|
|
135
137
|
if defvalue is not None:
|
|
136
138
|
if arg_type in ["str", "float", "int", "bool"]:
|
|
137
139
|
str_definition += f" = {defvalue.capitalize()}"
|
|
140
|
+
else:
|
|
141
|
+
str_definition += f" = None"
|
|
142
|
+
extra_comment = f" (default: {defvalue})"
|
|
138
143
|
str_definition += ","
|
|
139
144
|
if comment is not None:
|
|
140
|
-
str_definition += f" # {comment}"
|
|
145
|
+
str_definition += f" # {comment}{extra_comment}"
|
|
141
146
|
str_definition += "\n"
|
|
142
147
|
str_definition += f"\n{prefix}) -> {return_type}:\n"
|
|
143
148
|
if doc != "":
|
|
@@ -221,7 +226,7 @@ print("import typing")
|
|
|
221
226
|
for name, object in inspect.getmembers(placo):
|
|
222
227
|
if isinstance(object, type):
|
|
223
228
|
class_name = object.__name__
|
|
224
|
-
print(f
|
|
229
|
+
print(f'{class_name} = typing.NewType("{class_name}", None)')
|
|
225
230
|
|
|
226
231
|
groups = {}
|
|
227
232
|
|
|
@@ -234,10 +239,10 @@ for name, object in inspect.getmembers(placo):
|
|
|
234
239
|
metadata = get_metadata(py_registry[class_name])
|
|
235
240
|
|
|
236
241
|
if metadata is not None:
|
|
237
|
-
|
|
238
|
-
|
|
239
|
-
|
|
240
|
-
|
|
242
|
+
namespace = "::".join(metadata["name"].split("::")[:-1][:2])
|
|
243
|
+
if namespace not in groups:
|
|
244
|
+
groups[namespace] = []
|
|
245
|
+
groups[namespace].append(class_name)
|
|
241
246
|
|
|
242
247
|
if (
|
|
243
248
|
metadata is not None
|
|
@@ -259,4 +264,4 @@ for name, object in inspect.getmembers(placo):
|
|
|
259
264
|
else:
|
|
260
265
|
...
|
|
261
266
|
|
|
262
|
-
print(f"__groups__ = {groups}")
|
|
267
|
+
print(f"__groups__ = {groups}")
|
placo-0.6.4/PKG-INFO
DELETED
|
@@ -1,56 +0,0 @@
|
|
|
1
|
-
Metadata-Version: 2.4
|
|
2
|
-
Name: placo
|
|
3
|
-
Version: 0.6.4
|
|
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
|
-
[](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
|
-
[](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.4/README.md
DELETED
|
@@ -1,34 +0,0 @@
|
|
|
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
|
-
[](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
|
-
[](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.
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|