Skip to content

Commit a90b97d

Browse files
Remove deprecated items
1 parent c66e043 commit a90b97d

26 files changed

+55
-131
lines changed

tesseract_collision/core/include/tesseract_collision/core/types.h

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -167,9 +167,6 @@ std::size_t flattenMoveResults(ContactResultMap&& m, ContactResultVector& v);
167167

168168
std::size_t flattenCopyResults(const ContactResultMap& m, ContactResultVector& v);
169169

170-
// Need to mark deprecated
171-
std::size_t flattenResults(ContactResultMap&& m, ContactResultVector& v);
172-
173170
/**
174171
* @brief This data is intended only to be used internal to the collision checkers as a container and should not
175172
* be externally used by other libraries or packages.

tesseract_collision/core/include/tesseract_collision/test_suite/benchmarks/large_dataset_benchmarks.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -90,7 +90,7 @@ static void BM_LARGE_DATASET_MULTILINK(benchmark::State& state,
9090
ContactResultMap result;
9191
result_vector.clear();
9292
checker->contactTest(result, ContactTestType::ALL);
93-
flattenResults(std::move(result), result_vector);
93+
flattenMoveResults(std::move(result), result_vector);
9494
}
9595
};
9696

@@ -180,7 +180,7 @@ static void BM_LARGE_DATASET_SINGLELINK(benchmark::State& state,
180180
ContactResultMap result;
181181
result_vector.clear();
182182
checker->contactTest(result, ContactTestType::ALL);
183-
flattenResults(std::move(result), result_vector);
183+
flattenMoveResults(std::move(result), result_vector);
184184
}
185185
};
186186

tesseract_collision/core/include/tesseract_collision/test_suite/collision_box_box_cast_unit.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -143,7 +143,7 @@ inline void runTest(ContinuousContactManager& checker)
143143
checker.contactTest(result, ContactRequest(t));
144144

145145
ContactResultVector result_vector;
146-
flattenResults(std::move(result), result_vector);
146+
flattenMoveResults(std::move(result), result_vector);
147147

148148
EXPECT_TRUE(!result_vector.empty());
149149
EXPECT_NEAR(result_vector[0].distance, -0.2475, 0.001);

tesseract_collision/core/include/tesseract_collision/test_suite/collision_box_box_unit.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,7 @@ inline void runTestTyped(DiscreteContactManager& checker, ContactTestType test_t
147147
checker.contactTest(result, ContactRequest(test_type));
148148

149149
ContactResultVector result_vector;
150-
flattenResults(std::move(result), result_vector);
150+
flattenMoveResults(std::move(result), result_vector);
151151

152152
EXPECT_TRUE(!result_vector.empty());
153153
EXPECT_NEAR(result_vector[0].distance, -1.30, 0.001);
@@ -188,7 +188,7 @@ inline void runTestTyped(DiscreteContactManager& checker, ContactTestType test_t
188188
tesseract_common::VectorIsometry3d transforms = { location["box_link"] };
189189
checker.setCollisionObjectsTransform(names, transforms);
190190
checker.contactTest(result, test_type);
191-
flattenResults(std::move(result), result_vector);
191+
flattenMoveResults(std::move(result), result_vector);
192192

193193
EXPECT_TRUE(result_vector.empty());
194194
}
@@ -212,7 +212,7 @@ inline void runTestTyped(DiscreteContactManager& checker, ContactTestType test_t
212212
tesseract_common::VectorIsometry3d transforms = { location["box_link"] };
213213
checker.setCollisionObjectsTransform(names, transforms);
214214
checker.contactTest(result, test_type);
215-
flattenResults(std::move(result), result_vector);
215+
flattenMoveResults(std::move(result), result_vector);
216216

217217
EXPECT_TRUE(result_vector.empty());
218218
}
@@ -231,7 +231,7 @@ inline void runTestTyped(DiscreteContactManager& checker, ContactTestType test_t
231231
EXPECT_NEAR(checker.getCollisionMarginData().getPairCollisionMargin("box_link", "second_box_link"), 0.25, 1e-5);
232232
EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.25, 1e-5);
233233
checker.contactTest(result, ContactRequest(test_type));
234-
flattenResults(std::move(result), result_vector);
234+
flattenMoveResults(std::move(result), result_vector);
235235

236236
EXPECT_TRUE(!result_vector.empty());
237237
EXPECT_NEAR(result_vector[0].distance, 0.1, 0.001);
@@ -269,7 +269,7 @@ inline void runTestTyped(DiscreteContactManager& checker, ContactTestType test_t
269269
checker.setCollisionMarginData(CollisionMarginData(0.25));
270270
EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.25, 1e-5);
271271
checker.contactTest(result, ContactRequest(test_type));
272-
flattenResults(std::move(result), result_vector);
272+
flattenMoveResults(std::move(result), result_vector);
273273

274274
EXPECT_TRUE(!result_vector.empty());
275275
EXPECT_NEAR(result_vector[0].distance, 0.1, 0.001);

tesseract_collision/core/include/tesseract_collision/test_suite/collision_box_capsule_unit.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,7 @@ inline void runTest(DiscreteContactManager& checker)
123123
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
124124

125125
ContactResultVector result_vector;
126-
flattenResults(std::move(result), result_vector);
126+
flattenMoveResults(std::move(result), result_vector);
127127

128128
EXPECT_TRUE(!result_vector.empty());
129129
EXPECT_NEAR(result_vector[0].distance, -0.55, 0.0001);
@@ -160,7 +160,7 @@ inline void runTest(DiscreteContactManager& checker)
160160
checker.setCollisionObjectsTransform(location);
161161

162162
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
163-
flattenResults(std::move(result), result_vector);
163+
flattenMoveResults(std::move(result), result_vector);
164164

165165
EXPECT_TRUE(result_vector.empty());
166166

@@ -174,7 +174,7 @@ inline void runTest(DiscreteContactManager& checker)
174174
checker.setCollisionMarginData(CollisionMarginData(0.251));
175175
EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.251, 1e-5);
176176
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
177-
flattenResults(std::move(result), result_vector);
177+
flattenMoveResults(std::move(result), result_vector);
178178

179179
EXPECT_TRUE(!result_vector.empty());
180180
EXPECT_NEAR(result_vector[0].distance, 0.125, 0.001);

tesseract_collision/core/include/tesseract_collision/test_suite/collision_box_cone_unit.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -126,7 +126,7 @@ inline void runTest(DiscreteContactManager& checker)
126126
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
127127

128128
ContactResultVector result_vector;
129-
flattenResults(std::move(result), result_vector);
129+
flattenMoveResults(std::move(result), result_vector);
130130

131131
EXPECT_TRUE(!result_vector.empty());
132132
EXPECT_NEAR(result_vector[0].distance, -0.55, 0.0001);
@@ -170,7 +170,7 @@ inline void runTest(DiscreteContactManager& checker)
170170
// Use different method for setting transforms
171171
checker.setCollisionObjectsTransform("cone_link", location["cone_link"]);
172172
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
173-
flattenResults(std::move(result), result_vector);
173+
flattenMoveResults(std::move(result), result_vector);
174174

175175
EXPECT_TRUE(result_vector.empty());
176176

@@ -184,7 +184,7 @@ inline void runTest(DiscreteContactManager& checker)
184184
checker.setCollisionMarginData(CollisionMarginData(0.251));
185185
EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.251, 1e-5);
186186
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
187-
flattenResults(std::move(result), result_vector);
187+
flattenMoveResults(std::move(result), result_vector);
188188

189189
EXPECT_TRUE(!result_vector.empty());
190190
EXPECT_NEAR(result_vector[0].distance, 0.25, 0.001);

tesseract_collision/core/include/tesseract_collision/test_suite/collision_box_cylinder_unit.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,7 @@ inline void runTest(DiscreteContactManager& checker)
124124
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
125125

126126
ContactResultVector result_vector;
127-
flattenResults(std::move(result), result_vector);
127+
flattenMoveResults(std::move(result), result_vector);
128128

129129
EXPECT_TRUE(!result_vector.empty());
130130
EXPECT_NEAR(result_vector[0].distance, -0.55, 0.0001);
@@ -164,7 +164,7 @@ inline void runTest(DiscreteContactManager& checker)
164164
tesseract_common::VectorIsometry3d transforms = { location["cylinder_link"] };
165165
checker.setCollisionObjectsTransform(names, transforms);
166166
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
167-
flattenResults(std::move(result), result_vector);
167+
flattenMoveResults(std::move(result), result_vector);
168168

169169
EXPECT_TRUE(result_vector.empty());
170170

@@ -178,7 +178,7 @@ inline void runTest(DiscreteContactManager& checker)
178178
checker.setCollisionMarginData(CollisionMarginData(0.251));
179179
EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.251, 1e-5);
180180
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
181-
flattenResults(std::move(result), result_vector);
181+
flattenMoveResults(std::move(result), result_vector);
182182

183183
EXPECT_TRUE(!result_vector.empty());
184184
EXPECT_NEAR(result_vector[0].distance, 0.25, 0.001);

tesseract_collision/core/include/tesseract_collision/test_suite/collision_box_sphere_unit.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -144,7 +144,7 @@ inline void runTestPrimitive(DiscreteContactManager& checker)
144144
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
145145

146146
ContactResultVector result_vector;
147-
flattenResults(std::move(result), result_vector);
147+
flattenMoveResults(std::move(result), result_vector);
148148

149149
EXPECT_TRUE(!result_vector.empty());
150150
EXPECT_NEAR(result_vector[0].distance, -0.55, 0.001);
@@ -186,7 +186,7 @@ inline void runTestPrimitive(DiscreteContactManager& checker)
186186
// Use different method for setting transforms
187187
checker.setCollisionObjectsTransform("sphere_link", location["sphere_link"]);
188188
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
189-
flattenResults(std::move(result), result_vector);
189+
flattenMoveResults(std::move(result), result_vector);
190190

191191
EXPECT_TRUE(result_vector.empty());
192192

@@ -200,7 +200,7 @@ inline void runTestPrimitive(DiscreteContactManager& checker)
200200
checker.setCollisionMarginData(CollisionMarginData(0.251));
201201
EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.251, 1e-5);
202202
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
203-
flattenResults(std::move(result), result_vector);
203+
flattenMoveResults(std::move(result), result_vector);
204204

205205
EXPECT_TRUE(!result_vector.empty());
206206
EXPECT_NEAR(result_vector[0].distance, 0.25, 0.001);
@@ -253,7 +253,7 @@ inline void runTestConvex(DiscreteContactManager& checker)
253253
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
254254

255255
ContactResultVector result_vector;
256-
flattenResults(std::move(result), result_vector);
256+
flattenMoveResults(std::move(result), result_vector);
257257

258258
EXPECT_TRUE(!result_vector.empty());
259259
EXPECT_NEAR(result_vector[0].distance, -0.53776, 0.001);
@@ -289,7 +289,7 @@ inline void runTestConvex(DiscreteContactManager& checker)
289289
checker.setCollisionObjectsTransform(location);
290290

291291
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
292-
flattenResults(std::move(result), result_vector);
292+
flattenMoveResults(std::move(result), result_vector);
293293

294294
EXPECT_TRUE(result_vector.empty());
295295

@@ -303,7 +303,7 @@ inline void runTestConvex(DiscreteContactManager& checker)
303303
checker.setCollisionMarginData(CollisionMarginData(0.27));
304304
EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.27, 1e-5);
305305
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
306-
flattenResults(std::move(result), result_vector);
306+
flattenMoveResults(std::move(result), result_vector);
307307

308308
EXPECT_TRUE(!result_vector.empty());
309309
EXPECT_NEAR(result_vector[0].distance, 0.26224, 0.001);

tesseract_collision/core/include/tesseract_collision/test_suite/collision_clone_unit.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,7 @@ runTest(DiscreteContactManager& checker, double dist_tol = 0.001, double nearest
133133
checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
134134

135135
ContactResultVector result_vector;
136-
flattenResults(std::move(result), result_vector);
136+
flattenMoveResults(std::move(result), result_vector);
137137

138138
std::vector<int> idx = { 0, 1, 1 };
139139
if (result_vector[0].link_names[0] != "sphere_link")
@@ -146,7 +146,7 @@ runTest(DiscreteContactManager& checker, double dist_tol = 0.001, double nearest
146146
cloned_checker->contactTest(cloned_result, ContactRequest(ContactTestType::CLOSEST));
147147

148148
ContactResultVector cloned_result_vector;
149-
flattenResults(std::move(cloned_result), cloned_result_vector);
149+
flattenMoveResults(std::move(cloned_result), cloned_result_vector);
150150

151151
std::vector<int> cloned_idx = { 0, 1, 1 };
152152
if (cloned_result_vector[0].link_names[0] != "sphere_link")

tesseract_collision/core/include/tesseract_collision/test_suite/collision_compound_compound_unit.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,7 @@ inline void runTestCompound(DiscreteContactManager& checker)
8989
checker.contactTest(result, ContactRequest(ContactTestType::ALL));
9090

9191
ContactResultVector result_vector;
92-
flattenResults(std::move(result), result_vector);
92+
flattenMoveResults(std::move(result), result_vector);
9393

9494
EXPECT_TRUE(!result_vector.empty());
9595
for (const auto& cr : result_vector)
@@ -120,7 +120,7 @@ inline void runTestCompound(ContinuousContactManager& checker)
120120
checker.contactTest(result, ContactRequest(ContactTestType::ALL));
121121

122122
ContactResultVector result_vector;
123-
flattenResults(std::move(result), result_vector);
123+
flattenMoveResults(std::move(result), result_vector);
124124

125125
EXPECT_TRUE(!result_vector.empty());
126126
for (const auto& cr : result_vector)

0 commit comments

Comments
 (0)