Skip to content

Commit e293701

Browse files
committed
fix: improve coverage for multibody
1 parent 2de2ebc commit e293701

File tree

2 files changed

+14
-17
lines changed

2 files changed

+14
-17
lines changed

.cirrus.yml

Lines changed: 4 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -14,18 +14,14 @@ jammy_task:
1414
--jobs=8
1515
--remote_cache=http://$CIRRUS_HTTP_CACHE_HOST
1616
//...
17-
- bazel test
18-
--local_resources=ram=24000
19-
--local_resources=cpu=8
20-
--remote_cache=http://$CIRRUS_HTTP_CACHE_HOST
21-
//...
2217
- apt update && apt install -y lcov
18+
# Coverage will run tests, as well as coverage for the code.
2319
- bazel coverage
2420
--local_resources=ram=24000
2521
--local_resources=cpu=8
2622
--remote_cache=http://$CIRRUS_HTTP_CACHE_HOST
2723
//...
28-
- genhtml --branch-coverage
24+
- sudo genhtml --branch-coverage
2925
--output genhtml
3026
"$(bazel info output_path)/_coverage/_coverage_report.dat"
3127
always:
@@ -51,20 +47,16 @@ noble_task:
5147
--jobs=8
5248
--remote_cache=http://$CIRRUS_HTTP_CACHE_HOST
5349
//...
54-
- bazel test
55-
--local_resources=ram=24000
56-
--local_resources=cpu=8
57-
--remote_cache=http://$CIRRUS_HTTP_CACHE_HOST
58-
//...
5950
- apt update && apt install -y lcov
51+
# Coverage will run tests, as well as coverage for the code.
6052
- bazel coverage
6153
--local_resources=ram=24000
6254
--local_resources=cpu=8
6355
--remote_cache=http://$CIRRUS_HTTP_CACHE_HOST
6456
//...
6557
- genhtml --branch-coverage
6658
--output genhtml
67-
"$(bazel info output_path)/_coverage/_coverage_report.dat"
59+
"bazel-out/_coverage/_coverage_report.dat"
6860
always:
6961
noble_test_artifacts:
7062
path: "bazel-testlogs/**/test.xml"

multibody/test/lcs_factory_test.cc

Lines changed: 10 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,8 @@ GTEST_TEST(LCSFactoryTest, GetNumContactVariables) {
7979
EXPECT_THROW(LCSFactory::GetNumContactVariables(options), std::out_of_range);
8080
}
8181

82-
class LCSFactoryPivotingTest : public ::testing::TestWithParam<std::string> {
82+
class LCSFactoryPivotingTest
83+
: public ::testing::TestWithParam<std::tuple<std::string, int>> {
8384
protected:
8485
void SetUp() override {
8586
std::tie(plant, scene_graph) =
@@ -135,8 +136,9 @@ class LCSFactoryPivotingTest : public ::testing::TestWithParam<std::string> {
135136
VectorXd::Zero(plant->num_positions() + plant->num_velocities());
136137
drake::VectorX<double> input = VectorXd::Zero(plant->num_actuators());
137138

138-
options.contact_model = GetParam();
139-
contact_model = GetContactModelMap().at(GetParam());
139+
options.contact_model = std::get<0>(GetParam());
140+
contact_model = GetContactModelMap().at(options.contact_model);
141+
options.num_friction_directions = std::get<1>(GetParam());
140142
lcs_factory = std::make_unique<LCSFactory>(
141143
*plant, plant_context, *plant_autodiff, *plant_context_autodiff,
142144
contact_pairs, options);
@@ -256,8 +258,11 @@ TEST_P(LCSFactoryPivotingTest, FixSomeModes) {
256258
}
257259

258260
INSTANTIATE_TEST_SUITE_P(ContactModelTests, LCSFactoryPivotingTest,
259-
::testing::Values("frictionless_spring",
260-
"stewart_and_trinkle", "anitescu"));
261+
::testing::Values(std::tuple("frictionless_spring", 0),
262+
std::tuple("stewart_and_trinkle", 1),
263+
std::tuple("stewart_and_trinkle", 2),
264+
std::tuple("anitescu", 1),
265+
std::tuple("anitescu", 2)));
261266

262267
} // namespace test
263268
} // namespace multibody

0 commit comments

Comments
 (0)