Announcements
This release requires Python 3, C++17, and one of either Ubuntu 18.04 or macOS Mojave (or newer). Older platforms and toolchains are no longer supported.
Breaking changes since v0.11.0
These are breaking changes that did not undergo a deprecation period:
- Use dynamic (not static) friction coefficient while computing point contact, i.e., the static coefficient of friction is ignored from both URDF/SDF files when using a discrete MultibodyPlant model with point contact (#12109).
- Previously, in
*.sdf
files a<static>
element within a<model>
was ignored, but is now being parsed. Users with invalid*.sdf
files might receive error messages. The correct solution is to remove the tag (if everything is already welded to the world), or remove any redundant welds (#12226). - drake::multibody::ContactResults methods AddContactInfo and Clear are removed (#12249).
- Rename ImplicitStribeck to Tamsi to match notation in arXiv paper (#12053):
- drake::multibody::ImplicitStribeckSolver is now named TamsiSolver
- drake::multibody::ImplicitStribeckSolverParameters is now named TamsiSolverParameters
- drake::multibody::ImplicitStribeckSolverResults is now named TamsiSolverResults
- Users who compile Drake from source as a bazel external (as in the drake_bazel_external pattern) must set
build --incompatible_remove_legacy_whole_archive=false
in their project’s.bazelrc
for now (#12150). - Remove installed stx headers and stx-config.cmake; Drake no longer provides stx (#12246).
Changes since v0.11.0:
Dynamical Systems
New features
- Add Dormand-Prince (RK45) integrator (#12223)
- Add monitor callback for Simulator trajectories (#12213)
- Add GetMyContextFromRoot methods for subsystems (#12237)
Fixes
- Fix: Implicit Euler and 1-stage Radau now match (#12088)
- Fix: Guard against NaN in integrators (#12217, #12263)
- Fix: Improve PiecewisePolynomial error message (#12183)
Mathematical Program
No changes.
Multibody Dynamics
New features
- Add MultibodyPlant reaction_forces output port (#12123)
- Add MultibodyPlant generalized_contact_forces output port support when using continuous time (#12162)
- Add MultibodyPlant method GetActutationFromArray (#12011)
- Add SceneGraph boolean query HasCollisions (#12211)
- Add multibody
*.sdf
parsing support for link initial poses during CreateDefaultContext (#12226) - Add multibody
*.sdf
parser support for the<static>
element within a<model>
; note that “freezing” articulated joints is not supported (#12226) - Add partial multibody geometry support for the capsule primitive, including urdf parsing (#12254), sdf parsing with custom drake:capsule tag (#12258), visualization (#12235), and vtk and ospray sensor rendering (#12293, #12305)
- Add partial multibody geometry support for the ellipsoid primitive (#12256, #12323)
Fixes
- Fix: Enforce sensible shape specifications (#12172)
- Fix: Improve documentation of Jacobians (#12135, #12192), SpatialAcceleration (#12297), and model instances (#12269)
New hydroelastic contact model in progress (#12102, #12114, #12163, #12184, #12190, #12193, #12212, #12233, #12245, #12285, #12311):
- This is experimental and will change in the near future! (And it will not be used by default.)
- Hydroelastics only supports soft-hard contact with spheres; see demo at
examples/multibody/rolling_sphere
. - For more information, see Elandt, et al. “A pressure field model for fast, robust approximation of net contact force and moment between nominally rigid objects” to appear in IROS 2019. `ArXiv pre-print <https://arxiv.org/abs/1904.11433.
Miscellaneous features and fixes
- Add vector_gen support for yaml input format (#12228, #12244)
- Add DRAKE_LOGGER_TRACE and DRAKE_LOGGER_DEBUG macros (#12309)
- Add DRAKE_EXPECT_NO_THROW helper macros (#12242)
- Add planar_scenegraph_visualizer to pydrake (#12218)
- Fix: In meshcat visualizer, use correct frame for world geometry (#12129)
pydrake bindings
- pydrake.autodiffutils.initializeAutoDiffGivenGradientMatrix (#12229)
- pydrake.geometry.Box.width (#12185)
- pydrake.geometry.Box.depth (#12185)
- pydrake.geometry.Box.height (#12185)
- pydrake.geometry.Box.size (#12185)
- pydrake.geometry.Cylinder.get_length (#12185)
- pydrake.geometry.Cylinder.get_radius (#12185)
- pydrake.geometry.SceneGraph.model_inspector (#12177)
- pydrake.geometry.SceneGraphInspector.GetAllGeometryIds (#12177)
- pydrake.geometry.SceneGraphInspector.GetFrameId (#12177)
- pydrake.geometry.SceneGraphInspector.GetGeometryIdByName (#12177)
- pydrake.geometry.SceneGraphInspector.GetNameByFrameId (#12177)
- pydrake.geometry.SceneGraphInspector.GetNameByGeometryId (#12177)
- pydrake.geometry.SceneGraphInspector.GetPoseInFrame (#12177)
- pydrake.geometry.SceneGraphInspector.GetShape (#12177)
- pydrake.geometry.SceneGraphInspector.num_frames (#12177)
- pydrake.geometry.SceneGraphInspector.num_geometries (#12177)
- pydrake.geometry.SceneGraphInspector.num_sources (#12177)
- pydrake.geometry.Sphere.get_radius (#12185)
- pydrake.math.RotationMatrix.ToAngleAxis (#12313)
- pydrake.multibody.inverse_kinematics.InverseKinematics.context (#12232)
- pydrake.multibody.inverse_kinematics.InverseKinematics.get_mutable_context (#12232)
- pydrake.multibody.plant.CalcContactFrictionFromSurfaceProperties (#12219)
- pydrake.multibody.plant.CoulombFriction.dynamic_friction (#12219)
- pydrake.multibody.plant.CoulombFriction.static_friction (#12219)
- pydrake.multibody.plant.MultibodyPlant.CalcJacobianAngularVelocity (#12229)
- pydrake.multibody.plant.MultibodyPlant.CalcJacobianTranslationalVelocity (#12229)
- pydrake.multibody.plant.MultibodyPlant.GetBodyFrameIdOrThrow (#12177)
- pydrake.multibody.plant.MultibodyPlant.default_coulomb_friction (#12219)
- pydrake.multibody.plant.MultibodyPlant.num_collision_geometries (#12219)
- pydrake.multibody.tree.RigidBody.default_com (#12209)
- pydrake.multibody.tree.RigidBody.default_mass (#12209)
- pydrake.multibody.tree.RigidBody.default_spatial_inertia (#12209)
- pydrake.multibody.tree.RigidBody.default_unit_inertia (#12209)
- pydrake.solvers.mathematicalprogram.EvaluatorBase.SetGradientSparsityPattern (#12232)
- pydrake.solvers.mathematicalprogram.EvaluatorBase.gradient_sparsity_pattern (#12232)
- Add pydrake.systems.sensors.CameraInfo support for pickling (#12131)
Build system and dependencies
- Add macOS Catalina (10.15) support (#12148, #12194)
- Require C++ >= 17 (#12240), Bazel >= 1.1 (#12124, #12224, #12239), and CMake >= 3.10 (#12239)
- Upgrade spdlog to latest release 1.4.2 and switch to building shared library, not header-only (#12322)
- Update sdformat to latest release 8.4.0 (#12268)
- Update gtest to latest release 1.10.0 (#12267)
- Update clang-cindex-python3 to latest commit (#12321)
- Update dependency minimum versions in drake-config.cmake (#12195)
- Remove dependency on stx (#12246)
- Change dReal to private dependency compiled from source (#12186)
- Set FMT_USE_GRISU=1 for fmt (#12318)
- Install sdf data of the planar gripper (#12176)
- Fix: Install and use find-module for GFlags (#12205, #12216, #12250)
- Fix: Install and use find-module for TinyXML2 (#12195)
- Fix: Incompatibilities between Eigen <= 3.3.7 and Apple LLVM 11.0.0 (#12133)
- Fix: Incompatibilities with NumPy 1.17.0 (#12153)
- Remove support for macOS High Sierra (10.13) (#12194)
- Remove support for Ubuntu Xenial (16.04) (#12238)
- Remove support for Python 2 (#12126, #12138, #12146, #12147, #12243, #12155, #12296, #12320).
- Notably, the Drake-specific bazel command line options
bazel build --config python2
andbazel build --config python3
are removed.
- Notably, the Drake-specific bazel command line options
Newly-deprecated APIs
- DRAKE_SPDLOG_TRACE and DRAKE_SPDLOG_DEBUG (#12309)
- drake::optional, drake::nullopt (#12278)
- drake::variant, drake::get, drake::holds_alternative (#12282)
- drake::logging::HandleSpdlogGflags, i.e., text_logging_gflags (#12261, #12287)
- drake::multibody::plant::MultibodyPlant::CalcFrameGeometricJacobianExpressedInWorld (#12197)
- Everything under attic/perception, e.g., RigidBodyPointCloudFilter (#12292)
- Everything under attic/manipulation/dev, e.g., RemoveTreeViewerWrapper (#12294)
- Everything under attic/manipulation/scene_generation, e.g., RandomClutterGenerator (#12294)
- Everything under attic/manipulation/sensors, e.g., Xtion (#12294)
- Some code under attic/manipulation/util, e.g., SimpleTreeVisualizer (#12294)
- Everything under attic/systems/robotInterfaces, e.g., QPLocomotionPlan (#12291)
- Everything under attic/systems/controllers, e.g., InstantaneousQPController (#12291)
- Everything under examples/valkyrie (#12170)
- drake:MakeFileInputStreamOrThrow for protobufs (#12220)
- vector_gen
*.named_vector
protobuf input format (#12228) - //bindings/pydrake/common:drake_optional_pybind BUILD label (#12246)
- //bindings/pydrake/common:drake_variant_pybind BUILD label (#12246)
- //solvers:mathematical_program_lite BUILD label (#12142, #12149)
- @spruce BUILD label (#12161, #12178, #12179, #12180, #12182)
- @stx BUILD label (#12246)
Removal of deprecated APIs
- drake::SpatialForce (#12301)
- Use Vector6<> instead.
- drake::geometry::FramePoseVector::FramePoseVector taking an Isometry3d (#12300)
- Use RigidTransform instead of Isometry3.
- drake::geometry::FramePoseVector::set_value taking an Isometry3d (#12300)
- Use RigidTransform instead of Isometry3.
- drake::geometry::GeometryInstance::GeometryInstance taking an Isometry3d (#12300)
- Use RigidTransform instead of Isometry3.
- drake::geometry::SceneGraphInspector::all_geometry_ids (#12300)
- Use GetAllGeometryIds instead.
- drake::geometry::SceneGraphInspector::X_PG (#12300)
- Use GetPoseInParent instead.
- drake::geometry::SceneGraphInspector::X_FG (#12300)
- Use GetPoseInFrame instead.
- drake::multibody::MultibodyPlant::CalcPointsGeometricJacobianExpressedInWorld (#12157)
- Use CalcJacobianTranslationalVelocity().
- drake::multibody::MultibodyPlant::CalcPointsGeometricJacobianExpressedInWorld (#12157)
- Use CalcJacobianTranslationalVelocity().
- drake::multibody::MultibodyPlant::CalcPointsAnalyticalJacobianExpressedInWorld (#12171)
- Use CalcJacobianTranslationalVelocity().
- drake::multibody::SceneGraph::Finalize(SceneGraph*) (#12144)
- Remove the scene_graph argument instead.
- drake::multibody::SceneGraph::RegisterVisualGeometry(…, SceneGraph*) (#12144)
- Remove the scene_graph argument instead.
- drake::multibody::SceneGraph::RegisterCollisionGeometry(…, SceneGraph*) (#12144)
- Remove the scene_graph argument instead.
- drake::systems::UniformRandomSource (#12144)
- Use RandomSource(kUniform, …) instead.
- drake::systems::GaussianRandomSource (#12144)
- Use RandomSource(kGaussian, …) instead.
- drake::systems::ExponentialRandomSource (#12144)
- Use RandomSource(kExponential, …) instead.
- drake::systems::controllers::plan_eval (everything in namespace) (#12143)
- No replacement.
- drake::systems::controllers::qp_inverse_dynamics (everything in namespace) (#12143)
- No replacement.
- drake::examples::qp_inverse_dynamics (everything in namespace) (#12143)
- No replacement.
- RigidBodyTreeAliasGroups::LoadFromFile (#12143)
- Construct the groups using C++ API calls instead.
- pydrake.multibody.collision module (#12145)
- Use pydrake.attic.multibody.collision instead.
- pydrake.multibody.joints module (#12145)
- Use pydrake.attic.multibody.joints instead.
- pydrake.multibody.parsers module (#12145)
- Use pydrake.attic.multibody.parsers instead.
- pydrake.multibody.rigid_body module (#12145)
- Use pydrake.attic.multibody.rigid_body instead.
- pydrake.multibody.rigid_body_plant module (#12145)
- Use pydrake.attic.multibody.rigid_body_plant instead.
- pydrake.multibody.rigid_body_tree module (#12145)
- Use pydrake.attic.multibody.rigid_body_tree instead.
- pydrake.multibody.shapes module (#12145)
- Use pydrake.attic.multibody.shapes instead.
- pydrake.solvers.ik module (#12145)
- Use pydrake.attic.solvers.ik instead.
- pydrake.systems.framework.LeafSystem._DeclareAbstractInputPort (#12181)
- Use DeclareAbstractInputPort (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclareAbstractInputPort (#12181)
- Use DeclareAbstractInputPort (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclareAbstractParameter (#12181)
- Use DeclareAbstractParameter (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclareNumericParameter (#12181)
- Use DeclareNumericParameter (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclareAbstractOutputPort (#12181)
- Use DeclareAbstractOutputPort (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclareVectorInputPort (#12181)
- Use DeclareVectorInputPort (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclareVectorOutputPort (#12181)
- Use DeclareVectorOutputPort (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclareInitializationEvent (#12181)
- Use DeclareInitializationEvent (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclarePeriodicPublish (#12181)
- Use DeclarePeriodicPublish (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclarePeriodicDiscreteUpdate (#12181)
- Use DeclarePeriodicDiscreteUpdate (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclarePeriodicEvent (#12181)
- Use DeclarePeriodicEvent (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclarePerStepEvent (#12181)
- Use DeclarePerStepEvent (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DoPublish (#12181)
- Use DoPublish (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclareContinuousState (#12181)
- Use DeclareContinuousState (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclareDiscreteState (#12181)
- Use DeclareDiscreteState (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DoCalcTimeDerivatives (#12181)
- Use DoCalcTimeDerivatives (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DoCalcDiscreteVariableUpdates (#12181)
- Use DoCalcDiscreteVariableUpdates (no leading underscore) instead.
- pydrake.systems.framework.LeafSystem._DeclareAbstractState (#12181)
- Use DeclareAbstractState (no leading underscore) instead.
- //multibody BUILD label aliases into the attic (#12159)
- Use the //attic/multibody labels instead.
- Remove F2C build flavor of SNOPT solver, i.e.,
-DWITH_SNOPT=F2C
in CMake or--config snopt_f2c
in Bazel (#12299)- Only the Fortran build flavor is supported from now on.
Notes
This release provides
pre-compiled binaries
named drake-20191108-{bionic|mac}.tar.gz
. See
Stable Releases for instructions on how to use them.
Drake binary releases incorporate a pre-compiled version of SNOPT as part of the Mathematical Program toolbox. Thanks to Philip E. Gill and Elizabeth Wong for their kind support.