Closed jwnimmer-tri closed 3 years ago
See #14876 for a report of one probable incompatibility.
Looking at https://eigen.tuxfamily.org/index.php?title=Main_Page and clicking to unfold the rc1 announcement, we see
Eigen 3.4-rc1 has been released on April 19, 2021. Depending on the amount of reported issues, 3.4 will be released late April or early May.
Upgrading priority.
Depending on the amount of reported issues, 3.4 will be released late April or early May
Oh dear.
https://drake-jenkins.csail.mit.edu/view/Production/job/mac-big-sur-unprovisioned-clang-bazel-nightly-release/70/consoleFull was a failed build on macOS with the RC (link should be available through mid-July).
PR #15142 was created to try out the 3.4 branch (6/7/2021) on both Linux and Mac. A summary of results with relevant CDash links to full output are listed below:
Build Errors
multibody/tree/multibody_tree.cc:2939:36: error: no viable overloaded '='
Su(actuator_index, user_index) = 1.0;
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ ^ ~~~
In file included from common/trajectories/bspline_trajectory.cc:1:
In file included from bazel-out/k8-opt/bin/common/trajectories/_virtual_includes/bspline_trajectory/drake/common/trajectories/bspline_trajectory.h:6:
In file included from bazel-out/k8-opt/bin/common/_virtual_includes/drake_bool/drake/common/drake_bool.h:5:
In file included from external/eigen/Eigen/Core:19:
external/eigen/Eigen/src/Core/util/Macros.h:1325:34: error: value of type 'Eigen::CwiseBinaryOp<Eigen::internal::scalar_cmp_op<double, double, Eigen::internal::cmp_EQ>, const Eigen::ArrayWrapper<const Eigen::Matrix<double, -1, -1, 0, -1, -1> >, const Eigen::ArrayWrapper<const Eigen::Matrix<double, -1, -1, 0, -1, -1> > >' is not contextually convertible to 'bool'
bool all(T t, Ts ... ts){ return t && all(ts...); }
solvers/csdp_solver.cc:102:24: error: assigning to 'Eigen::DenseCoeffsBase<Eigen::Matrix<double, -1, 1, 0, -1, 1>, 1>::Scalar' (aka 'double') from incompatible type 'typename internal::enable_if<(!IsRowMajor) && (!(internal::get_compile_time_incr<typename IvcType<TypeSafeIndex<FreeVariableTag> >::type>::value == 1 || internal::is_valid_index_type<TypeSafeIndex<FreeVariableTag> >::value)), IndexedView<const Matrix<double, -1, 1, 0, -1, 1>, typename IvcType<TypeSafeIndex<FreeVariableTag> >::type, IvcIndex> >::type' (aka 'Eigen::IndexedView<const Eigen::Matrix<double, -1, 1, 0, -1, 1>, drake::TypeSafeIndex<drake::solvers::internal::FreeVariableTag>, Eigen::internal::SingleRange>')
(*prog_sol)(i) = s_val(std::get<SdpaFreeFormat::FreeVariableIndex>(
^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
multibody/plant/test/multibody_plant_reflected_inertia_test.cc:88:48: error: no viable conversion from 'typename internal::enable_if<(!IsRowMajor) && (!(internal::get_compile_time_incr<typename IvcType<TypeSafeIndex<JointActuatorElementTag> >::type>::value == 1 || internal::is_valid_index_type<TypeSafeIndex<JointActuatorElementTag> >::value)), IndexedView<const Matrix<double, -1, 1, 0, -1, 1>, typename IvcType<TypeSafeIndex<JointActuatorElementTag> >::type, IvcIndex> >::type' (aka 'Eigen::IndexedView<const Eigen::Matrix<double, -1, 1, 0, -1, 1>, drake::TypeSafeIndex<drake::multibody::JointActuatorElementTag>, Eigen::internal::SingleRange>') to 'double'
joint_actuator.set_default_rotor_inertia(rotor_inertias(index));
^~~~~~~~~~~~~~~~~~~~~
bazel-out/k8-opt/bin/multibody/tree/_virtual_includes/multibody_tree_core/drake/multibody/tree/joint_actuator.h:183:41: note: passing argument to parameter 'rotor_inertia' here
void set_default_rotor_inertia(double rotor_inertia) {
^
multibody/plant/test/multibody_plant_reflected_inertia_test.cc:89:45: error: no viable conversion from 'typename internal::enable_if<(!IsRowMajor) && (!(internal::get_compile_time_incr<typename IvcType<TypeSafeIndex<JointActuatorElementTag> >::type>::value == 1 || internal::is_valid_index_type<TypeSafeIndex<JointActuatorElementTag> >::value)), IndexedView<const Matrix<double, -1, 1, 0, -1, 1>, typename IvcType<TypeSafeIndex<JointActuatorElementTag> >::type, IvcIndex> >::type' (aka 'Eigen::IndexedView<const Eigen::Matrix<double, -1, 1, 0, -1, 1>, drake::TypeSafeIndex<drake::multibody::JointActuatorElementTag>, Eigen::internal::SingleRange>') to 'double'
joint_actuator.set_default_gear_ratio(gear_ratios(index));
^~~~~~~~~~~~~~~~~~
bazel-out/k8-opt/bin/multibody/tree/_virtual_includes/multibody_tree_core/drake/multibody/tree/joint_actuator.h:189:38: note: passing argument to parameter 'gear_ratio' here
void set_default_gear_ratio(double gear_ratio) {
multibody/inverse_kinematics/test/global_inverse_kinematics_reachable_test.cc:80:17: error: no viable conversion from 'typename internal::enable_if<(!IsRowMajor) && (!(internal::get_compile_time_incr<typename IvcType<TypeSafeIndex<JointElementTag> >::type>::value == 1 || internal::is_valid_index_type<TypeSafeIndex<JointElementTag> >::value)), IndexedView<Matrix<double, 7, 1, 0, 7, 1>, typename IvcType<TypeSafeIndex<JointElementTag> >::type, IvcIndex> >::type' (aka 'Eigen::IndexedView<Eigen::Matrix<double, 7, 1, 0, 7, 1>, drake::TypeSafeIndex<drake::multibody::JointElementTag>, Eigen::internal::SingleRange>') to 'double'
EXPECT_NEAR(q_global_ik(plant_->GetJointByName("iiwa_joint_2").index()),
^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
math/test/rotation_conversion_test.cc:174:34: error: 'LinSpaced' is deprecated [-Werror,-Wdeprecated-declarations]
auto roll = Eigen::VectorXd::LinSpaced(Eigen::Sequential, kSweepSize,
In file included from multibody/fixed_fem/dev/fem_model_base.cc:1:
In file included from bazel-out/k8-opt/bin/multibody/fixed_fem/dev/_virtual_includes/fem_model_base/drake/multibody/fixed_fem/dev/fem_model_base.h:11:
bazel-out/k8-opt/bin/multibody/fixed_fem/dev/_virtual_includes/dirichlet_boundary_condition/drake/multibody/fixed_fem/dev/dirichlet_boundary_condition.h:111:30: error: no viable overloaded '='
(*residual)(dof_index) = 0;
~~~~~~~~~~~~~~~~~~~~~~ ^ ~
Fixes and workarounds are in PR #15142. There is currently one build error and 20 failing tests. Results are the same across all platforms and configurations.
To test locally, checkout branch from PR and revert referenced commit. To sanity check against Eigen 3.3, update eigen/repository.bzl
to branch = "3.3.9"
instead of branch = "3.4"
[x] Remove deprecated function (#15321)
[x] Ensure we're using drake::all
not Eigen::all
(#15323)
[ ] EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR
error (#15335)
[x] Can no longer reproduce ~robot_plan_interpolator_test: Use EXPECT_NEAR
instead of EXPECT_FLOAT_EQ
~ (#15322)
[x] Fixed in Eigen at 05bab813 ~Fix errors introduced in Eigen commit a235ddef~
[ ] Build error: 'static_assert failed ...' To test:
bazel test multibody/tree:screw_mobilizer_test
...
In file included from multibody/tree/test/screw_mobilizer_test.cc:1:
In file included from bazel-out/darwin-opt/bin/multibody/tree/_virtual_includes/multibody_tree_core/drake/multibody/tree/screw_mobilizer.h:5:
In file included from bazel-out/darwin-opt/bin/common/_virtual_includes/default_scalars/drake/common/default_scalars.h:3:
In file included from bazel-out/darwin-opt/bin/common/_virtual_includes/autodiff/drake/common/autodiff.h:12:
In file included from external/eigen/Eigen/Core:271:
external/eigen/Eigen/src/Core/DenseCoeffsBase.h:142:7: error: static_assert failed due to requirement 'internal::evaluator<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 1, 1, 0, 1, 1> > >::Flags & LinearAccessBit' "THIS_COEFFICIENT_ACCESSOR_TAKING_ONE_ACCESS_IS_ONLY_FOR_EXPRESSIONS_ALLOWING_LINEAR_ACCESS"
EIGEN_STATIC_ASSERT(internal::evaluator<Derived>::Flags & LinearAccessBit,
^ ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
external/eigen/Eigen/src/Core/util/StaticAssert.h:33:40: note: expanded from macro 'EIGEN_STATIC_ASSERT'
#define EIGEN_STATIC_ASSERT(X,MSG) static_assert(X,#MSG);
^ ~
external/eigen/Eigen/src/Core/DenseCoeffsBase.h:182:14: note: in instantiation of member function 'Eigen::DenseCoeffsBase<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 1, 1, 0, 1, 1> >, 0>::coeff' requested here
return coeff(index);
^
external/eigen/Eigen/src/Core/StlIterators.h:299:50: note: in instantiation of member function 'Eigen::DenseCoeffsBase<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 1, 1, 0, 1, 1> >, 0>::operator()' requested here
reference operator*() const { return (*mp_xpr)(m_index); }
^
external/gtest/googletest/include/gtest/gtest-printers.h:423:30: note: in instantiation of member function 'Eigen::internal::generic_randaccess_stl_iterator<const Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 1, 1, 0, 1, 1> > >::operator*' requested here
internal::UniversalPrint(*it, os);
^
external/gtest/googletest/include/gtest/gtest-printers.h:503:3: note: in instantiation of function template specialization 'testing::internal::DefaultPrintTo<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 1, 1, 0, 1, 1> > >' requested here
DefaultPrintTo(
^
external/gtest/googletest/include/gtest/gtest-printers.h:679:5: note: in instantiation of function template specialization 'testing::internal::PrintTo<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 1, 1, 0, 1, 1> > >' requested here
PrintTo(value, os);
^
external/gtest/googletest/include/gtest/gtest-printers.h:869:25: note: (skipping 4 contexts in backtrace; use -ftemplate-backtrace-limit=0 to see all)
UniversalPrinter<T1>::Print(value, os);
^
external/gtest/googletest/include/gtest/gtest-printers.h:379:39: note: in instantiation of member function 'testing::internal::FormatForComparison<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 1, 1, 0, 1, 1> >, Eigen::Matrix<double, -1, -1, 0, -1, -1> >::Format' requested here
return FormatForComparison<T1, T2>::Format(value);
^
external/gtest/googletest/include/gtest/gtest.h:1510:20: note: in instantiation of function template specialization 'testing::internal::FormatForComparisonFailureMessage<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 1, 1, 0, 1, 1> >, Eigen::Matrix<double, -1, -1, 0, -1, -1> >' requested here
FormatForComparisonFailureMessage(rhs, lhs),
^
external/gtest/googletest/include/gtest/gtest.h:1531:10: note: in instantiation of function template specialization 'testing::internal::CmpHelperEQFailure<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 1, 1, 0, 1, 1> > >' requested here
return CmpHelperEQFailure(lhs_expression, rhs_expression, lhs, rhs);
^
external/gtest/googletest/include/gtest/gtest.h:1554:12: note: in instantiation of function template specialization 'testing::internal::CmpHelperEQ<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 1, 1, 0, 1, 1> > >' requested here
return CmpHelperEQ(lhs_expression, rhs_expression, lhs, rhs);
^
multibody/tree/test/screw_mobilizer_test.cc:284:3: note: in instantiation of function template specialization 'testing::internal::EqHelper::Compare<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 1, 1, 0, 1, 1> >, nullptr>' requested here
EXPECT_EQ(N, Matrix1d::Identity());
^
external/gtest/googletest/include/gtest/gtest.h:2028:54: note: expanded from macro 'EXPECT_EQ'
EXPECT_PRED_FORMAT2(::testing::internal::EqHelper::Compare, val1, val2)
[ ] 'the environment does not have an entry for the variable ...' (may be related to #14927) examples/pendulum:print_symbolic_dynamics_test, multibody/plant:multibody_plant_symbolic_test, multibody/plant:spring_mass_system_test
The following tests are failing without much output in the normal test results. Leak sanitizer results may provide some clues?
@jwnimmer-tri it would be helpful to have some Eigen experts dig into these failures.
@BetsyMcPhail
These three completed checkbox commits seem like good fixes. Could you PR each one to Drake individually, so that we can get them merged and out of the way to narrow down the branch?
You can assign these two to me for review.
Remove deprecated function (1a3083f)
robot_plan_interpolator_test: Use EXPECT_NEAR instead of EXPECT_FLOAT_EQ (7b03907)
This one looks correct at first glance, but please assign to @soonho-tri to review just to be sure.
Ensure we're using drake::all not Eigen::all (505f2e2)
EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR error (temp. workaround to get tests running 8a3532d, need an actual solution)
I spent a few minutes investigating, and I don't think there is a good systemic fix. I think a more polished version of your current work-around is the best way to go, as follows.
For lines like this, which fail because an Eigen::Matrix
lookup uses a TypeSafeIndex
(in this case, the actuator.index()
) ...
B(actuator.joint().velocity_start(), actuator.index()) = 1;
... we just need to guide the implicit conversion to int, like so ...
B(actuator.joint().velocity_start(), int(actuator.index())) = 1;
Note that I use the int constructor int(...)
instead of static_cast<int>(...)
, and that I keep it inline instead of factoring it into a different named variable just to change the type.
I suspect that more brief approach will lead to a slightly more readable patch, that would be acceptable to merge to master now. Could you try opening a PR with that?
Build error: 'static_assert failed ...' ... cassie_benchmark test failures
I suspect that our forked copy of common/autodiffxd.h
might be incompatible with Eigen 3.4. Maybe I can nominate @rpoyner-tri to root cause and fix these two failures.
Edit: Filed as https://github.com/RobotLocomotion/drake/issues/15401 now.
Any tests that are failing related to symbolic::Expression
are probably due to #15298. We could apply that work-around to the branch for now, to help clear the deck of those errors until upstream gets fixed.
Any tests that are failing related to
symbolic::Expression
are probably due to #15298. We could apply that work-around to the branch for now, to help clear the deck of those errors until upstream gets fixed.
Sounds good to me. I will apply the patch now.
EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR error (temp. workaround to get tests running 8a3532d, need an actual solution)
I spent a few minutes investigating, and I don't think there is a good systemic fix. I think a more polished version of your current work-around is the best way to go, as follows.
For lines like this, which fail because an
Eigen::Matrix
lookup uses aTypeSafeIndex
(in this case, theactuator.index()
) ...B(actuator.joint().velocity_start(), actuator.index()) = 1;
... we just need to guide the implicit conversion to int, like so ...
B(actuator.joint().velocity_start(), int(actuator.index())) = 1;
Note that I use the int constructor
int(...)
instead ofstatic_cast<int>(...)
, and that I keep it inline instead of factoring it into a different named variable just to change the type.I suspect that more brief approach will lead to a slightly more readable patch, that would be acceptable to merge to master now. Could you try opening a PR with that?
Using just the int constructor makes cpplint unhappy, For example, in multibody_plant.cc,
--- a/multibody/plant/multibody_plant.cc
+++ b/multibody/plant/multibody_plant.cc
@@ -768,7 +768,7 @@ MatrixX<T> MultibodyPlant<T>::MakeActuationMatrix() const {
// This method assumes actuators on single dof joints. Assert this
// condition.
DRAKE_DEMAND(actuator.joint().num_velocities() == 1);
- B(actuator.joint().velocity_start(), actuator.index()) = 1;
+ B(actuator.joint().velocity_start(), int(actuator.index())) = 1;
}
return B;
}
Results in style error:
==================== Test output for //multibody/plant:py/multibody_plant_core_cpplint:
multibody/plant/multibody_plant.cc:771: Using deprecated casting style. Use static_cast<int>(...) instead [readability/casting] [4]
Oops. What about int{actuator.index()}
with curlies instead?
At this point, I think this meta-issue isn't useful anymore, so I'll close it.
We'll leave #15142 open as our canary branch. Once it's passing all CI (even post-merge) with zero diffs vs master other than using Eigen 3.4 in the repository rule, then our job is done.
As we identify acute problems in the canary branch, we'll open specific issues for them.
Eigen has entered the release candidate process for a 3.4.0 release. It's likely that Drake will incur some kinds of compilation errors due to the changes.
It's not clear yet how long it will be until a final release, but we should probably test against the candidates, and either adapt Drake to meet the new requirements, or else file Eigen upstream bugs if appropriate.
Since homebrew will immediately adopt Eigen 3.4.0 once it's tagged, we should try to get ahead of that failure mode.
Note, however, that we can probably test the Eigen 3.4.0 candidates on Ubuntu, even though the motivation here is to keep macOS working.