Skip to content

Commit

Permalink
Initialize the AutoDiffXd value field to NaN (RobotLocomotion#15792)
Browse files Browse the repository at this point in the history
* Initialize the AutoDiffXd value field to NaN.
  • Loading branch information
sherm1 authored Sep 21, 2021
1 parent cbeebdc commit 58becee
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 1 deletion.
21 changes: 20 additions & 1 deletion common/autodiffxd.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#endif

#include <cmath>
#include <limits>
#include <ostream>

#include <Eigen/Dense>
Expand Down Expand Up @@ -58,6 +59,19 @@ namespace Eigen {
// value, and only allocate when needed, as determined by the compiler. For C++
// considerations, see Scott Meyers' _Effective Modern C++_ Item 41. See #13985
// for more discussion of Drake considerations.
//
// @note default initialization
// Value initialization is not part of the Eigen::AutoDiffScalar contract nor
// part of the contract for our AutoDiffXd specialization of that template
// class. Thus no code should be written assuming that default-constructed
// AutoDiffXd objects will be value initialized. However, leaving the value
// uninitialized triggered hard-to-eliminate maybe-uninitialized warnings (not
// necessarily spurious) from some versions of gcc (not seen with clang).
// After determining that there is a negligible effect on performance, we
// decided (see PRs #15699 and #15792) to initialize the value member to avoid
// those warnings. Initializing to NaN (as opposed to zero) ensures that no code
// will function with uninitialized AutoDiffXd objects, just as it should not
// with any other Eigen::AutoDiffScalar.
template <>
class AutoDiffScalar<VectorXd>
: public internal::auto_diff_special_op<VectorXd, false> {
Expand All @@ -70,6 +84,8 @@ class AutoDiffScalar<VectorXd>
using Base::operator+;
using Base::operator*;

// Default constructor leaves the value effectively uninitialized and the
// derivatives vector zero length.
AutoDiffScalar() {}

AutoDiffScalar(const Scalar& value, int nbDer, int derNumber)
Expand Down Expand Up @@ -374,7 +390,10 @@ class AutoDiffScalar<VectorXd>
}

protected:
Scalar m_value;
// See class documentation above for why we are initializing the value here
// even though that is not part of the Eigen::AutoDiffScalar contract.
// Scalar is always double in this specialization.
Scalar m_value{std::numeric_limits<double>::quiet_NaN()};
DerType m_derivatives;
};

Expand Down
8 changes: 8 additions & 0 deletions math/test/autodiff_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,14 @@ TEST_F(AutodiffTest, ToGradientMatrix) {
<< gradients;
}

// See note in class documentation for our AutoDiffXd specialization in
// common/autodiffxd.h for why we initialize the value field even though
// that is not part of the Eigen::AutoDiffScalar contract.
GTEST_TEST(AdditionalAutodiffTest, ValueIsInitializedToNaN) {
AutoDiffXd autodiff;
EXPECT_TRUE(std::isnan(autodiff.value()));
}

GTEST_TEST(AdditionalAutodiffTest, DiscardGradient) {
// Test the double case:
Eigen::Matrix2d test = Eigen::Matrix2d::Identity();
Expand Down

0 comments on commit 58becee

Please sign in to comment.