GCC Code Coverage Report


Directory: ./
File: unittest/factory/impulse_cost.cpp
Date: 2025-02-24 23:41:29
Exec Total Coverage
Lines: 83 93 89.2%
Branches: 76 152 50.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2021-2022, University of Edinburgh, Heriot-Watt University
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
7 ///////////////////////////////////////////////////////////////////////////////
8
9 #include "impulse_cost.hpp"
10
11 #include "action.hpp"
12 #include "crocoddyl/core/costs/residual.hpp"
13 #include "crocoddyl/core/utils/exception.hpp"
14 #include "crocoddyl/multibody/residuals/contact-cop-position.hpp"
15 #include "crocoddyl/multibody/residuals/contact-force.hpp"
16 #include "crocoddyl/multibody/residuals/contact-friction-cone.hpp"
17 #include "crocoddyl/multibody/residuals/contact-wrench-cone.hpp"
18 #include "crocoddyl/multibody/residuals/impulse-com.hpp"
19
20 namespace crocoddyl {
21 namespace unittest {
22
23 const std::vector<ImpulseCostModelTypes::Type> ImpulseCostModelTypes::all(
24 ImpulseCostModelTypes::init_all());
25
26 42 std::ostream& operator<<(std::ostream& os, ImpulseCostModelTypes::Type type) {
27
5/7
✓ Branch 0 taken 6 times.
✓ Branch 1 taken 12 times.
✓ Branch 2 taken 6 times.
✓ Branch 3 taken 12 times.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
✗ Branch 6 not taken.
42 switch (type) {
28 6 case ImpulseCostModelTypes::CostModelResidualImpulseCoM:
29 6 os << "CostModelResidualImpulseCoM";
30 6 break;
31 12 case ImpulseCostModelTypes::CostModelResidualContactForce:
32 12 os << "CostModelResidualContactForce";
33 12 break;
34 6 case ImpulseCostModelTypes::CostModelResidualContactCoPPosition:
35 6 os << "CostModelResidualContactCoPPosition";
36 6 break;
37 12 case ImpulseCostModelTypes::CostModelResidualContactFrictionCone:
38 12 os << "CostModelResidualContactFrictionCone";
39 12 break;
40 6 case ImpulseCostModelTypes::CostModelResidualContactWrenchCone:
41 6 os << "CostModelResidualContactWrenchCone";
42 6 break;
43 case ImpulseCostModelTypes::NbImpulseCostModelTypes:
44 os << "NbImpulseCostModelTypes";
45 break;
46 default:
47 break;
48 }
49 42 return os;
50 }
51
52 42 ImpulseCostModelFactory::ImpulseCostModelFactory() {}
53 42 ImpulseCostModelFactory::~ImpulseCostModelFactory() {}
54
55 42 std::shared_ptr<crocoddyl::ActionModelAbstract> ImpulseCostModelFactory::create(
56 ImpulseCostModelTypes::Type cost_type, PinocchioModelTypes::Type model_type,
57 ActivationModelTypes::Type activation_type) const {
58 // Create impulse action model with no cost
59 42 std::shared_ptr<crocoddyl::ActionModelImpulseFwdDynamics> action;
60
2/3
✓ Branch 0 taken 30 times.
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
42 switch (model_type) {
61 30 case PinocchioModelTypes::Talos:
62
2/4
✓ Branch 1 taken 30 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 30 times.
✗ Branch 5 not taken.
60 action = ActionModelFactory().create_impulseFwdDynamics(
63 30 StateModelTypes::StateMultibody_Talos);
64 30 break;
65 12 case PinocchioModelTypes::HyQ:
66
2/4
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
24 action = ActionModelFactory().create_impulseFwdDynamics(
67 12 StateModelTypes::StateMultibody_HyQ);
68 12 break;
69 default:
70 throw_pretty(__FILE__ ": Wrong PinocchioModelTypes::Type given");
71 break;
72 }
73
2/4
✓ Branch 5 taken 42 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 42 times.
✗ Branch 9 not taken.
42 action->get_costs()->removeCost("state");
74
75 // Create cost
76 42 std::shared_ptr<crocoddyl::CostModelAbstract> cost;
77
1/2
✓ Branch 1 taken 42 times.
✗ Branch 2 not taken.
84 PinocchioModelFactory model_factory(model_type);
78 std::shared_ptr<crocoddyl::StateMultibody> state =
79 84 std::static_pointer_cast<crocoddyl::StateMultibody>(action->get_state());
80
2/4
✓ Branch 1 taken 42 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 42 times.
✗ Branch 5 not taken.
42 Eigen::Matrix3d R = Eigen::Matrix3d::Identity();
81
1/2
✓ Branch 1 taken 42 times.
✗ Branch 2 not taken.
84 std::vector<std::size_t> frame_ids = model_factory.get_frame_ids();
82
5/6
✓ Branch 0 taken 6 times.
✓ Branch 1 taken 12 times.
✓ Branch 2 taken 6 times.
✓ Branch 3 taken 12 times.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
42 switch (cost_type) {
83 6 case ImpulseCostModelTypes::CostModelResidualImpulseCoM:
84
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 cost = std::make_shared<crocoddyl::CostModelResidual>(
85
2/4
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
12 state, ActivationModelFactory().create(activation_type, 3),
86
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
18 std::make_shared<crocoddyl::ResidualModelImpulseCoM>(state));
87
2/4
✓ Branch 6 taken 6 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 6 times.
✗ Branch 10 not taken.
6 action->get_costs()->addCost("cost_0", cost, 0.01);
88 6 break;
89 12 case ImpulseCostModelTypes::CostModelResidualContactForce:
90
2/2
✓ Branch 1 taken 36 times.
✓ Branch 2 taken 12 times.
48 for (std::size_t i = 0; i < frame_ids.size(); ++i) {
91
1/2
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
72 cost = std::make_shared<crocoddyl::CostModelResidual>(
92 state,
93
3/6
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 36 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 36 times.
✗ Branch 8 not taken.
72 ActivationModelFactory().create(activation_type,
94 model_factory.get_contact_nc()),
95
1/2
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
72 std::make_shared<crocoddyl::ResidualModelContactForce>(
96 36 state, frame_ids[i], pinocchio::Force::Random(),
97
2/4
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 36 times.
✗ Branch 5 not taken.
72 model_factory.get_contact_nc(), 0));
98
3/6
✓ Branch 5 taken 36 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 36 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 36 times.
✗ Branch 12 not taken.
36 action->get_costs()->addCost("cost_" + std::to_string(i), cost, 0.01);
99 }
100 12 break;
101 6 case ImpulseCostModelTypes::CostModelResidualContactCoPPosition:
102
2/2
✓ Branch 1 taken 12 times.
✓ Branch 2 taken 6 times.
18 for (std::size_t i = 0; i < frame_ids.size(); ++i) {
103
1/2
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
24 cost = std::make_shared<crocoddyl::CostModelResidual>(
104
2/4
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
24 state, ActivationModelFactory().create(activation_type, 4),
105
1/2
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
24 std::make_shared<crocoddyl::ResidualModelContactCoPPosition>(
106 12 state, frame_ids[i],
107
3/6
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
24 CoPSupport(Eigen::Matrix3d::Identity(),
108 Eigen::Vector2d(0.1, 0.1)),
109
1/2
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
24 0));
110
3/6
✓ Branch 5 taken 12 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 12 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 12 times.
✗ Branch 12 not taken.
12 action->get_costs()->addCost("cost_" + std::to_string(i), cost, 0.01);
111 }
112 6 break;
113 12 case ImpulseCostModelTypes::CostModelResidualContactFrictionCone:
114
2/2
✓ Branch 1 taken 36 times.
✓ Branch 2 taken 12 times.
48 for (std::size_t i = 0; i < frame_ids.size(); ++i) {
115
1/2
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
72 cost = std::make_shared<crocoddyl::CostModelResidual>(
116
2/4
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 36 times.
✗ Branch 5 not taken.
72 state, ActivationModelFactory().create(activation_type, 5),
117
1/2
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
72 std::make_shared<crocoddyl::ResidualModelContactFrictionCone>(
118
1/2
✓ Branch 2 taken 36 times.
✗ Branch 3 not taken.
108 state, frame_ids[i], crocoddyl::FrictionCone(R, 1.), 0));
119
3/6
✓ Branch 5 taken 36 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 36 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 36 times.
✗ Branch 12 not taken.
36 action->get_costs()->addCost("cost_" + std::to_string(i), cost, 0.01);
120 }
121 12 break;
122 6 case ImpulseCostModelTypes::CostModelResidualContactWrenchCone:
123
2/2
✓ Branch 1 taken 12 times.
✓ Branch 2 taken 6 times.
18 for (std::size_t i = 0; i < frame_ids.size(); ++i) {
124
1/2
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
24 cost = std::make_shared<crocoddyl::CostModelResidual>(
125
2/4
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
24 state, ActivationModelFactory().create(activation_type, 17),
126
1/2
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
24 std::make_shared<crocoddyl::ResidualModelContactWrenchCone>(
127 12 state, frame_ids[i],
128
2/4
✓ Branch 2 taken 12 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 12 times.
✗ Branch 6 not taken.
36 crocoddyl::WrenchCone(R, 1., Eigen::Vector2d(0.1, 0.1)), 0));
129
3/6
✓ Branch 5 taken 12 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 12 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 12 times.
✗ Branch 12 not taken.
12 action->get_costs()->addCost("cost_" + std::to_string(i), cost, 0.01);
130 }
131 6 break;
132 default:
133 throw_pretty(__FILE__ ": Wrong ImpulseCostModelTypes::Type given");
134 break;
135 }
136
137 // Include the cost in the impulse model
138
2/4
✓ Branch 6 taken 42 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 42 times.
✗ Branch 10 not taken.
42 action->get_costs()->addCost("cost", cost, 0.1);
139 84 return action;
140 42 }
141
142 } // namespace unittest
143 } // namespace crocoddyl
144