GCC Code Coverage Report


Directory: ./
File: benchmark/factory/arm.hpp
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 0 24 0.0%
Branches: 0 68 0.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2025, University of Edinburgh, LAAS-CNRS,
5 // Heriot-Watt University
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
8 ///////////////////////////////////////////////////////////////////////////////
9
10 #ifndef CROCODDYL_ARM_FACTORY_HPP_
11 #define CROCODDYL_ARM_FACTORY_HPP_
12
13 #include <example-robot-data/path.hpp>
14 #include <pinocchio/algorithm/model.hpp>
15 #include <pinocchio/parsers/srdf.hpp>
16 #include <pinocchio/parsers/urdf.hpp>
17
18 #include "crocoddyl/core/costs/cost-sum.hpp"
19 #include "crocoddyl/core/costs/residual.hpp"
20 #include "crocoddyl/core/integrator/euler.hpp"
21 #include "crocoddyl/core/mathbase.hpp"
22 #include "crocoddyl/core/residuals/control.hpp"
23 #include "crocoddyl/multibody/actions/free-fwddyn.hpp"
24 #include "crocoddyl/multibody/actuations/full.hpp"
25 #include "crocoddyl/multibody/residuals/frame-placement.hpp"
26 #include "crocoddyl/multibody/residuals/state.hpp"
27 #include "crocoddyl/multibody/states/multibody.hpp"
28
29 namespace crocoddyl {
30 namespace benchmark {
31
32 template <typename Scalar>
33 void build_arm_action_models(
34 std::shared_ptr<crocoddyl::ActionModelAbstractTpl<Scalar> >& runningModel,
35 std::shared_ptr<crocoddyl::ActionModelAbstractTpl<Scalar> >&
36 terminalModel) {
37 typedef typename crocoddyl::DifferentialActionModelFreeFwdDynamicsTpl<Scalar>
38 DifferentialActionModelFreeFwdDynamics;
39 typedef typename crocoddyl::IntegratedActionModelEulerTpl<Scalar>
40 IntegratedActionModelEuler;
41 typedef typename crocoddyl::ActuationModelFullTpl<Scalar> ActuationModelFull;
42 typedef typename crocoddyl::CostModelSumTpl<Scalar> CostModelSum;
43 typedef typename crocoddyl::CostModelAbstractTpl<Scalar> CostModelAbstract;
44 typedef typename crocoddyl::CostModelResidualTpl<Scalar> CostModelResidual;
45 typedef typename crocoddyl::ResidualModelStateTpl<Scalar> ResidualModelState;
46 typedef typename crocoddyl::ResidualModelFramePlacementTpl<Scalar>
47 ResidualModelFramePlacement;
48 typedef typename crocoddyl::ResidualModelControlTpl<Scalar>
49 ResidualModelControl;
50 typedef typename crocoddyl::MathBaseTpl<Scalar>::Vector3s Vector3s;
51 typedef typename crocoddyl::MathBaseTpl<Scalar>::Matrix3s Matrix3s;
52
53 // because urdf is not supported with all scalar types.
54 pinocchio::ModelTpl<double> modeld;
55 pinocchio::urdf::buildModel(EXAMPLE_ROBOT_DATA_MODEL_DIR
56 "/talos_data/robots/talos_left_arm.urdf",
57 modeld);
58 pinocchio::srdf::loadReferenceConfigurations(
59 modeld, EXAMPLE_ROBOT_DATA_MODEL_DIR "/talos_data/srdf/talos.srdf",
60 false);
61
62 pinocchio::ModelTpl<Scalar> model(modeld.cast<Scalar>());
63
64 std::shared_ptr<crocoddyl::StateMultibodyTpl<Scalar> > state =
65 std::make_shared<crocoddyl::StateMultibodyTpl<Scalar> >(
66 std::make_shared<pinocchio::ModelTpl<Scalar> >(model));
67
68 std::shared_ptr<CostModelAbstract> goalTrackingCost =
69 std::make_shared<CostModelResidual>(
70 state, std::make_shared<ResidualModelFramePlacement>(
71 state, model.getFrameId("gripper_left_joint"),
72 pinocchio::SE3Tpl<Scalar>(
73 Matrix3s::Identity(),
74 Vector3s(Scalar(0.), Scalar(0.), Scalar(0.4)))));
75 std::shared_ptr<CostModelAbstract> xRegCost =
76 std::make_shared<CostModelResidual>(
77 state, std::make_shared<ResidualModelState>(state));
78 std::shared_ptr<CostModelAbstract> uRegCost =
79 std::make_shared<CostModelResidual>(
80 state, std::make_shared<ResidualModelControl>(state));
81
82 // Create a cost model per the running and terminal action model.
83 std::shared_ptr<CostModelSum> runningCostModel =
84 std::make_shared<CostModelSum>(state);
85 std::shared_ptr<CostModelSum> terminalCostModel =
86 std::make_shared<CostModelSum>(state);
87
88 // Then let's added the running and terminal cost functions
89 runningCostModel->addCost("gripperPose", goalTrackingCost, Scalar(1));
90 runningCostModel->addCost("xReg", xRegCost, Scalar(1e-1));
91 runningCostModel->addCost("uReg", uRegCost, Scalar(1e-1));
92 terminalCostModel->addCost("gripperPose", goalTrackingCost, Scalar(1e3));
93
94 // We define an actuation model
95 std::shared_ptr<ActuationModelFull> actuation =
96 std::make_shared<ActuationModelFull>(state);
97
98 // Next, we need to create an action model for running and terminal knots. The
99 // forward dynamics (computed using ABA) are implemented
100 // inside DifferentialActionModelFullyActuated.
101 std::shared_ptr<DifferentialActionModelFreeFwdDynamics> runningDAM =
102 std::make_shared<DifferentialActionModelFreeFwdDynamics>(
103 state, actuation, runningCostModel);
104
105 runningModel =
106 std::make_shared<IntegratedActionModelEuler>(runningDAM, Scalar(1e-2));
107 terminalModel =
108 std::make_shared<IntegratedActionModelEuler>(runningDAM, Scalar(0.));
109 }
110
111 } // namespace benchmark
112 } // namespace crocoddyl
113
114 #endif // CROCODDYL_ARM_FACTORY_HPP_
115