GCC Code Coverage Report


Directory: ./
File: tests/test-bezier-symbolic.cpp
Date: 2025-03-18 04:20:50
Exec Total Coverage
Lines: 154 154 100.0%
Branches: 440 856 51.4%

Line Branch Exec Source
1 //
2 // Copyright (c) 2018 CNRS
3 // Authors: Pierre Fernbach
4 //
5 // This file is part of bezier_COM_traj
6 // hpp-core is free software: you can redistribute it
7 // and/or modify it under the terms of the GNU Lesser General Public
8 // License as published by the Free Software Foundation, either version
9 // 3 of the License, or (at your option) any later version.
10 //
11 // hpp-core is distributed in the hope that it will be
12 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
13 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
14 // General Lesser Public License for more details. You should have
15 // received a copy of the GNU Lesser General Public License along with
16 // hpp-core If not, see
17 // <http://www.gnu.org/licenses/>.
18
19 #define BOOST_TEST_MODULE transition
20 #include <ndcurves/bezier_curve.h>
21
22 #include <boost/test/included/unit_test.hpp>
23 #include <hpp/bezier-com-traj/common_solve_methods.hh>
24 #include <hpp/bezier-com-traj/data.hh>
25 #include <hpp/bezier-com-traj/solve.hh>
26 #include <hpp/centroidal-dynamics/centroidal_dynamics.hh>
27
28 #include "test_helper.hh"
29
30 using namespace bezier_com_traj;
31 const double T = 1.5;
32
33 14 ProblemData buildPData(const centroidal_dynamics::EquilibriumAlgorithm algo =
34 centroidal_dynamics::EQUILIBRIUM_ALGORITHM_PP) {
35
1/2
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
14 ProblemData pData;
36
1/2
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
14 pData.c0_ = Vector3(0, 0.5, 5.);
37
1/2
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
14 pData.c1_ = Vector3(2, -0.5, 5.);
38
2/4
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 14 times.
✗ Branch 5 not taken.
14 pData.dc0_ = Vector3::Zero();
39
2/4
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 14 times.
✗ Branch 5 not taken.
14 pData.dc1_ = Vector3::Zero();
40
2/4
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 14 times.
✗ Branch 5 not taken.
14 pData.ddc0_ = Vector3::Zero();
41
2/4
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 14 times.
✗ Branch 5 not taken.
14 pData.ddc1_ = Vector3::Zero();
42 14 pData.constraints_.flag_ = INIT_POS | INIT_VEL | END_VEL | END_POS;
43
44
2/4
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 14 times.
✗ Branch 5 not taken.
14 MatrixX3 normals(2, 3), positions(2, 3);
45
3/6
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 14 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 14 times.
✗ Branch 8 not taken.
14 normals.block<1, 3>(0, 0) = Vector3(0, 0, 1);
46
3/6
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 14 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 14 times.
✗ Branch 8 not taken.
14 positions.block<1, 3>(0, 0) = Vector3(0, 0.1, 0);
47
3/6
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 14 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 14 times.
✗ Branch 8 not taken.
14 normals.block<1, 3>(1, 0) = Vector3(0, 0, 1);
48
3/6
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 14 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 14 times.
✗ Branch 8 not taken.
14 positions.block<1, 3>(1, 0) = Vector3(0, -0.1, 0);
49 std::pair<MatrixX3, MatrixX3> contacts =
50
3/6
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 14 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 14 times.
✗ Branch 8 not taken.
28 computeRectangularContacts(normals, positions, LX, LY);
51
4/8
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 14 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 14 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 14 times.
✗ Branch 11 not taken.
28 pData.contacts_.push_back(new centroidal_dynamics::Equilibrium(
52
2/4
✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 14 times.
✗ Branch 5 not taken.
14 ComputeContactCone(contacts.first, contacts.second, algo)));
53
54 28 return pData;
55 14 }
56
57 6 std::vector<point_t> generate_wps() {
58
1/2
✓ Branch 2 taken 6 times.
✗ Branch 3 not taken.
12 return computeConstantWaypoints(buildPData(), T);
59 }
60
61 6 bezier_wp_t::t_point_t generate_wps_symbolic() {
62
1/2
✓ Branch 2 taken 6 times.
✗ Branch 3 not taken.
12 return computeConstantWaypointsSymbolic(buildPData(), T);
63 }
64
65 20638 VectorX eval(const waypoint_t& w, const point_t& x) {
66
2/4
✓ Branch 2 taken 20638 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20638 times.
✗ Branch 6 not taken.
41276 return w.first * x + w.second;
67 }
68
69 15907 void vectorEqual(const VectorX& a, const VectorX& b, const double EPS = 1e-14) {
70
4/8
✓ Branch 3 taken 15907 times.
✗ Branch 4 not taken.
✓ Branch 10 taken 15907 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 15907 times.
✗ Branch 14 not taken.
✗ Branch 17 not taken.
✓ Branch 18 taken 15907 times.
15907 BOOST_CHECK_EQUAL(a.size(), b.size());
71
7/14
✓ Branch 3 taken 15907 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 15907 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 15907 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 15907 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 15907 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 15907 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 15907 times.
15907 BOOST_CHECK((a - b).norm() < EPS);
72 15907 }
73
74 BOOST_AUTO_TEST_SUITE(symbolic)
75
76
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(symbolic_eval_c) {
77
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::vector<point_t> pts = generate_wps();
78
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 bezier_wp_t::t_point_t wps = generate_wps_symbolic();
79
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 point_t y(1, 0.2, 4.5);
80
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pts[2] = y;
81
82
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_t c(pts.begin(), pts.end(), 0., T);
83
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_wp_t c_sym(wps.begin(), wps.end(), 0., T);
84
85 2 double t = 0.;
86
2/2
✓ Branch 0 taken 150 times.
✓ Branch 1 taken 1 times.
302 while (t < T) {
87
5/10
✓ Branch 1 taken 150 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 150 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 150 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 150 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 150 times.
✗ Branch 14 not taken.
300 vectorEqual(c(t), eval(c_sym(t), y));
88 300 t += 0.01;
89 }
90 2 }
91
92
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(symbolic_eval_dc) {
93
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::vector<point_t> pts = generate_wps();
94
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 bezier_wp_t::t_point_t wps = generate_wps_symbolic();
95
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 point_t y(1, 0.2, 4.5);
96
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pts[2] = y;
97
98
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_t c(pts.begin(), pts.end(), 0., T);
99
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 bezier_t dc = c.compute_derivate(1);
100
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_wp_t c_sym(wps.begin(), wps.end(), 0., T);
101
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 bezier_wp_t dc_sym = c_sym.compute_derivate(1);
102
103 2 double t = 0.;
104
2/2
✓ Branch 0 taken 150 times.
✓ Branch 1 taken 1 times.
302 while (t < T) {
105
5/10
✓ Branch 1 taken 150 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 150 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 150 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 150 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 150 times.
✗ Branch 14 not taken.
300 vectorEqual(dc(t), eval(dc_sym(t), y));
106 300 t += 0.01;
107 }
108 2 }
109
110
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(symbolic_eval_ddc) {
111
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::vector<point_t> pts = generate_wps();
112
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 bezier_wp_t::t_point_t wps = generate_wps_symbolic();
113
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 point_t y(1, 0.2, 4.5);
114
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pts[2] = y;
115
116
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_t c(pts.begin(), pts.end(), 0., T);
117
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 bezier_t ddc = c.compute_derivate(2);
118
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_wp_t c_sym(wps.begin(), wps.end(), 0., T);
119
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 bezier_wp_t ddc_sym = c_sym.compute_derivate(2);
120
121 2 double t = 0.;
122
2/2
✓ Branch 0 taken 150 times.
✓ Branch 1 taken 1 times.
302 while (t < T) {
123
5/10
✓ Branch 1 taken 150 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 150 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 150 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 150 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 150 times.
✗ Branch 14 not taken.
300 vectorEqual(ddc(t), eval(ddc_sym(t), y), 1e-10);
124 300 t += 0.01;
125 }
126 2 }
127
128
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(symbolic_eval_jc) {
129
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::vector<point_t> pts = generate_wps();
130
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 bezier_wp_t::t_point_t wps = generate_wps_symbolic();
131
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 point_t y(1, 0.2, 4.5);
132
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pts[2] = y;
133
134
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_t c(pts.begin(), pts.end(), 0., T);
135
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 bezier_t jc = c.compute_derivate(3);
136
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_wp_t c_sym(wps.begin(), wps.end(), 0., T);
137
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 bezier_wp_t jc_sym = c_sym.compute_derivate(3);
138
139 2 double t = 0.;
140
2/2
✓ Branch 0 taken 150 times.
✓ Branch 1 taken 1 times.
302 while (t < T) {
141
5/10
✓ Branch 1 taken 150 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 150 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 150 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 150 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 150 times.
✗ Branch 14 not taken.
300 vectorEqual(jc(t), eval(jc_sym(t), y), 1e-10);
142 300 t += 0.01;
143 }
144 2 }
145
146
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(symbolic_split_c) {
147
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::vector<point_t> pts = generate_wps();
148
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 bezier_wp_t::t_point_t wps = generate_wps_symbolic();
149
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 point_t y(1, 0.2, 4.5);
150
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pts[2] = y;
151
152
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_t c(pts.begin(), pts.end(), 0., T);
153
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_wp_t c_sym(wps.begin(), wps.end(), 0., T);
154
155 double a, b, t, t1, t2;
156
2/2
✓ Branch 0 taken 100 times.
✓ Branch 1 taken 1 times.
202 for (size_t i = 0; i < 100; ++i) {
157 200 a = (rand() / (double)RAND_MAX) * T;
158 200 b = (rand() / (double)RAND_MAX) * T;
159 200 t1 = std::min(a, b);
160 200 t2 = std::max(a, b);
161 // std::cout<<"try extract between : ["<<t1<<";"<<t2<<"] "<<std::endl;
162
1/2
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
200 bezier_t c_e = c.extract(t1, t2);
163
1/2
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
200 bezier_wp_t c_sym_e = c_sym.extract(t1, t2);
164 200 t = t1;
165
2/2
✓ Branch 0 taken 5288 times.
✓ Branch 1 taken 100 times.
10776 while (t < t2) {
166
5/10
✓ Branch 1 taken 5288 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5288 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 5288 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 5288 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 5288 times.
✗ Branch 14 not taken.
10576 vectorEqual(c_e(t), eval(c_sym_e(t), y));
167
5/10
✓ Branch 1 taken 5288 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5288 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 5288 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 5288 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 5288 times.
✗ Branch 14 not taken.
10576 vectorEqual(c(t), eval(c_sym_e(t), y));
168 10576 t += 0.01;
169 }
170 200 }
171 2 }
172
173
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(symbolic_split_c_bench) {
174 using namespace std;
175
176
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::vector<point_t> pts = generate_wps();
177
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 bezier_wp_t::t_point_t wps = generate_wps_symbolic();
178
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 point_t y(1, 0.2, 4.5);
179
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pts[2] = y;
180
181
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_wp_t c_sym(wps.begin(), wps.end(), 0., T);
182
183 2 std::vector<double> values;
184
3/4
✓ Branch 2 taken 100000 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 100000 times.
✓ Branch 5 taken 1 times.
200002 for (int i = 0; i < 100000; ++i) values.push_back((double)rand() / RAND_MAX);
185
186 clock_t s0, e0;
187
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::pair<bezier_wp_t, bezier_wp_t> splitted = c_sym.split(0.5);
188 2 s0 = clock();
189 2 for (std::vector<double>::const_iterator cit = values.begin();
190
2/2
✓ Branch 2 taken 100000 times.
✓ Branch 3 taken 1 times.
200002 cit != values.end(); ++cit) {
191
2/4
✓ Branch 2 taken 100000 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 100000 times.
✗ Branch 6 not taken.
200000 splitted = c_sym.split(*cit);
192 }
193 2 e0 = clock();
194
195
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::cout << "Time required to split a c curve : "
196
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 << ((double)(e0 - s0) / CLOCKS_PER_SEC) / 100. << " ms "
197
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 << std::endl;
198 2 }
199
200
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(symbolic_split_w) {
201
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 bezier_wp_t::t_point_t wps = computeWwaypoints(buildPData(), T);
202
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 point_t y(1, 0.2, 4.5);
203
204
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_wp_t w(wps.begin(), wps.end(), 0., T);
205
206 double a, b, t, t1, t2;
207
2/2
✓ Branch 0 taken 100 times.
✓ Branch 1 taken 1 times.
202 for (size_t i = 0; i < 100; ++i) {
208 200 a = (rand() / (double)RAND_MAX) * T;
209 200 b = (rand() / (double)RAND_MAX) * T;
210 200 t1 = std::min(a, b);
211 200 t2 = std::max(a, b);
212 // std::cout<<"try extract between : ["<<t1<<";"<<t2<<"] "<<std::endl;
213
1/2
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
200 bezier_wp_t w_e = w.extract(t1, t2);
214 200 t = t1;
215
2/2
✓ Branch 0 taken 4731 times.
✓ Branch 1 taken 100 times.
9662 while (t < t2) {
216
5/10
✓ Branch 1 taken 4731 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 4731 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 4731 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 4731 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 4731 times.
✗ Branch 14 not taken.
9462 vectorEqual(eval(w(t), y), eval(w_e(t), y), 1e-12);
217 9462 t += 0.01;
218 }
219 200 }
220 2 }
221
222
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(symbolic_split_w_bench) {
223
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 bezier_wp_t::t_point_t wps = computeWwaypoints(buildPData(), T);
224
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 point_t y(1, 0.2, 4.5);
225
226
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 bezier_wp_t w(wps.begin(), wps.end(), 0., T);
227
228 2 std::vector<double> values;
229
3/4
✓ Branch 2 taken 100000 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 100000 times.
✓ Branch 5 taken 1 times.
200002 for (int i = 0; i < 100000; ++i) values.push_back((double)rand() / RAND_MAX);
230
231 clock_t s0, e0;
232
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::pair<bezier_wp_t, bezier_wp_t> splitted = w.split(0.5);
233 2 s0 = clock();
234 2 for (std::vector<double>::const_iterator cit = values.begin();
235
2/2
✓ Branch 2 taken 100000 times.
✓ Branch 3 taken 1 times.
200002 cit != values.end(); ++cit) {
236
2/4
✓ Branch 2 taken 100000 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 100000 times.
✗ Branch 6 not taken.
200000 splitted = w.split(*cit);
237 }
238 2 e0 = clock();
239
240
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::cout << "Time required to split a w curve : "
241
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 << ((double)(e0 - s0) / CLOCKS_PER_SEC) / 100. << " ms "
242
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 << std::endl;
243 2 }
244
245 BOOST_AUTO_TEST_SUITE_END()
246