GCC Code Coverage Report


Directory: ./
File: unittest/factory/impulse_cost.cpp
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 83 93 89.2%
Branches: 84 168 50.0%

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