placo 0.8.0__tar.gz → 0.8.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.8.0 → placo-0.8.5}/.github/workflows/wheels.yml +7 -6
- {placo-0.8.0 → placo-0.8.5}/PKG-INFO +1 -1
- {placo-0.8.0 → placo-0.8.5}/bindings/expose-footsteps.cpp +4 -0
- {placo-0.8.0 → placo-0.8.5}/bindings/expose-walk-pattern-generator.cpp +5 -3
- {placo-0.8.0 → placo-0.8.5}/pyproject.toml +1 -1
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/walk_pattern_generator.cpp +19 -13
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/walk_pattern_generator.h +12 -10
- {placo-0.8.0 → placo-0.8.5}/.clang-format +0 -0
- {placo-0.8.0 → placo-0.8.5}/.gitattributes +0 -0
- {placo-0.8.0 → placo-0.8.5}/.gitignore +0 -0
- {placo-0.8.0 → placo-0.8.5}/.readthedocs.yaml +0 -0
- {placo-0.8.0 → placo-0.8.5}/CMakeLists.txt +0 -0
- {placo-0.8.0 → placo-0.8.5}/Doxyfile +0 -0
- {placo-0.8.0 → placo-0.8.5}/LICENSE +0 -0
- {placo-0.8.0 → placo-0.8.5}/Makefile +0 -0
- {placo-0.8.0 → placo-0.8.5}/README.md +0 -0
- {placo-0.8.0 → placo-0.8.5}/bindings/doxystub.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/bindings/expose-dynamics.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/bindings/expose-eigen.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/bindings/expose-kinematics.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/bindings/expose-parameters.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/bindings/expose-problem.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/bindings/expose-robot-wrapper.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/bindings/expose-tools.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/bindings/expose-utils.hpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/bindings/module.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/bindings/module.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/build_wheel.sh +0 -0
- {placo-0.8.0 → placo-0.8.5}/python/.vscode/settings.json +0 -0
- {placo-0.8.0 → placo-0.8.5}/python/Makefile +0 -0
- {placo-0.8.0 → placo-0.8.5}/python/placo_utils/__init__.py +0 -0
- {placo-0.8.0 → placo-0.8.5}/python/placo_utils/tf.py +0 -0
- {placo-0.8.0 → placo-0.8.5}/python/placo_utils/view.py +0 -0
- {placo-0.8.0 → placo-0.8.5}/python/placo_utils/visualization.py +0 -0
- {placo-0.8.0 → placo-0.8.5}/python/run_tests.sh +0 -0
- {placo-0.8.0 → placo-0.8.5}/scripts/requirements.sh +0 -0
- {placo-0.8.0 → placo-0.8.5}/scripts/robotpkg.sh +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/avoid_self_collisions_constraint.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/avoid_self_collisions_constraint.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/com_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/com_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/constraint.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/constraint.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/contacts.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/contacts.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/dynamics_solver.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/dynamics_solver.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/frame_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/frame_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/gear_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/gear_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/joints_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/joints_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/orientation_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/orientation_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/position_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/position_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/relative_frame_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/relative_frame_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/relative_orientation_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/relative_orientation_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/relative_position_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/relative_position_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/torque_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/dynamics/torque_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/foot_trajectory.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/foot_trajectory.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/footsteps_planner.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/footsteps_planner.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/footsteps_planner_naive.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/footsteps_planner_naive.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/footsteps_planner_repetitive.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/footsteps_planner_repetitive.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/humanoid_parameters.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/humanoid_parameters.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/humanoid_robot.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/humanoid_robot.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/kick.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/kick.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/lipm.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/lipm.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/swing_foot.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/swing_foot.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/swing_foot_cubic.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/swing_foot_cubic.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/swing_foot_quintic.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/swing_foot_quintic.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/walk_tasks.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/humanoid/walk_tasks.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/avoid_self_collisions_constraint.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/avoid_self_collisions_constraint.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/axis_align_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/axis_align_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/centroidal_momentum_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/centroidal_momentum_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/com_polygon_constraint.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/com_polygon_constraint.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/com_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/com_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/cone_constraint.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/cone_constraint.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/constraint.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/constraint.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/distance_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/distance_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/frame_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/frame_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/gear_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/gear_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/joint_space_half_spaces_constraint.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/joint_space_half_spaces_constraint.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/joints_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/joints_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/kinematics_solver.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/kinematics_solver.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/kinetic_energy_regularization_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/kinetic_energy_regularization_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/manipulability_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/manipulability_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/orientation_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/orientation_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/position_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/position_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/regularization_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/regularization_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/relative_frame_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/relative_frame_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/relative_orientation_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/relative_orientation_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/relative_position_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/relative_position_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/wheel_task.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/kinematics/wheel_task.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/model/robot_wrapper.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/model/robot_wrapper.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/constraint.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/constraint.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/expression.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/expression.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/integrator.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/integrator.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/polygon_constraint.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/polygon_constraint.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/problem.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/problem.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/problem_polynom.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/problem_polynom.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/qp_error.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/qp_error.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/sparsity.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/sparsity.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/variable.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/problem/variable.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/axises_mask.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/axises_mask.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/cubic_spline.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/cubic_spline.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/cubic_spline_3d.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/cubic_spline_3d.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/directions.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/directions.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/polynom.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/polynom.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/prioritized.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/prioritized.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/segment.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/segment.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/utils.cpp +0 -0
- {placo-0.8.0 → placo-0.8.5}/src/placo/tools/utils.h +0 -0
- {placo-0.8.0 → placo-0.8.5}/tweak_sdist.sh +0 -0
- {placo-0.8.0 → placo-0.8.5}/wks.yml +0 -0
|
@@ -6,16 +6,17 @@ on:
|
|
|
6
6
|
- published
|
|
7
7
|
|
|
8
8
|
env:
|
|
9
|
-
CIBW_SKIP: "*musl* *
|
|
9
|
+
CIBW_SKIP: "*i686 *musl* *armv7* *ppc64* *s390*"
|
|
10
10
|
CIBW_REPAIR_WHEEL_COMMAND: ""
|
|
11
11
|
|
|
12
12
|
jobs:
|
|
13
13
|
build_wheels:
|
|
14
|
-
name:
|
|
14
|
+
name: Wheel ${{ matrix.os }}, ${{ matrix.pyver }}
|
|
15
15
|
runs-on: ${{ matrix.os }}
|
|
16
16
|
strategy:
|
|
17
17
|
matrix:
|
|
18
|
-
os: [macos-latest, ubuntu-latest, macos-13]
|
|
18
|
+
os: [macos-latest, ubuntu-latest, ubuntu-24.04-arm, macos-13]
|
|
19
|
+
pyver: [cp39, cp310, cp311, cp312, cp313]
|
|
19
20
|
|
|
20
21
|
steps:
|
|
21
22
|
- uses: actions/checkout@v4
|
|
@@ -29,13 +30,13 @@ jobs:
|
|
|
29
30
|
- name: Build wheels
|
|
30
31
|
run: python -m cibuildwheel --output-dir wheelhouse
|
|
31
32
|
# to supply options, put them in 'env', like:
|
|
32
|
-
|
|
33
|
-
|
|
33
|
+
env:
|
|
34
|
+
CIBW_BUILD: ${{ matrix.pyver }}-*
|
|
34
35
|
# ...
|
|
35
36
|
|
|
36
37
|
- uses: actions/upload-artifact@v4
|
|
37
38
|
with:
|
|
38
|
-
name: cibw-wheels-${{ matrix.os }}-${{
|
|
39
|
+
name: cibw-wheels-${{ matrix.os }}-${{ matrix.pyver }}
|
|
39
40
|
path: ./wheelhouse/*.whl
|
|
40
41
|
|
|
41
42
|
build_sdist:
|
|
@@ -25,6 +25,10 @@ void exposeFootsteps()
|
|
|
25
25
|
.add_property("foot_length", &FootstepsPlanner::Footstep::foot_length, &FootstepsPlanner::Footstep::foot_length)
|
|
26
26
|
.add_property("foot_width", &FootstepsPlanner::Footstep::foot_width, &FootstepsPlanner::Footstep::foot_width)
|
|
27
27
|
.add_property("frame", &FootstepsPlanner::Footstep::frame, &FootstepsPlanner::Footstep::frame)
|
|
28
|
+
.def("set_frame_xy", +[](FootstepsPlanner::Footstep& footstep, double x, double y) {
|
|
29
|
+
footstep.frame.translation().x() = x;
|
|
30
|
+
footstep.frame.translation().y() = y;
|
|
31
|
+
})
|
|
28
32
|
.def("support_polygon", &FootstepsPlanner::Footstep::support_polygon)
|
|
29
33
|
.def("overlap", &FootstepsPlanner::Footstep::overlap)
|
|
30
34
|
.def("polygon_contains", &FootstepsPlanner::Footstep::polygon_contains)
|
|
@@ -23,9 +23,9 @@ using namespace placo::humanoid;
|
|
|
23
23
|
void exposeWalkPatternGenerator()
|
|
24
24
|
{
|
|
25
25
|
class__<WalkPatternGenerator::TrajectoryPart>("WPGTrajectoryPart", init<FootstepsPlanner::Support, double>())
|
|
26
|
-
.add_property("t_start", &WalkPatternGenerator::TrajectoryPart::t_start)
|
|
26
|
+
.add_property("t_start", &WalkPatternGenerator::TrajectoryPart::t_start, &WalkPatternGenerator::TrajectoryPart::t_start)
|
|
27
27
|
.add_property("t_end", &WalkPatternGenerator::TrajectoryPart::t_end, &WalkPatternGenerator::TrajectoryPart::t_end)
|
|
28
|
-
.add_property("support", &WalkPatternGenerator::TrajectoryPart::support);
|
|
28
|
+
.add_property("support", &WalkPatternGenerator::TrajectoryPart::support, &WalkPatternGenerator::TrajectoryPart::support);
|
|
29
29
|
|
|
30
30
|
class__<WalkPatternGenerator::Trajectory>("WPGTrajectory", init<double, double, double, double>())
|
|
31
31
|
.add_property("t_start", &WalkPatternGenerator::Trajectory::t_start)
|
|
@@ -34,6 +34,7 @@ void exposeWalkPatternGenerator()
|
|
|
34
34
|
.add_property("trunk_pitch", &WalkPatternGenerator::Trajectory::trunk_pitch)
|
|
35
35
|
.add_property("trunk_roll", &WalkPatternGenerator::Trajectory::trunk_roll)
|
|
36
36
|
.add_property("kept_ts", &WalkPatternGenerator::Trajectory::kept_ts)
|
|
37
|
+
.add_property("parts", &WalkPatternGenerator::Trajectory::parts)
|
|
37
38
|
.def("get_T_world_left", &WalkPatternGenerator::Trajectory::get_T_world_left)
|
|
38
39
|
.def("get_T_world_right", &WalkPatternGenerator::Trajectory::get_T_world_right)
|
|
39
40
|
.def("get_v_world_right", &WalkPatternGenerator::Trajectory::get_v_world_right)
|
|
@@ -65,7 +66,8 @@ void exposeWalkPatternGenerator()
|
|
|
65
66
|
.def("update_supports", &WalkPatternGenerator::update_supports)
|
|
66
67
|
.def("get_optimal_zmp", &WalkPatternGenerator::get_optimal_zmp)
|
|
67
68
|
.def("support_default_timesteps", &WalkPatternGenerator::support_default_timesteps)
|
|
68
|
-
.def("support_default_duration", &WalkPatternGenerator::support_default_duration)
|
|
69
|
+
.def("support_default_duration", &WalkPatternGenerator::support_default_duration)
|
|
70
|
+
.add_property("soft", &WalkPatternGenerator::soft, &WalkPatternGenerator::soft);
|
|
69
71
|
|
|
70
72
|
class__<SwingFoot>("SwingFoot", init<>())
|
|
71
73
|
.def("make_trajectory", &SwingFoot::make_trajectory)
|
|
@@ -376,7 +376,11 @@ void WalkPatternGenerator::constrain_lipm(problem::Problem& problem, LIPM& lipm,
|
|
|
376
376
|
for (int timestep = 1; timestep < lipm.timesteps+1; timestep++)
|
|
377
377
|
{
|
|
378
378
|
// Ensuring ZMP remains in the support polygon
|
|
379
|
-
problem.add_constraint(PolygonConstraint::in_polygon_xy(lipm.zmp(timestep, omega_2), support.support_polygon(), parameters.zmp_margin));
|
|
379
|
+
auto& zmp_constraint = problem.add_constraint(PolygonConstraint::in_polygon_xy(lipm.zmp(timestep, omega_2), support.support_polygon(), parameters.zmp_margin));
|
|
380
|
+
if (soft)
|
|
381
|
+
{
|
|
382
|
+
zmp_constraint.configure(ProblemConstraint::Soft, 1e5);
|
|
383
|
+
}
|
|
380
384
|
|
|
381
385
|
// Optional offset for single supports
|
|
382
386
|
double x_offset = 0., y_offset = 0.;
|
|
@@ -393,9 +397,16 @@ void WalkPatternGenerator::constrain_lipm(problem::Problem& problem, LIPM& lipm,
|
|
|
393
397
|
// At the end of an end support, we reach the target with a null speed and a null acceleration
|
|
394
398
|
if (support.end && timestep == lipm.timesteps)
|
|
395
399
|
{
|
|
396
|
-
problem.add_constraint(lipm.pos(timestep) == Eigen::Vector2d(support.frame().translation().x(), support.frame().translation().y()));
|
|
397
|
-
problem.add_constraint(lipm.vel(timestep) == Eigen::Vector2d(0., 0.));
|
|
398
|
-
problem.add_constraint(lipm.acc(timestep) == Eigen::Vector2d(0., 0.));
|
|
400
|
+
auto& pos_constraint = problem.add_constraint(lipm.pos(timestep) == Eigen::Vector2d(support.frame().translation().x(), support.frame().translation().y()));
|
|
401
|
+
auto& vel_constraint = problem.add_constraint(lipm.vel(timestep) == Eigen::Vector2d(0., 0.));
|
|
402
|
+
auto& acc_constraint = problem.add_constraint(lipm.acc(timestep) == Eigen::Vector2d(0., 0.));
|
|
403
|
+
|
|
404
|
+
if (soft)
|
|
405
|
+
{
|
|
406
|
+
pos_constraint.configure(ProblemConstraint::Soft, 1e3);
|
|
407
|
+
vel_constraint.configure(ProblemConstraint::Soft, 1e3);
|
|
408
|
+
acc_constraint.configure(ProblemConstraint::Soft, 1e3);
|
|
409
|
+
}
|
|
399
410
|
}
|
|
400
411
|
}
|
|
401
412
|
}
|
|
@@ -602,19 +613,13 @@ void WalkPatternGenerator::Trajectory::print_parts_timings()
|
|
|
602
613
|
}
|
|
603
614
|
|
|
604
615
|
std::vector<FootstepsPlanner::Support> WalkPatternGenerator::update_supports(double t,
|
|
605
|
-
std::vector<FootstepsPlanner::Support> supports, Eigen::Vector2d world_measured_dcm)
|
|
616
|
+
std::vector<FootstepsPlanner::Support> supports, Eigen::Vector2d world_target_zmp, Eigen::Vector2d world_measured_dcm)
|
|
606
617
|
{
|
|
607
618
|
FootstepsPlanner::Support current_support = supports[0];
|
|
608
|
-
FootstepsPlanner::Support next_support = supports[1];
|
|
609
|
-
|
|
610
619
|
if (current_support.is_both())
|
|
611
620
|
{
|
|
612
621
|
throw std::runtime_error("Can't modify flying target and step duration if the current support is both");
|
|
613
622
|
}
|
|
614
|
-
if (next_support.is_both())
|
|
615
|
-
{
|
|
616
|
-
throw std::runtime_error("Next support is both, not supported for now");
|
|
617
|
-
}
|
|
618
623
|
|
|
619
624
|
placo::problem::Problem problem;
|
|
620
625
|
double w1 = 5;
|
|
@@ -638,10 +643,11 @@ std::vector<FootstepsPlanner::Support> WalkPatternGenerator::update_supports(dou
|
|
|
638
643
|
|
|
639
644
|
// ZMP Reference (expressed in the world frame)
|
|
640
645
|
Expression world_next_zmp_expr = p_world_support + R_world_support * support_next_zmp->expr();
|
|
641
|
-
problem.add_constraint(world_next_zmp_expr ==
|
|
646
|
+
problem.add_constraint(world_next_zmp_expr == world_target_zmp).configure(ProblemConstraint::Soft, w2);
|
|
642
647
|
|
|
643
648
|
// DCM offset reference (expressed in the world frame)
|
|
644
|
-
|
|
649
|
+
// XXX : l'offset doit être calculé par rapport à la cible mise à jour non ?
|
|
650
|
+
Eigen::Vector2d world_target_dcm_offset = current_support.target_world_dcm - world_target_zmp;
|
|
645
651
|
// Eigen::Vector2d world_target_dcm_offset = world_end_dcm - next_support.frame().translation().head(2);
|
|
646
652
|
// std::cout << "world_target_dcm_offset: " << world_target_dcm_offset.transpose() << std::endl;
|
|
647
653
|
|
|
@@ -180,21 +180,21 @@ public:
|
|
|
180
180
|
/**
|
|
181
181
|
* @brief Updates the supports to ensure DCM viability by adjusting the
|
|
182
182
|
* duration and the target of the current swing trajectory.
|
|
183
|
-
* @param t
|
|
184
|
-
* @param supports
|
|
185
|
-
* @param
|
|
186
|
-
* @param
|
|
183
|
+
* @param t Current time
|
|
184
|
+
* @param supports Planned supports
|
|
185
|
+
* @param world_target_zmp Target ZMP for the flying foot in world frame
|
|
186
|
+
* @param world_measured_dcm Measured DCM in world frame
|
|
187
187
|
*/
|
|
188
|
-
std::vector<FootstepsPlanner::Support> update_supports(double t,
|
|
189
|
-
|
|
188
|
+
std::vector<FootstepsPlanner::Support> update_supports(double t, std::vector<FootstepsPlanner::Support> supports,
|
|
189
|
+
Eigen::Vector2d world_target_zmp, Eigen::Vector2d world_measured_dcm);
|
|
190
190
|
|
|
191
191
|
/**
|
|
192
192
|
* @brief Computes the best ZMP in the support polygon to move de DCM from
|
|
193
193
|
* world_dcm_start to world_dcm_end in duration.
|
|
194
|
-
* @param world_dcm_start
|
|
195
|
-
* @param world_dcm_end
|
|
196
|
-
* @param duration
|
|
197
|
-
* @param support
|
|
194
|
+
* @param world_dcm_start Initial DCM position in world frame
|
|
195
|
+
* @param world_dcm_end Desired final DCM position in world frame
|
|
196
|
+
* @param duration Duration
|
|
197
|
+
* @param support Support
|
|
198
198
|
*/
|
|
199
199
|
Eigen::Vector2d get_optimal_zmp(Eigen::Vector2d world_dcm_start, Eigen::Vector2d world_dcm_end,
|
|
200
200
|
double duration, FootstepsPlanner::Support& support);
|
|
@@ -202,6 +202,8 @@ public:
|
|
|
202
202
|
int support_default_timesteps(FootstepsPlanner::Support& support);
|
|
203
203
|
double support_default_duration(FootstepsPlanner::Support& support);
|
|
204
204
|
|
|
205
|
+
bool soft = false;
|
|
206
|
+
|
|
205
207
|
protected:
|
|
206
208
|
// Robot associated to the WPG
|
|
207
209
|
HumanoidRobot& robot;
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
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
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|
|
File without changes
|