Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Replaced parent by parentJoint introduced in Pinocchio 3 #1271

Merged
merged 2 commits into from
Jun 24, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/).

## [Unreleased]

* Replaced parent by parentJoint (which was introduced in Pinocchio 3) in https://github.com/loco-3d/crocoddyl/pull/1271
* Introduced the notion of terminal dimension, residuals and constraints in https://github.com/loco-3d/crocoddyl/pull/1269
* General clean ups about std::size_t in https://github.com/loco-3d/crocoddyl/pull/1265
* Fixed issues in LQR extensions in https://github.com/loco-3d/crocoddyl/pull/1263
Expand Down
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -103,8 +103,8 @@ if(BUILD_PYTHON_INTERFACE)
add_project_dependency(eigenpy 3.1.0 REQUIRED PKG_CONFIG_REQUIRES
"eigenpy >= 3.1.0")
endif(BUILD_PYTHON_INTERFACE)
add_project_dependency(pinocchio 2.6.20 REQUIRED PKG_CONFIG_REQUIRES
"pinocchio >= 2.6.20")
add_project_dependency(pinocchio 3.0.0 REQUIRED PKG_CONFIG_REQUIRES
"pinocchio >= 3.0.0")
if(BUILD_EXAMPLES
OR BUILD_TESTING
OR BUILD_BENCHMARK)
Expand Down
4 changes: 2 additions & 2 deletions include/crocoddyl/multibody/contacts/contact-1d.hxx
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
///////////////////////////////////////////////////////////////////////////////
// BSD 3-Clause License
//
// Copyright (C) 2020-2023, LAAS-CNRS, University of Edinburgh,
// Copyright (C) 2020-2024, LAAS-CNRS, University of Edinburgh,
// Heriot-Watt University
// Copyright note valid unless otherwise stated in individual files.
// All rights reserved.
Expand Down Expand Up @@ -110,7 +110,7 @@ void ContactModel1DTpl<Scalar>::calcDiff(
const Eigen::Ref<const VectorXs>&) {
Data* d = static_cast<Data*>(data.get());
const pinocchio::JointIndex joint =
state_->get_pinocchio()->frames[d->frame].parent;
state_->get_pinocchio()->frames[d->frame].parentJoint;
pinocchio::getJointAccelerationDerivatives(
*state_->get_pinocchio().get(), *d->pinocchio, joint, pinocchio::LOCAL,
d->v_partial_dq, d->a_partial_dq, d->a_partial_dv, d->a_partial_da);
Expand Down
4 changes: 2 additions & 2 deletions include/crocoddyl/multibody/contacts/contact-2d.hxx
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
///////////////////////////////////////////////////////////////////////////////
// BSD 3-Clause License
//
// Copyright (C) 2020-2023, LAAS-CNRS, University of Edinburgh,
// Copyright (C) 2020-2024, LAAS-CNRS, University of Edinburgh,
// Heriot-Watt University
// Copyright note valid unless otherwise stated in individual files.
// All rights reserved.
Expand Down Expand Up @@ -73,7 +73,7 @@ void ContactModel2DTpl<Scalar>::calcDiff(
const Eigen::Ref<const VectorXs>&) {
Data* d = static_cast<Data*>(data.get());
const pinocchio::JointIndex joint =
state_->get_pinocchio()->frames[d->frame].parent;
state_->get_pinocchio()->frames[d->frame].parentJoint;
pinocchio::getJointAccelerationDerivatives(
*state_->get_pinocchio().get(), *d->pinocchio, joint, pinocchio::LOCAL,
d->v_partial_dq, d->a_partial_dq, d->a_partial_dv, d->a_partial_da);
Expand Down
4 changes: 2 additions & 2 deletions include/crocoddyl/multibody/contacts/contact-3d.hxx
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
///////////////////////////////////////////////////////////////////////////////
// BSD 3-Clause License
//
// Copyright (C) 2019-2023, LAAS-CNRS, University of Edinburgh,
// Copyright (C) 2019-2024, LAAS-CNRS, University of Edinburgh,
// Heriot-Watt University
// Copyright note valid unless otherwise stated in individual files.
// All rights reserved.
Expand Down Expand Up @@ -106,7 +106,7 @@ void ContactModel3DTpl<Scalar>::calcDiff(
const Eigen::Ref<const VectorXs>&) {
Data* d = static_cast<Data*>(data.get());
const pinocchio::JointIndex joint =
state_->get_pinocchio()->frames[d->frame].parent;
state_->get_pinocchio()->frames[d->frame].parentJoint;
pinocchio::getJointAccelerationDerivatives(
*state_->get_pinocchio().get(), *d->pinocchio, joint, pinocchio::LOCAL,
d->v_partial_dq, d->a_partial_dq, d->a_partial_dv, d->a_partial_da);
Expand Down
4 changes: 2 additions & 2 deletions include/crocoddyl/multibody/contacts/contact-6d.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
///////////////////////////////////////////////////////////////////////////////
// BSD 3-Clause License
//
// Copyright (C) 2019-2023, LAAS-CNRS, University of Edinburgh,
// Copyright (C) 2019-2024, LAAS-CNRS, University of Edinburgh,
// Heriot-Watt University
// Copyright note valid unless otherwise stated in individual files.
// All rights reserved.
Expand Down Expand Up @@ -110,7 +110,7 @@ void ContactModel6DTpl<Scalar>::calcDiff(
const Eigen::Ref<const VectorXs>&) {
Data* d = static_cast<Data*>(data.get());
const pinocchio::JointIndex joint =
state_->get_pinocchio()->frames[d->frame].parent;
state_->get_pinocchio()->frames[d->frame].parentJoint;
pinocchio::getJointAccelerationDerivatives(
*state_->get_pinocchio().get(), *d->pinocchio, joint, pinocchio::LOCAL,
d->v_partial_dq, d->a_partial_dq, d->a_partial_dv, d->a_partial_da);
Expand Down
6 changes: 3 additions & 3 deletions include/crocoddyl/multibody/contacts/multiple-contacts.hxx
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
///////////////////////////////////////////////////////////////////////////////
// BSD 3-Clause License
//
// Copyright (C) 2019-2023, LAAS-CNRS, University of Edinburgh,
// Copyright (C) 2019-2024, LAAS-CNRS, University of Edinburgh,
// Heriot-Watt University
// Copyright note valid unless otherwise stated in individual files.
// All rights reserved.
Expand Down Expand Up @@ -251,7 +251,7 @@ void ContactModelMultipleTpl<Scalar>::updateForce(
force.segment(nc, nc_i);
m_i->contact->updateForce(d_i, force_i);
const pinocchio::JointIndex joint =
state_->get_pinocchio()->frames[d_i->frame].parent;
state_->get_pinocchio()->frames[d_i->frame].parentJoint;
data->fext[joint] = d_i->fext;
} else {
m_i->contact->setZeroForce(d_i);
Expand All @@ -272,7 +272,7 @@ void ContactModelMultipleTpl<Scalar>::updateForce(
force.segment(nc, nc_i);
m_i->contact->updateForce(d_i, force_i);
const pinocchio::JointIndex joint =
state_->get_pinocchio()->frames[d_i->frame].parent;
state_->get_pinocchio()->frames[d_i->frame].parentJoint;
data->fext[joint] = d_i->fext;
nc += nc_i;
} else {
Expand Down
4 changes: 2 additions & 2 deletions include/crocoddyl/multibody/impulses/impulse-3d.hxx
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
///////////////////////////////////////////////////////////////////////////////
// BSD 3-Clause License
//
// Copyright (C) 2019-2023, LAAS-CNRS, University of Edinburgh,
// Copyright (C) 2019-2024, LAAS-CNRS, University of Edinburgh,
// Heriot-Watt University
// Copyright note valid unless otherwise stated in individual files.
// All rights reserved.
Expand Down Expand Up @@ -54,7 +54,7 @@ void ImpulseModel3DTpl<Scalar>::calcDiff(
const Eigen::Ref<const VectorXs>&) {
boost::shared_ptr<Data> d = boost::static_pointer_cast<Data>(data);
const pinocchio::JointIndex joint =
state_->get_pinocchio()->frames[d->frame].parent;
state_->get_pinocchio()->frames[d->frame].parentJoint;
pinocchio::getJointVelocityDerivatives(*state_->get_pinocchio().get(),
*d->pinocchio, joint, pinocchio::LOCAL,
d->v_partial_dq, d->v_partial_dv);
Expand Down
4 changes: 2 additions & 2 deletions include/crocoddyl/multibody/impulses/impulse-6d.hxx
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
///////////////////////////////////////////////////////////////////////////////
// BSD 3-Clause License
//
// Copyright (C) 2019-2023, LAAS-CNRS, University of Edinburgh,
// Copyright (C) 2019-2024, LAAS-CNRS, University of Edinburgh,
// Heriot-Watt University
// Copyright note valid unless otherwise stated in individual files.
// All rights reserved.
Expand Down Expand Up @@ -52,7 +52,7 @@ void ImpulseModel6DTpl<Scalar>::calcDiff(
const Eigen::Ref<const VectorXs>&) {
boost::shared_ptr<Data> d = boost::static_pointer_cast<Data>(data);
const pinocchio::JointIndex joint =
state_->get_pinocchio()->frames[d->frame].parent;
state_->get_pinocchio()->frames[d->frame].parentJoint;
pinocchio::getJointVelocityDerivatives(*state_->get_pinocchio().get(),
*d->pinocchio, joint, pinocchio::LOCAL,
d->v_partial_dq, d->v_partial_dv);
Expand Down
4 changes: 2 additions & 2 deletions include/crocoddyl/multibody/impulses/multiple-impulses.hxx
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
///////////////////////////////////////////////////////////////////////////////
// BSD 3-Clause License
//
// Copyright (C) 2019-2023, LAAS-CNRS, University of Edinburgh,
// Copyright (C) 2019-2024, LAAS-CNRS, University of Edinburgh,
// Heriot-Watt University
// Copyright note valid unless otherwise stated in individual files.
// All rights reserved.
Expand Down Expand Up @@ -183,7 +183,7 @@ void ImpulseModelMultipleTpl<Scalar>::updateForce(
force.segment(nc, nc_i);
m_i->impulse->updateForce(d_i, force_i);
const pinocchio::JointIndex joint =
state_->get_pinocchio()->frames[d_i->frame].parent;
state_->get_pinocchio()->frames[d_i->frame].parentJoint;
data->fext[joint] = d_i->fext;
nc += nc_i;
} else {
Expand Down
12 changes: 6 additions & 6 deletions unittest/bindings/factory.py
Original file line number Diff line number Diff line change
Expand Up @@ -1101,7 +1101,7 @@ def __init__(self, model, collector):
self.fXj = (
model.state.pinocchio.frames[model._frame_id].placement.inverse().action
)
self.joint = model.state.pinocchio.frames[model._frame_id].parent
self.joint = model.state.pinocchio.frames[model._frame_id].parentJoint


class Contact1DModelDerived(crocoddyl.ContactModelAbstract):
Expand Down Expand Up @@ -1151,7 +1151,7 @@ def calc(self, data, x):
data.a0[0] = np.dot(np.dot(self.Raxis, oRf), data.a0_local)[2]

def calcDiff(self, data, x):
joint = self.state.pinocchio.frames[self.id].parent
joint = self.state.pinocchio.frames[self.id].parentJoint
(
v_partial_dq,
a_partial_dq,
Expand Down Expand Up @@ -1271,7 +1271,7 @@ def calc(self, data, x):
data.a0[:] = np.dot(oRf, data.a0_local)

def calcDiff(self, data, x):
joint = self.state.pinocchio.frames[self.id].parent
joint = self.state.pinocchio.frames[self.id].parentJoint
(
v_partial_dq,
a_partial_dq,
Expand Down Expand Up @@ -1425,7 +1425,7 @@ def calc(self, data, x):
data.a0[:] = data.lwaMl.act(data.a0_local).vector

def calcDiff(self, data, x):
joint = self.state.pinocchio.frames[self.id].parent
joint = self.state.pinocchio.frames[self.id].parentJoint
(
v_partial_dq,
a_partial_dq,
Expand Down Expand Up @@ -1536,7 +1536,7 @@ def calc(self, data, x):
)

def calcDiff(self, data, x):
joint = self.state.pinocchio.frames[self.id].parent
joint = self.state.pinocchio.frames[self.id].parentJoint
v_partial_dq, _ = pinocchio.getJointVelocityDerivatives(
self.state.pinocchio, data.pinocchio, joint, pinocchio.ReferenceFrame.LOCAL
)
Expand Down Expand Up @@ -1613,7 +1613,7 @@ def calc(self, data, x):
data.Jc[:, :] = np.dot(data.lwaMl.toActionMatrix(), data.fJf)

def calcDiff(self, data, x):
joint = self.state.pinocchio.frames[self.id].parent
joint = self.state.pinocchio.frames[self.id].parentJoint
v_partial_dq, _ = pinocchio.getJointVelocityDerivatives(
self.state.pinocchio, data.pinocchio, joint, pinocchio.ReferenceFrame.LOCAL
)
Expand Down
8 changes: 4 additions & 4 deletions unittest/factory/cost.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
///////////////////////////////////////////////////////////////////////////////
// BSD 3-Clause License
//
// Copyright (C) 2019-2023, LAAS-CNRS, University of Edinburgh,
// Copyright (C) 2019-2024, LAAS-CNRS, University of Edinburgh,
// Heriot-Watt University
// Copyright note valid unless otherwise stated in individual files.
// All rights reserved.
Expand Down Expand Up @@ -229,14 +229,14 @@ boost::shared_ptr<crocoddyl::CostModelAbstract> CostModelFactory::create(
pinocchio::GeomIndex ig_frame =
geometry->addGeometryObject(pinocchio::GeometryObject(
"frame", frame_index,
state->get_pinocchio()->frames[frame_index].parent,
state->get_pinocchio()->frames[frame_index].parentJoint,
CollisionGeometryPtr(new hpp::fcl::Capsule(0, alpha)), frame_SE3));
pinocchio::GeomIndex ig_obs =
geometry->addGeometryObject(pinocchio::GeometryObject(
"obs", state->get_pinocchio()->getFrameId("universe"),
state->get_pinocchio()
->frames[state->get_pinocchio()->getFrameId("universe")]
.parent,
.parentJoint,
CollisionGeometryPtr(new hpp::fcl::Capsule(0, beta)),
frame_SE3_obstacle));
geometry->addCollisionPair(pinocchio::CollisionPair(ig_frame, ig_obs));
Expand All @@ -247,7 +247,7 @@ boost::shared_ptr<crocoddyl::CostModelAbstract> CostModelFactory::create(
state, boost::make_shared<crocoddyl::ActivationModelQuad>(3),
boost::make_shared<crocoddyl::ResidualModelPairCollision>(
state, nu, geometry, 0,
state->get_pinocchio()->frames[frame_index].parent));
state->get_pinocchio()->frames[frame_index].parentJoint));
break;
default:
throw_pretty(__FILE__ ": Wrong CostModelTypes::Type given");
Expand Down
9 changes: 5 additions & 4 deletions unittest/factory/residual.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
///////////////////////////////////////////////////////////////////////////////
// BSD 3-Clause License
//
// Copyright (C) 2021-2022, University of Edinburgh, LAAS-CNRS
// Copyright (C) 2021-2024, University of Edinburgh, LAAS-CNRS,
// Heriot-Watt University
// Copyright note valid unless otherwise stated in individual files.
// All rights reserved.
///////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -91,14 +92,14 @@ ResidualModelFactory::create(ResidualModelTypes::Type residual_type,
pinocchio::GeomIndex ig_frame =
geometry->addGeometryObject(pinocchio::GeometryObject(
"frame", frame_index,
state->get_pinocchio()->frames[frame_index].parent,
state->get_pinocchio()->frames[frame_index].parentJoint,
std::make_shared<hpp::fcl::Sphere>(0), frame_SE3));
pinocchio::GeomIndex ig_obs =
geometry->addGeometryObject(pinocchio::GeometryObject(
"obs", state->get_pinocchio()->getFrameId("universe"),
state->get_pinocchio()
->frames[state->get_pinocchio()->getFrameId("universe")]
.parent,
.parentJoint,
std::make_shared<hpp::fcl::Sphere>(0), frame_SE3_obstacle));
geometry->addCollisionPair(pinocchio::CollisionPair(ig_frame, ig_obs));
#endif // PINOCCHIO_WITH_HPP_FCL
Expand Down Expand Up @@ -148,7 +149,7 @@ ResidualModelFactory::create(ResidualModelTypes::Type residual_type,
case ResidualModelTypes::ResidualModelPairCollision:
residual = boost::make_shared<crocoddyl::ResidualModelPairCollision>(
state, nu, geometry, 0,
state->get_pinocchio()->frames[frame_index].parent);
state->get_pinocchio()->frames[frame_index].parentJoint);
break;
#endif // PINOCCHIO_WITH_HPP_FCL
default:
Expand Down
Loading