Skip to content

Commit 8f25c3a

Browse files
nim65sabussy-aldebaranManifoldFR
authored
Crocoddyl v3: boost -> std pointers (#278)
* nix flake: clean * nix flake update override with NixOS/nixpkgs#390922 * fix pixi warnings * pixi: bump crocoddyl Co-authored-by: Antoine <116184195+abussy-aldebaran@users.noreply.github.com> * pixi update * CMake: require crocoddyl v3 * croco v3: boost -> std pointers Co-authored-by: Wilson <21089660+manifoldfr@users.noreply.github.com> * add changelog entry --------- Co-authored-by: Antoine <116184195+abussy-aldebaran@users.noreply.github.com> Co-authored-by: Wilson <21089660+manifoldfr@users.noreply.github.com>
1 parent db746ec commit 8f25c3a

File tree

19 files changed

+4503
-5721
lines changed

19 files changed

+4503
-5721
lines changed

CHANGELOG.md

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,10 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
77

88
## [Unreleased]
99

10+
### Changed
11+
12+
- Update for crocoddyl v3: boost -> std pointers ([#278](https://github.com/Simple-Robotics/aligator/issues/278))
13+
1014
## [0.11.0] - 2025-03-17
1115

1216
### Changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -459,7 +459,7 @@ if(DOWNLOAD_TRACY)
459459
endif()
460460

461461
if(BUILD_CROCODDYL_COMPAT)
462-
ADD_PROJECT_DEPENDENCY(crocoddyl REQUIRED)
462+
ADD_PROJECT_DEPENDENCY(crocoddyl 3.0.0 REQUIRED)
463463
add_subdirectory(src/compat/crocoddyl)
464464
endif()
465465

bench/croc-talos-arm.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ static void BM_croc_fddp(benchmark::State &state) {
3939
const double croc_tol = TOL * TOL * (double)nsteps;
4040
solver.set_th_stop(croc_tol);
4141
if (verbose)
42-
solver.setCallbacks({boost::make_shared<croc::CallbackVerbose>()});
42+
solver.setCallbacks({std::make_shared<croc::CallbackVerbose>()});
4343

4444
for (auto _ : state) {
4545
solver.solve(xs_i, us_i, maxiters);

bindings/python/src/compat/expose-croco-compat.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ void exposeCrocoddylCompat() {
3232

3333
bp::class_<ActionModelWrapper, bp::bases<context::StageModel>>(
3434
"ActionModelWrapper", "Wrapper for Crocoddyl action models.",
35-
bp::init<boost::shared_ptr<CrocActionModel>>(bp::args("action_model")))
35+
bp::init<shared_ptr<CrocActionModel>>(bp::args("action_model")))
3636
.def_readonly("action_model", &ActionModelWrapper::action_model_,
3737
"Underlying Crocoddyl ActionModel.")
3838
.def(PolymorphicMultiBaseVisitor<context::StageModel>());
@@ -51,8 +51,7 @@ void exposeCrocoddylCompat() {
5151

5252
bp::class_<StateWrapper, bp::bases<context::Manifold>>(
5353
"StateWrapper", "Wrapper for a Crocoddyl state.", bp::no_init)
54-
.def(
55-
bp::init<boost::shared_ptr<StateAbstract>>(bp::args("self", "state")))
54+
.def(bp::init<shared_ptr<StateAbstract>>(bp::args("self", "state")))
5655
.def_readonly("croc_state", &StateWrapper::croc_state)
5756
.def(PolymorphicMultiBaseVisitor<context::Manifold>());
5857
}

examples/croc-talos-arm.cpp

Lines changed: 20 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ void makeTalosArm(pin::Model &model) {
2222
pin::urdf::buildModel(talos_arm_path, model);
2323
}
2424

25-
boost::shared_ptr<croc::ShootingProblem>
25+
std::shared_ptr<croc::ShootingProblem>
2626
defineCrocoddylProblem(std::size_t nsteps) {
2727
using croc::ActuationModelFull;
2828
using croc::CostModelResidual;
@@ -36,67 +36,65 @@ defineCrocoddylProblem(std::size_t nsteps) {
3636
using DAM = croc::DifferentialActionModelFreeFwdDynamics;
3737
using ActionModel = croc::ActionModelAbstract;
3838

39-
auto rmodel = boost::make_shared<pin::Model>();
39+
auto rmodel = std::make_shared<pin::Model>();
4040
makeTalosArm(*rmodel);
41-
auto state = boost::make_shared<StateMultibody>(rmodel);
41+
auto state = std::make_shared<StateMultibody>(rmodel);
4242

43-
auto runningCost = boost::make_shared<CostModelSum>(state);
44-
auto terminalCost = boost::make_shared<CostModelSum>(state);
43+
auto runningCost = std::make_shared<CostModelSum>(state);
44+
auto terminalCost = std::make_shared<CostModelSum>(state);
4545

4646
pin::JointIndex joint_id = rmodel->getFrameId("gripper_left_joint");
4747
pin::SE3 target_frame;
4848
target_frame.setIdentity();
4949
target_frame.translation() << 0., 0., 0.4;
5050

51-
auto framePlacementResidual = boost::make_shared<ResidualModelFramePlacement>(
51+
auto framePlacementResidual = std::make_shared<ResidualModelFramePlacement>(
5252
state, joint_id, target_frame);
5353

5454
auto goalTrackingCost =
55-
boost::make_shared<CostModelResidual>(state, framePlacementResidual);
56-
auto xregCost = boost::make_shared<CostModelResidual>(
57-
state, boost::make_shared<ResidualModelState>(state));
58-
auto uregCost = boost::make_shared<CostModelResidual>(
59-
state, boost::make_shared<ResidualModelControl>(state));
55+
std::make_shared<CostModelResidual>(state, framePlacementResidual);
56+
auto xregCost = std::make_shared<CostModelResidual>(
57+
state, std::make_shared<ResidualModelState>(state));
58+
auto uregCost = std::make_shared<CostModelResidual>(
59+
state, std::make_shared<ResidualModelControl>(state));
6060

6161
runningCost->addCost("gripperPose", goalTrackingCost, 1.0);
6262
runningCost->addCost("xReg", xregCost, 1e-4);
6363
runningCost->addCost("uReg", uregCost, 1e-4);
6464

6565
terminalCost->addCost("gripperPose", goalTrackingCost, 1.0);
6666

67-
auto actuationModel = boost::make_shared<ActuationModelFull>(state);
67+
auto actuationModel = std::make_shared<ActuationModelFull>(state);
6868

6969
const double dt = 1e-3;
7070

7171
VectorXd armature(7);
7272
armature << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0;
7373

74-
auto contDyn = boost::make_shared<DAM>(state, actuationModel, runningCost);
74+
auto contDyn = std::make_shared<DAM>(state, actuationModel, runningCost);
7575
contDyn->set_armature(armature);
76-
auto runningModel =
77-
boost::make_shared<IntegratedActionModelEuler>(contDyn, dt);
76+
auto runningModel = std::make_shared<IntegratedActionModelEuler>(contDyn, dt);
7877

79-
auto termContDyn =
80-
boost::make_shared<DAM>(state, actuationModel, terminalCost);
78+
auto termContDyn = std::make_shared<DAM>(state, actuationModel, terminalCost);
8179
termContDyn->set_armature(armature);
8280
auto terminalModel =
83-
boost::make_shared<IntegratedActionModelEuler>(termContDyn, 0.0);
81+
std::make_shared<IntegratedActionModelEuler>(termContDyn, 0.0);
8482

8583
VectorXd q0(rmodel->nq);
8684
q0 << 0.173046, 1.0, -0.52366, 0.0, 0.0, 0.1, -0.005;
8785
VectorXd x0(state->get_nx());
8886
x0 << q0, VectorXd::Zero(rmodel->nv);
8987

90-
std::vector<boost::shared_ptr<ActionModel>> running_models(nsteps,
91-
runningModel);
88+
std::vector<std::shared_ptr<ActionModel>> running_models(nsteps,
89+
runningModel);
9290

93-
auto shooting_problem = boost::make_shared<croc::ShootingProblem>(
91+
auto shooting_problem = std::make_shared<croc::ShootingProblem>(
9492
x0, running_models, terminalModel);
9593
return shooting_problem;
9694
}
9795

9896
void getInitialGuesses(
99-
const boost::shared_ptr<croc::ShootingProblem> &croc_problem,
97+
const std::shared_ptr<croc::ShootingProblem> &croc_problem,
10098
std::vector<Eigen::VectorXd> &xs_i, std::vector<Eigen::VectorXd> &us_i) {
10199
using Eigen::VectorXd;
102100

examples/croc-talos-arm.hpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,9 @@
11
/// @file
22
/// @copyright Copyright (C) 2022 LAAS-CNRS, INRIA
33

4+
#include <memory>
45
#include <vector>
56

6-
#include <boost/shared_ptr.hpp>
7-
87
#include <Eigen/Core>
98

109
#include <pinocchio/multibody/fwd.hpp>
@@ -18,9 +17,9 @@ void makeTalosArm(pin::Model &model);
1817

1918
/// This reimplements the Crocoddyl problem defined in
2019
/// examples/croc_arm_manipulation.py.
21-
boost::shared_ptr<croc::ShootingProblem>
20+
std::shared_ptr<croc::ShootingProblem>
2221
defineCrocoddylProblem(std::size_t nsteps);
2322

2423
void getInitialGuesses(
25-
const boost::shared_ptr<croc::ShootingProblem> &croc_problem,
24+
const std::shared_ptr<croc::ShootingProblem> &croc_problem,
2625
std::vector<Eigen::VectorXd> &xs_i, std::vector<Eigen::VectorXd> &us_i);

flake.lock

Lines changed: 16 additions & 13 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

flake.nix

Lines changed: 0 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -14,36 +14,9 @@
1414
{
1515
pkgs,
1616
self',
17-
system,
1817
...
1918
}:
2019
{
21-
_module.args.pkgs = import inputs.nixpkgs {
22-
inherit system;
23-
overlays = [
24-
(final: prev: {
25-
# Fix aba explicit template instanciation
26-
# Remove this for pinocchio > 3.3.1
27-
pinocchio = prev.pinocchio.overrideAttrs (super: {
28-
patches = (super.patches or [ ]) ++ [
29-
(final.fetchpatch {
30-
url = "https://github.com/stack-of-tasks/pinocchio/pull/2541/commits/23a638ebfb180aa7d4ea75f17e3d89477dcb6509.patch";
31-
hash = "sha256-XIZpq1JK5mY5tv3MqRk/ep6/5cJOjV2gkW1ywLjXUBU=";
32-
})
33-
];
34-
});
35-
# Ignore pinocchio #2563
36-
# Remove this for pinocchio > 3.3.1 && crocoddyl >= 3.0.0
37-
crocoddyl = prev.crocoddyl.overrideAttrs (super: {
38-
cmakeFlags =
39-
(super.cmakeFlags or [ ])
40-
++ final.lib.optionals final.stdenv.hostPlatform.isDarwin [
41-
(final.lib.cmakeFeature "CMAKE_CTEST_ARGUMENTS" "--exclude-regex;test_pybinds_*")
42-
];
43-
});
44-
})
45-
];
46-
};
4720
apps.default = {
4821
type = "app";
4922
program = pkgs.python3.withPackages (_: [ self'.packages.default ]);

include/aligator/compat/crocoddyl/action-model-wrap.hpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -47,10 +47,9 @@ struct ActionModelWrapperTpl : StageModelTpl<Scalar> {
4747
using DynDataWrap = DynamicsDataWrapperTpl<Scalar>;
4848
using Manifold = ManifoldAbstractTpl<Scalar>;
4949

50-
boost::shared_ptr<CrocActionModel> action_model_;
50+
shared_ptr<CrocActionModel> action_model_;
5151

52-
explicit ActionModelWrapperTpl(
53-
boost::shared_ptr<CrocActionModel> action_model);
52+
explicit ActionModelWrapperTpl(shared_ptr<CrocActionModel> action_model);
5453

5554
bool hasDynModel() const override { return false; }
5655

@@ -81,7 +80,7 @@ struct ActionDataWrapperTpl : public StageDataTpl<Scalar> {
8180
using CrocActionData = crocoddyl::ActionDataAbstractTpl<Scalar>;
8281
using DynamicsDataWrapper = DynamicsDataWrapperTpl<Scalar>;
8382

84-
boost::shared_ptr<CrocActionData> croc_action_data;
83+
shared_ptr<CrocActionData> croc_action_data;
8584

8685
ActionDataWrapperTpl(const ActionModelWrapperTpl<Scalar> &croc_action_model);
8786

include/aligator/compat/crocoddyl/action-model-wrap.hxx

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@ namespace croc {
1212

1313
template <typename Scalar>
1414
ActionModelWrapperTpl<Scalar>::ActionModelWrapperTpl(
15-
boost::shared_ptr<CrocActionModel> action_model)
15+
shared_ptr<CrocActionModel> action_model)
1616
: Base(CostAbstract{StateWrapper{action_model->get_state()},
1717
int(action_model->get_nu())},
1818
NoOpDynamics<Scalar>{StateWrapper{action_model->get_state()},

0 commit comments

Comments
 (0)