@@ -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>
2626defineCrocoddylProblem (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
9896void 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
0 commit comments