GCC Code Coverage Report


Directory: ./
File: benchmark/factory/arm.hpp
Date: 2025-01-16 08:47:40
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-2023, 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 boost::shared_ptr<crocoddyl::ActionModelAbstractTpl<Scalar> >& runningModel,
35 boost::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 "/kinova_description/robots/kinova.urdf",
57 modeld);
58 pinocchio::srdf::loadReferenceConfigurations(
59 modeld,
60 EXAMPLE_ROBOT_DATA_MODEL_DIR "/kinova_description/srdf/kinova.srdf",
61 false);
62
63 pinocchio::ModelTpl<Scalar> model(modeld.cast<Scalar>());
64
65 boost::shared_ptr<crocoddyl::StateMultibodyTpl<Scalar> > state =
66 boost::make_shared<crocoddyl::StateMultibodyTpl<Scalar> >(
67 boost::make_shared<pinocchio::ModelTpl<Scalar> >(model));
68
69 boost::shared_ptr<CostModelAbstract> goalTrackingCost =
70 boost::make_shared<CostModelResidual>(
71 state, boost::make_shared<ResidualModelFramePlacement>(
72 state, model.getFrameId("j2s6s200_end_effector"),
73 pinocchio::SE3Tpl<Scalar>(
74 Matrix3s::Identity(),
75 Vector3s(Scalar(0.6), Scalar(0.2), Scalar(0.5)))));
76 boost::shared_ptr<CostModelAbstract> xRegCost =
77 boost::make_shared<CostModelResidual>(
78 state, boost::make_shared<ResidualModelState>(state));
79 boost::shared_ptr<CostModelAbstract> uRegCost =
80 boost::make_shared<CostModelResidual>(
81 state, boost::make_shared<ResidualModelControl>(state));
82
83 // Create a cost model per the running and terminal action model.
84 boost::shared_ptr<CostModelSum> runningCostModel =
85 boost::make_shared<CostModelSum>(state);
86 boost::shared_ptr<CostModelSum> terminalCostModel =
87 boost::make_shared<CostModelSum>(state);
88
89 // Then let's added the running and terminal cost functions
90 runningCostModel->addCost("gripperPose", goalTrackingCost, Scalar(1));
91 runningCostModel->addCost("xReg", xRegCost, Scalar(1e-1));
92 runningCostModel->addCost("uReg", uRegCost, Scalar(1e-1));
93 terminalCostModel->addCost("gripperPose", goalTrackingCost, Scalar(1e3));
94
95 // We define an actuation model
96 boost::shared_ptr<ActuationModelFull> actuation =
97 boost::make_shared<ActuationModelFull>(state);
98
99 // Next, we need to create an action model for running and terminal knots. The
100 // forward dynamics (computed using ABA) are implemented
101 // inside DifferentialActionModelFullyActuated.
102 boost::shared_ptr<DifferentialActionModelFreeFwdDynamics> runningDAM =
103 boost::make_shared<DifferentialActionModelFreeFwdDynamics>(
104 state, actuation, runningCostModel);
105
106 runningModel =
107 boost::make_shared<IntegratedActionModelEuler>(runningDAM, Scalar(1e-2));
108 terminalModel =
109 boost::make_shared<IntegratedActionModelEuler>(runningDAM, Scalar(0.));
110 }
111
112 } // namespace benchmark
113 } // namespace crocoddyl
114
115 #endif // CROCODDYL_ARM_FACTORY_HPP_
116