Skip to content

Commit

Permalink
Fix a few examples scripts (#2392)
Browse files Browse the repository at this point in the history
* [unittest] Remove compilation warning from mjcf test

* [examples] Remove duplicate line

* [examples] Update talos example

* [examples] Update closed kinematic example

* Update CHANGELOG.md

---------

Co-authored-by: Megane Millan <[email protected]>
  • Loading branch information
MegMll and Megane Millan authored Aug 27, 2024
1 parent 40570d5 commit da40f76
Show file tree
Hide file tree
Showing 5 changed files with 7 additions and 8 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/).
- Fixed urdfdom in ROS packaging ([#2341](https://github.com/stack-of-tasks/pinocchio/pull/2341))
- Fixed overview-urdf cpp example ([#2384](https://github.com/stack-of-tasks/pinocchio/pull/2384))
- Fixed mjcf model without a base link parsing ([#2386](https://github.com/stack-of-tasks/pinocchio/pull/2386))
- Fixed talos-simulation.py, simulation-contact-dynamics.py and simulation-closed-kinematic-chains.py examples ([#2392](https://github.com/stack-of-tasks/pinocchio/pull/2392))

### Added
- Add getMotionAxis method to helical, prismatic, revolute and ubounded revolute joint ([#2315](https://github.com/stack-of-tasks/pinocchio/pull/2315))
Expand Down
2 changes: 1 addition & 1 deletion examples/simulation-closed-kinematic-chains.py
Original file line number Diff line number Diff line change
Expand Up @@ -160,7 +160,7 @@
t = 0
mu_sim = 1e-10
constraint_model.corrector.Kp[:] = 10
constraint_model.corrector.Kd = 2.0 * np.sqrt(constraint_model.corrector.Kp)
constraint_model.corrector.Kd[:] = 2.0 * np.sqrt(constraint_model.corrector.Kp)
pin.initConstraintDynamics(model, data, [constraint_model])
prox_settings = pin.ProximalSettings(1e-8, mu_sim, 10)

Expand Down
4 changes: 0 additions & 4 deletions examples/simulation-contact-dynamics.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,6 @@
# Conversion with str seems to be necessary when executing this file with ipython
pinocchio_model_dir = join(dirname(dirname(str(abspath(__file__)))), "models")

# Load the URDF model.
# Conversion with str seems to be necessary when executing this file with ipython
pinocchio_model_dir = join(dirname(dirname(str(abspath(__file__)))), "models")

model_path = join(pinocchio_model_dir, "example-robot-data/robots")
mesh_dir = pinocchio_model_dir
urdf_filename = "talos_reduced.urdf"
Expand Down
5 changes: 3 additions & 2 deletions examples/talos-simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,9 @@

import numpy as np
import pinocchio
from example_robot_data import loadTalos
import example_robot_data

robot = loadTalos()
robot = example_robot_data.load("talos")
model = robot.model
data = robot.data

Expand Down Expand Up @@ -35,6 +35,7 @@
for j, frame_id in enumerate(foot_frame_ids):
contact_model_lf1 = pinocchio.RigidConstraintModel(
pinocchio.ContactType.CONTACT_6D,
robot.model,
foot_joint_ids[j],
robot.model.frames[frame_id].placement,
0,
Expand Down
3 changes: 2 additions & 1 deletion unittest/mjcf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -464,7 +464,8 @@ BOOST_AUTO_TEST_CASE(parse_default_class)
pinocchio::Model::JointIndex idx;
pinocchio::Inertia inertia(0, Vector3(0.0, 0., 0.0), Matrix3::Identity());
idx = model_u.addJoint(
model_u.njoints - 1, pinocchio::JointModelSpherical(), pinocchio::SE3::Identity(), "joint3");
size_t(model_u.njoints - 1), pinocchio::JointModelSpherical(), pinocchio::SE3::Identity(),
"joint3");
model_u.appendBodyToJoint(idx, inertia);

for (int i = 0; i < model_m.njoints; i++)
Expand Down

0 comments on commit da40f76

Please sign in to comment.