Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion examples/multibody/cart_pole/test/cart_pole_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,6 @@ TEST_F(CartPoleTest, SystemDynamics) {
const Vector2<double> q(2.5, M_PI / 3);
const Vector2<double> v(-1.5, 0.5);

Matrix2<double> M;
cart_slider_->set_translation(context_.get(), q(0));
cart_slider_->set_translation_rate(context_.get(), v(0));
pole_pin_->set_angle(context_.get(), q(1));
Expand Down
1 change: 0 additions & 1 deletion math/test/rigid_transform_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -854,7 +854,6 @@ GTEST_TEST(RigidTransform, SpecializedTransformOperators) {

// Test ApplyAxialRotation().
const Vector3d p_C(1.0, 2.0, 3.0);
Vector3d p_B; // reusable result
EXPECT_TRUE(CompareMatrices(Xform::ApplyAxialRotation<0>(xrX_BC, p_C),
xrX_BC * p_C, kTol));
EXPECT_TRUE(CompareMatrices(Xform::ApplyAxialRotation<1>(yrX_BC, p_C),
Expand Down
2 changes: 0 additions & 2 deletions math/test/rotation_matrix_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -720,7 +720,6 @@ GTEST_TEST(RotationMatrix, AxialRotationOperators) {

// Test ApplyAxialRotation().
const Vector3d v_C(1.0, 2.0, 3.0);
Vector3d v_B; // reusable result
EXPECT_TRUE(CompareMatrices(Rmat::ApplyAxialRotation<0>(xR_BC, v_C),
xR_BC * v_C, kTol));
EXPECT_TRUE(CompareMatrices(Rmat::ApplyAxialRotation<1>(yR_BC, v_C),
Expand Down Expand Up @@ -803,7 +802,6 @@ GTEST_TEST(RotationMatrix, AxialRotationOptimizations) {

// But ... ApplyAxialRotation() should work anyway with this junk in place.
const Vector3d v_C(1.0, 2.0, 3.0);
Vector3d v_B;
EXPECT_TRUE(CompareMatrices(Rmat::ApplyAxialRotation<1>(yR_BC_mangled, v_C),
yR_BC * v_C, kTol));

Expand Down
3 changes: 0 additions & 3 deletions solvers/mixed_integer_rotation_constraint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -520,9 +520,6 @@ void AddBoxSphereIntersectionConstraints(
double cos_theta = d;
const double theta = std::acos(cos_theta);

Eigen::Matrix<double, 1, 6> a;
Eigen::Matrix<double, 3, 9> A_cross;

Eigen::Vector3d orthant_normal;
Vector3<Expression> orthant_c;
for (int o = 0; o < 8; o++) { // iterate over orthants
Expand Down
3 changes: 0 additions & 3 deletions solvers/test/mathematical_program_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4369,9 +4369,6 @@ GTEST_TEST(TestMathematicalProgram, AddConstraintMatrix2) {
ASSERT_EQ(prog.GetAllConstraints().size(), 1);
ASSERT_EQ(prog.GetAllLinearConstraints().size(), 1);

Eigen::Matrix<double, 4, 2> A_expected;
Eigen::Matrix<double, 4, 1> lower_bound_expected;
Eigen::Matrix<double, 4, 1> upper_bound_expected;
std::array<std::array<Eigen::RowVector2d, 2>, 2> coeff;
coeff[0][0] << 1, 0;
coeff[0][1] << 1, 2;
Expand Down
12 changes: 6 additions & 6 deletions systems/primitives/test/affine_system_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -142,12 +142,12 @@ TEST_F(AffineSystemTest, UpdateCoefficients) {
}

TEST_F(AffineSystemTest, UpdateCoefficientsButWrongSize) {
const Eigen::Matrix<double, 2, 3> new_A;
const Eigen::Matrix<double, 3, 2> new_B;
const Eigen::Vector3d new_f0;
const Eigen::Matrix3d new_C;
const Eigen::Matrix4d new_D;
const Eigen::Vector4d new_y0;
const Eigen::Matrix<double, 2, 3> new_A = Eigen::Matrix<double, 2, 3>::Zero();
const Eigen::Matrix<double, 3, 2> new_B = Eigen::Matrix<double, 3, 2>::Zero();
const Eigen::Vector3d new_f0 = Eigen::Vector3d::Zero();
const Eigen::Matrix3d new_C = Eigen::Matrix3d::Zero();
const Eigen::Matrix4d new_D = Eigen::Matrix4d::Zero();
const Eigen::Vector4d new_y0 = Eigen::Vector4d::Zero();

const std::string error_msg_regrex =
"^New and current .* have different sizes\\.$";
Expand Down
2 changes: 1 addition & 1 deletion systems/primitives/test/multilayer_perceptron_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -330,7 +330,7 @@ GTEST_TEST(MultilayerPereceptronTest, BatchOutputWithGradients) {
GTEST_TEST(MultilayerPerceptronTest, BatchOutputWithGradientsThrows) {
MultilayerPerceptron<double> mlp({2, 2});
auto context = mlp.CreateDefaultContext();
const Eigen::Matrix2d X;
const Eigen::Matrix2d X = Eigen::Matrix2d::Zero();
Eigen::Matrix2d Y, dYdX;

DRAKE_EXPECT_THROWS_MESSAGE(
Expand Down