GCC Code Coverage Report


Directory: ./
File: unittest/factory/contact_cost.cpp
Date: 2025-02-24 23:41:29
Exec Total Coverage
Lines: 85 94 90.4%
Branches: 77 152 50.7%

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 "contact_cost.hpp"
10
11 #include "crocoddyl/core/costs/residual.hpp"
12 #include "crocoddyl/core/utils/exception.hpp"
13 #include "crocoddyl/multibody/residuals/contact-control-gravity.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 "diff_action.hpp"
19
20 namespace crocoddyl {
21 namespace unittest {
22
23 const std::vector<ContactCostModelTypes::Type> ContactCostModelTypes::all(
24 ContactCostModelTypes::init_all());
25
26 48 std::ostream& operator<<(std::ostream& os, ContactCostModelTypes::Type type) {
27
5/7
✓ Branch 0 taken 12 times.
✓ Branch 1 taken 6 times.
✓ Branch 2 taken 12 times.
✓ Branch 3 taken 6 times.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✗ Branch 6 not taken.
48 switch (type) {
28 12 case ContactCostModelTypes::CostModelResidualContactForce:
29 12 os << "CostModelResidualContactForce";
30 12 break;
31 6 case ContactCostModelTypes::CostModelResidualContactCoPPosition:
32 6 os << "CostModelResidualContactCoPPosition";
33 6 break;
34 12 case ContactCostModelTypes::CostModelResidualContactFrictionCone:
35 12 os << "CostModelResidualContactFrictionCone";
36 12 break;
37 6 case ContactCostModelTypes::CostModelResidualContactWrenchCone:
38 6 os << "CostModelResidualContactWrenchCone";
39 6 break;
40 12 case ContactCostModelTypes::CostModelResidualContactControlGrav:
41 12 os << "CostModelResidualContactControlGrav";
42 12 break;
43 case ContactCostModelTypes::NbContactCostModelTypes:
44 os << "NbContactCostModelTypes";
45 break;
46 default:
47 break;
48 }
49 48 return os;
50 }
51
52 48 ContactCostModelFactory::ContactCostModelFactory() {}
53 48 ContactCostModelFactory::~ContactCostModelFactory() {}
54
55 std::shared_ptr<crocoddyl::DifferentialActionModelAbstract>
56 48 ContactCostModelFactory::create(
57 ContactCostModelTypes::Type cost_type, PinocchioModelTypes::Type model_type,
58 ActivationModelTypes::Type activation_type,
59 ActuationModelTypes::Type actuation_type) const {
60 // Create contact action model with no cost
61 48 std::shared_ptr<crocoddyl::DifferentialActionModelContactFwdDynamics> action;
62
2/3
✓ Branch 0 taken 30 times.
✓ Branch 1 taken 18 times.
✗ Branch 2 not taken.
48 switch (model_type) {
63 30 case PinocchioModelTypes::Talos:
64
2/4
✓ Branch 1 taken 30 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 30 times.
✗ Branch 5 not taken.
60 action = DifferentialActionModelFactory().create_contactFwdDynamics(
65 30 StateModelTypes::StateMultibody_Talos, actuation_type, false);
66 30 break;
67 18 case PinocchioModelTypes::HyQ:
68
2/4
✓ Branch 1 taken 18 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 18 times.
✗ Branch 5 not taken.
36 action = DifferentialActionModelFactory().create_contactFwdDynamics(
69 18 StateModelTypes::StateMultibody_HyQ, actuation_type, false);
70 18 break;
71 default:
72 throw_pretty(__FILE__ ": Wrong PinocchioModelTypes::Type given");
73 break;
74 }
75
2/4
✓ Branch 5 taken 48 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 48 times.
✗ Branch 9 not taken.
48 action->get_costs()->removeCost("state");
76
2/4
✓ Branch 5 taken 48 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 48 times.
✗ Branch 9 not taken.
48 action->get_costs()->removeCost("control");
77
78 // Create cost
79 48 std::shared_ptr<crocoddyl::CostModelAbstract> cost;
80
1/2
✓ Branch 1 taken 48 times.
✗ Branch 2 not taken.
96 PinocchioModelFactory model_factory(model_type);
81 std::shared_ptr<crocoddyl::StateMultibody> state =
82 96 std::static_pointer_cast<crocoddyl::StateMultibody>(action->get_state());
83 48 const std::size_t nu = action->get_actuation()->get_nu();
84
2/4
✓ Branch 1 taken 48 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 48 times.
✗ Branch 5 not taken.
48 Eigen::Matrix3d R = Eigen::Matrix3d::Identity();
85
1/2
✓ Branch 1 taken 48 times.
✗ Branch 2 not taken.
96 std::vector<std::size_t> frame_ids = model_factory.get_frame_ids();
86
5/6
✓ Branch 0 taken 12 times.
✓ Branch 1 taken 6 times.
✓ Branch 2 taken 12 times.
✓ Branch 3 taken 6 times.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
48 switch (cost_type) {
87 12 case ContactCostModelTypes::CostModelResidualContactForce:
88
2/2
✓ Branch 1 taken 36 times.
✓ Branch 2 taken 12 times.
48 for (std::size_t i = 0; i < frame_ids.size(); ++i) {
89
1/2
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
72 cost = std::make_shared<crocoddyl::CostModelResidual>(
90 state,
91
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,
92 model_factory.get_contact_nc()),
93
1/2
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
72 std::make_shared<crocoddyl::ResidualModelContactForce>(
94 36 state, frame_ids[i], pinocchio::Force::Random(),
95
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(), nu));
96
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.001);
97 }
98 12 break;
99 6 case ContactCostModelTypes::CostModelResidualContactCoPPosition:
100
2/2
✓ Branch 1 taken 12 times.
✓ Branch 2 taken 6 times.
18 for (std::size_t i = 0; i < frame_ids.size(); ++i) {
101
1/2
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
24 cost = std::make_shared<crocoddyl::CostModelResidual>(
102
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),
103
1/2
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
24 std::make_shared<crocoddyl::ResidualModelContactCoPPosition>(
104 12 state, frame_ids[i],
105
2/4
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
36 crocoddyl::CoPSupport(R, Eigen::Vector2d(0.1, 0.1)), nu));
106
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.001);
107 }
108 6 break;
109 12 case ContactCostModelTypes::CostModelResidualContactFrictionCone:
110
2/2
✓ Branch 1 taken 36 times.
✓ Branch 2 taken 12 times.
48 for (std::size_t i = 0; i < frame_ids.size(); ++i) {
111
1/2
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
72 cost = std::make_shared<crocoddyl::CostModelResidual>(
112
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),
113
1/2
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
72 std::make_shared<crocoddyl::ResidualModelContactFrictionCone>(
114
1/2
✓ Branch 2 taken 36 times.
✗ Branch 3 not taken.
108 state, frame_ids[i], crocoddyl::FrictionCone(R, 1.), nu));
115
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.001);
116 }
117 12 break;
118 6 case ContactCostModelTypes::CostModelResidualContactWrenchCone:
119
2/2
✓ Branch 1 taken 12 times.
✓ Branch 2 taken 6 times.
18 for (std::size_t i = 0; i < frame_ids.size(); ++i) {
120
1/2
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
24 cost = std::make_shared<crocoddyl::CostModelResidual>(
121
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),
122
1/2
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
24 std::make_shared<crocoddyl::ResidualModelContactWrenchCone>(
123 12 state, frame_ids[i],
124
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)), nu));
125
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.001);
126 }
127 6 break;
128 12 case ContactCostModelTypes::CostModelResidualContactControlGrav:
129
2/2
✓ Branch 1 taken 36 times.
✓ Branch 2 taken 12 times.
48 for (std::size_t i = 0; i < frame_ids.size(); ++i) {
130
1/2
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
72 cost = std::make_shared<crocoddyl::CostModelResidual>(
131 state,
132
2/4
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
✓ Branch 6 taken 36 times.
✗ Branch 7 not taken.
72 ActivationModelFactory().create(activation_type, state->get_nv()),
133
1/2
✓ Branch 1 taken 36 times.
✗ Branch 2 not taken.
72 std::make_shared<crocoddyl::ResidualModelContactControlGrav>(state,
134 36 nu));
135
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.001);
136 }
137 12 break;
138 default:
139 throw_pretty(__FILE__ ": Wrong ContactCostModelTypes::Type given");
140 break;
141 }
142 // Include the cost in the contact model
143 96 return action;
144 48 }
145
146 } // namespace unittest
147 } // namespace crocoddyl
148