GCC Code Coverage Report


Directory: ./
File: benchmark/factory/arm-kinova.hpp
Date: 2025-05-13 10:30:51
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_KINOVA_FACTORY_HPP_
11 #define CROCODDYL_ARM_KINOVA_FACTORY_HPP_
12
13 #include <example-robot-data/path.hpp>
14 #include <pinocchio/parsers/srdf.hpp>
15 #include <pinocchio/parsers/urdf.hpp>
16
17 #include "crocoddyl/core/costs/cost-sum.hpp"
18 #include "crocoddyl/core/costs/residual.hpp"
19 #include "crocoddyl/core/integrator/euler.hpp"
20 #include "crocoddyl/core/residuals/control.hpp"
21 #include "crocoddyl/multibody/actions/free-fwddyn.hpp"
22 #include "crocoddyl/multibody/actuations/full.hpp"
23 #include "crocoddyl/multibody/residuals/frame-placement.hpp"
24 #include "crocoddyl/multibody/residuals/state.hpp"
25 #include "crocoddyl/multibody/states/multibody.hpp"
26
27 namespace crocoddyl {
28 namespace benchmark {
29
30 template <typename Scalar>
31 void build_arm_kinova_action_models(
32 std::shared_ptr<crocoddyl::ActionModelAbstractTpl<Scalar> >& runningModel,
33 std::shared_ptr<crocoddyl::ActionModelAbstractTpl<Scalar> >&
34 terminalModel) {
35 typedef typename crocoddyl::DifferentialActionModelFreeFwdDynamicsTpl<Scalar>
36 DifferentialActionModelFreeFwdDynamics;
37 typedef typename crocoddyl::IntegratedActionModelEulerTpl<Scalar>
38 IntegratedActionModelEuler;
39 typedef typename crocoddyl::CostModelSumTpl<Scalar> CostModelSum;
40 typedef typename crocoddyl::ActuationModelFullTpl<Scalar> ActuationModelFull;
41 typedef typename crocoddyl::CostModelAbstractTpl<Scalar> CostModelAbstract;
42 typedef typename crocoddyl::CostModelResidualTpl<Scalar> CostModelResidual;
43 typedef typename crocoddyl::ResidualModelFramePlacementTpl<Scalar>
44 ResidualModelFramePlacement;
45 typedef typename crocoddyl::ResidualModelStateTpl<Scalar> ResidualModelState;
46 typedef typename crocoddyl::ResidualModelControlTpl<Scalar>
47 ResidualModelControl;
48 typedef typename crocoddyl::MathBaseTpl<Scalar>::Vector3s Vector3s;
49 typedef typename crocoddyl::MathBaseTpl<Scalar>::Matrix3s Matrix3s;
50
51 // because urdf is not supported with all scalar types.
52 pinocchio::ModelTpl<double> modeld;
53 pinocchio::urdf::buildModel(EXAMPLE_ROBOT_DATA_MODEL_DIR
54 "/kinova_description/robots/kinova.urdf",
55 modeld);
56 pinocchio::srdf::loadReferenceConfigurations(
57 modeld,
58 EXAMPLE_ROBOT_DATA_MODEL_DIR "/kinova_description/srdf/kinova.srdf",
59 false);
60 pinocchio::ModelTpl<Scalar> model(modeld.cast<Scalar>());
61
62 std::shared_ptr<crocoddyl::StateMultibodyTpl<Scalar> > state =
63 std::make_shared<crocoddyl::StateMultibodyTpl<Scalar> >(
64 std::make_shared<pinocchio::ModelTpl<Scalar> >(model));
65
66 std::shared_ptr<CostModelAbstract> goalTrackingCost =
67 std::make_shared<CostModelResidual>(
68 state, std::make_shared<ResidualModelFramePlacement>(
69 state, model.getFrameId("j2s6s200_end_effector"),
70 pinocchio::SE3Tpl<Scalar>(
71 Matrix3s::Identity(),
72 Vector3s(Scalar(0), Scalar(0), Scalar(.4)))));
73 std::shared_ptr<CostModelAbstract> xRegCost =
74 std::make_shared<CostModelResidual>(
75 state, std::make_shared<ResidualModelState>(state));
76 std::shared_ptr<CostModelAbstract> uRegCost =
77 std::make_shared<CostModelResidual>(
78 state, std::make_shared<ResidualModelControl>(state));
79
80 // Create a cost model per the running and terminal action model.
81 std::shared_ptr<CostModelSum> runningCostModel =
82 std::make_shared<CostModelSum>(state);
83 std::shared_ptr<CostModelSum> terminalCostModel =
84 std::make_shared<CostModelSum>(state);
85
86 // Then let's added the running and terminal cost functions
87 runningCostModel->addCost("gripperPose", goalTrackingCost, Scalar(1));
88 runningCostModel->addCost("xReg", xRegCost, Scalar(1e-4));
89 runningCostModel->addCost("uReg", uRegCost, Scalar(1e-4));
90 terminalCostModel->addCost("gripperPose", goalTrackingCost, Scalar(1));
91
92 // We define an actuation model
93 std::shared_ptr<ActuationModelFull> actuation =
94 std::make_shared<ActuationModelFull>(state);
95
96 // Next, we need to create an action model for running and terminal knots. The
97 // forward dynamics (computed using ABA) are implemented
98 // inside DifferentialActionModelFullyActuated.
99 std::shared_ptr<DifferentialActionModelFreeFwdDynamics> runningDAM =
100 std::make_shared<DifferentialActionModelFreeFwdDynamics>(
101 state, actuation, runningCostModel);
102
103 // VectorXs armature(state->get_nq());
104 // armature << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.;
105 // runningDAM->set_armature(armature);
106 // terminalDAM->set_armature(armature);
107 runningModel =
108 std::make_shared<IntegratedActionModelEuler>(runningDAM, Scalar(1e-3));
109 terminalModel =
110 std::make_shared<IntegratedActionModelEuler>(runningDAM, Scalar(0.));
111 }
112
113 } // namespace benchmark
114 } // namespace crocoddyl
115
116 #endif // CROCODDYL_ARM_FACTORY_HPP_
117