Announcements
This release of Drake does NOT support macOS. The macOS homebrew dependencies are rapidly shifting, and we have been unable to keep up.
- The python3.9 upgrade remains an unsolved problem (#14243).
- VTK and drake-visualizer binaries remain an unsolved problem (#14206).
As soon as macOS functionality is restored, we will release new version of Drake that re-adds support.
Breaking changes since v0.23.0
- Temporary removal of macOS support.
- De-referencing a drake::EigenPtr no longer checks for nullptr (#14088). Users relying on the nullptr checks should add their own before dereferencing.
- The exact exception subclasses thrown by VectorBase changed (#14101).
- BasicVector::DoGetAtIndex changed from protected to private.
- SceneGraph::AllocateContext now returns an empty context without any geometry. Users should call CreateDefaultContext instead (#14189). Note that System::AllocateContext generally only ever guarantees allocated storage, not any particular value; in this case, though, it was easy to accidentally rely on geometry being present by default.
Changes since v0.23.0
Dynamical Systems
New features
- Add System::HasInputPort and System::HasOutputPort (#14176)
- Add DiagramBuilder::GetSystems (#14066)
- Add Context::SetStateAndParametersFrom (#14156)
- Add SimulatorConfig, ApplySimulatorConfig, ExtractSimulatorConfig (#14103, #14135, #14150)
- Add publish_period option to ConnectLcmScope (#14062)
Fixes
- Remove VectorBase::operator[] bounds checking (#14101)
- Improve error message for bushing gimbal-lock singularity (#14126)
- Rename accelerometer_sensor.h to accelerometer.h (#14185)
- Rename gyroscope_sensor.h to gyroscope.h (#14185)
Mathematical Program
New features
- AggregateLinearCosts (#14190)
- AggregateQuadraticAndLinearCosts (#14165)
- GenericPolynomial operators (+, -, *, /, ==, pow, hash) (#14053, #14100, #14158)
Fixes
- Improve inlining for EigenPtr (#14088)
- Improve inlining for AutoDiffXd::operator*= (#14171)
- Document that CSDP supports SOCP (#14122)
Multibody Dynamics
New features
- MultibodyPlant calculates the spatial momentum of a subset of model instances (#13916)
- Rewrite GlobalInverseKinematics using MultibodyPlant public API (#13921)
- Add parameters for FixedOffsetFrame (#14137)
- SceneGraph can store geometry data as State or Parameter (#14189)
- SceneGraph provides GeometryVersion to track geometry changes (#14196)
- Add model directives tooling for scene assembly (#14038, #14038, #14144, #14145)
- New hydroelastic contact model in progress (#14178, #14110, #13978, #13808, #14216)
Fixes
- Add unit length constraint on quaternion variables (#14141)
- Improve inlining for RotationalInertia::ReExpress (#14088)
- Change UnitInertia::ReExpress to use frame A instead of frame F (#14112)
- Don’t warn when re-discovering the same package.xml (#14089)
- Merge all multibody/math targets into a single package :spatial_algebra, with header spatial_algebra.h (#14113, #14117)
- Improve error message for LinearBushingRollPitchYaw gimbal-lock singularity (#14126)
Tutorials and examples
- manipulation_station: Add package.xml (#14164)
- manipulation_station: Remove noisy warnings about unsupported joint limits (#14079)
Miscellaneous features and fixes
- find_runfiles: Always return a normalized path (#14211)
- jaco_description: Add package.xml (#14134)
- pr2: Remove
*.obj
files from git and use stl2obj instead (#14219) - realsense2_description: Add d415 camera model (#14203)
- yaml: Fix in std::optional handling (#14076)
- yaml: Add support for BsplineBasis and BsplineTrajectory (#14106)
pydrake bindings
New features
- jupyter: Add joint sliders using publishing callback (#14059)
- meshcat: Add option to set contact cylinder radius (#14131)
- meshcat: Rewrite MeshcatContactVisualizer (#14210, #14218)
- multibody: Allow SpatialVector’s to be pickled (#14104)
- solvers: Add vectorized version of EvalBinding (#14064)
Fixes
- multibody: SpatialVector default constructor initializes to NaN (#14096)
- jupyter: Improve descriptive text for joint sliders (#14130)
- Fix missing runtime module imports (#14072, #14095)
Newly bound
- pydrake.geometry.render.ClippingRange (#13835)
- pydrake.geometry.render.ColorRenderCamera (#13835)
- pydrake.geometry.render.DepthRange (#13835)
- pydrake.geometry.render.DepthRenderCamera (#13835)
- pydrake.geometry.render.RenderCameraCore (#13835)
- pydrake.geometry.render.RenderEngine (#13835)
- pydrake.math.BsplineBasis (#14201)
- pydrake.math.BsplineTrajectory (#14201)
- pydrake.multibody.math.SpatialAcceleration.ComposeWithMovingFrameAcceleration (#14193)
- pydrake.multibody.math.SpatialAcceleration.Shift (#14193)
- pydrake.multibody.math.SpatialForce.Shift (#14098)
- pydrake.multibody.math.SpatialForce.dot (#14098)
- pydrake.multibody.math.SpatialMomentum.Shift (#14193)
- pydrake.multibody.math.SpatialMomentum.dot (#14193)
- pydrake.multibody.math.SpatialVector arithmetic operators (#14098)
- pydrake.multibody.math.SpatialVelocity.ComposeWithMovingFrameVelocity (#14098)
- pydrake.multibody.math.SpatialVelocity.Shift (#14098)
- pydrake.multibody.math.SpatialVelocity.dot (#14098)
- pydrake.multibody.optimization.ContactWrench (#14140)
- pydrake.multibody.optimization.StaticEquilibriumProblem (#14140)
- pydrake.multibody.parsing.PackageMap.AddPackageXml (#14192)
- pydrake.multibody.plant.ContactModel (#14108)
- pydrake.multibody.plant.CoulombFriction default ctor (#14192)
- pydrake.multibody.plant.MultibodyPlant.CalcSpatialMomentumInWorldAboutPoint (#14078)
- pydrake.multibody.plant.MultibodyPlant.GetFloatingBaseBodies (#14139)
- pydrake.multibody.plant.MultibodyPlant.GetFreeBodyPose (#14166)
- pydrake.multibody.plant.MultibodyPlant.get_contact_model (#14108)
- pydrake.multibody.plant.MultibodyPlant.set_contact_model (#14108)
- pydrake.multibody.plant.PropellerInfo (#14192)
- pydrake.multibody.tree.BallRpyJoint.damping (#14195)
- pydrake.multibody.tree.BallRpyJoint.get_default_angles (#14195)
- pydrake.multibody.tree.BallRpyJoint.set_default_angles (#14195)
- pydrake.multibody.tree.Body.GetParentPlant (#14195)
- pydrake.multibody.tree.Body.floating_positions_start (#14166)
- pydrake.multibody.tree.Body.floating_velocities_start (#14166)
- pydrake.multibody.tree.DoorHinge ctor (#14195)
- pydrake.multibody.tree.FixedOffsetFrame additional ctors (#14195)
- pydrake.multibody.tree.ForceElement.GetParentPlant (#14195)
- pydrake.multibody.tree.Frame.GetParentPlant (#14195)
- pydrake.multibody.tree.Joint.AddInDamping (#14195)
- pydrake.multibody.tree.Joint.AddInOneForce (#14195)
- pydrake.multibody.tree.Joint.GetOnePosition (#14195)
- pydrake.multibody.tree.Joint.GetOneVelocity (#14195)
- pydrake.multibody.tree.Joint.GetParentPlant (#14195)
- pydrake.multibody.tree.Joint.type_name (#14195)
- pydrake.multibody.tree.JointActuator.GetParentPlant (#14195)
- pydrake.multibody.tree.JointActuator.get_actuation_vector (#14195)
- pydrake.multibody.tree.JointActuator.set_actuation_vector (#14195)
- pydrake.multibody.tree.LinearBushingRollPitchYaw (#14070)
- pydrake.multibody.tree.MultibodyForces ctor (#14193)
- pydrake.multibody.tree.MultibodyForces.num_bodies (#14193)
- pydrake.multibody.tree.MultibodyForces.num_velocities (#14193)
- pydrake.multibody.tree.PlanarJoint.get_default_rotation (#14195)
- pydrake.multibody.tree.PlanarJoint.get_default_translation (#14195)
- pydrake.multibody.tree.PlanarJoint.set_default_pose (#14195)
- pydrake.multibody.tree.PlanarJoint.set_default_rotation (#14195)
- pydrake.multibody.tree.PlanarJoint.set_default_translation (#14195)
- pydrake.multibody.tree.PrismaticJoint.acceleration_lower_limit (#14195)
- pydrake.multibody.tree.PrismaticJoint.acceleration_upper_limit (#14195)
- pydrake.multibody.tree.PrismaticJoint.get_default_translation (#14195)
- pydrake.multibody.tree.PrismaticJoint.position_lower_limit (#14195)
- pydrake.multibody.tree.PrismaticJoint.position_upper_limit (#14195)
- pydrake.multibody.tree.PrismaticJoint.set_default_translation (#14195)
- pydrake.multibody.tree.PrismaticJoint.velocity_lower_limit (#14195)
- pydrake.multibody.tree.PrismaticJoint.velocity_upper_limit (#14195)
- pydrake.multibody.tree.RevoluteJoint additional ctors (#14195)
- pydrake.multibody.tree.RevoluteJoint.acceleration_lower_limit (#14195)
- pydrake.multibody.tree.RevoluteJoint.acceleration_upper_limit (#14195)
- pydrake.multibody.tree.RevoluteJoint.get_angular_rate (#14195)
- pydrake.multibody.tree.RevoluteJoint.get_default_angle (#14195)
- pydrake.multibody.tree.RevoluteJoint.position_lower_limit (#14195)
- pydrake.multibody.tree.RevoluteJoint.position_upper_limit (#14195)
- pydrake.multibody.tree.RevoluteJoint.set_angular_rate (#14195)
- pydrake.multibody.tree.RevoluteJoint.set_default_angle (#14195)
- pydrake.multibody.tree.RevoluteJoint.velocity_lower_limit (#14195)
- pydrake.multibody.tree.RevoluteJoint.velocity_upper_limit (#14195)
- pydrake.multibody.tree.RigidBody additional ctors (#14195)
- pydrake.multibody.tree.RigidBody.SetCenterOfMassInBodyFrame (#14195)
- pydrake.multibody.tree.RigidBody.SetMass (#14195)
- pydrake.multibody.tree.RigidBody.SetSpatialInertiaInBodyFrame (#14195)
- pydrake.multibody.tree.RigidBody.default_rotational_inertia (#14195)
- pydrake.multibody.tree.RotationalInertia (many methods) (#14193)
- pydrake.multibody.tree.RotationalInertia.ReExpress (#14111, #14194)
- pydrake.multibody.tree.RotationalInertia.UnitInertia.ReExpress (#14111, #14194)
- pydrake.multibody.tree.SpatialInertia.MakeFromCentralInertia (#14193)
- pydrake.multibody.tree.UniformGravityFieldElement default ctor (#14195)
- pydrake.multibody.tree.UniformGravityFieldElement.CalcGravityGeneralizedForces (#14195)
- pydrake.multibody.tree.UniformGravityFieldElement.kDefaultStrength (#14195)
- pydrake.multibody.tree.UnitInertia (many methods) (#14193)
- pydrake.multibody.tree.UniversalJoint.get_default_angles (#14195)
- pydrake.multibody.tree.UniversalJoint.set_default_angles (#14195)
- pydrake.solvers.mathematicalprogram.MathematicalProgram.AddLorentzConeConstraint (#14119)
- pydrake.solvers.mathematicalprogram.MathematicalProgram.AddRotatedLorentzConeConstraint (#14120)
- pydrake.symbolic.Monomial ctor (#14222)
- pydrake.systems.framework.BasicVector.set_value (#14231)
- pydrake.systems.framework.ContinuousState.SetFrom (#14231)
- pydrake.systems.framework.ContinuousState.SetFromVector (#14231)
- pydrake.systems.framework.ContinuousState.ctors (#14231)
- pydrake.systems.framework.ContinuousState.get_generalized_position (#14231)
- pydrake.systems.framework.ContinuousState.get_generalized_velocity (#14231)
- pydrake.systems.framework.ContinuousState.get_misc_continuous_state (#14231)
- pydrake.systems.framework.ContinuousState.get_mutable_generalized_position (#14231)
- pydrake.systems.framework.ContinuousState.get_mutable_generalized_velocity (#14231)
- pydrake.systems.framework.ContinuousState.get_mutable_misc_continuous_state (#14231)
- pydrake.systems.framework.ContinuousState.num_q (#14231)
- pydrake.systems.framework.ContinuousState.num_v (#14231)
- pydrake.systems.framework.ContinuousState.num_z (#14231)
- pydrake.systems.framework.ContinuousState.operator[] (#14231)
- pydrake.systems.framework.DiscreteValues ctors (#14231)
- pydrake.systems.framework.DiscreteValues.SetFrom (#14231)
- pydrake.systems.framework.DiscreteValues.operator[] (#14231)
- pydrake.systems.framework.VectorBase.PlusEqScaled (#14231)
- pydrake.systems.framework.VectorBase.SetFrom (#14231)
- pydrake.systems.framework.VectorBase.operator[] (#14231)
Build system and dependencies
- Upgrade to Xcode 12 on Catalina (#14142)
- Upgrade buildifier to latest release 3.5.0 (#14152)
- Upgrade dreal to latest release 4.20.09.1 (#14083)
- Upgrade fcl to latest commit (#14063)
- Upgrade googlebenchmark to latest release (#14154)
- Upgrade ignition_math to latest release 6.6.0 (#14148)
- Upgrade rules_python to latest release 0.0.3 (#14161)
- Upgrade sdformat to latest release 9.3.0 (#14147)
- Upgrade spdlog to latest release 1.8.1 (#14153)
- Upgrade styleguide latest commit (#14217)
- Downgrade doxygen to 1.8.15 on macOS (#14169)
- Fix snopt external for Bazel 3.6 (#14179)
- Fix compilation errors vs Eigen 3.3.8 (#14159)
- Do not install certain private headers (#14221)
- Cleanup pkg-config path for ibex (#14109)
- Clarify which vector_gen macros are to be used outside of Drake (#14092)
Newly-deprecated APIs
- drake/math/expmap.h include path (#14099)
- drake/multibody/math/spatial_acceleration.h include path (#14117)
- drake/multibody/math/spatial_force.h include path (#14117)
- drake/multibody/math/spatial_momentum.h include path (#14117)
- drake/multibody/math/spatial_vector.h include path (#14117)
- drake/multibody/math/spatial_velocity.h include path (#14117)
- drake/systems/analysis/simulator_flags.h include path (#14135)
- drake/systems/sensors/accelerometer_sensor.h include path (#14185)
- drake/systems/sensors/gyroscope_sensor.h include path (#14185)
- drake::math::closestExpmap (#14099)
- drake::math::expmap2quat (#14099)
- drake::math::quat2expmap (#14099)
- drake::math::quat2expmapSequence (#14099)
- drake::multibody::math::SpatialVector::ScalarType (#14188)
- drake::systems::Context::FixInputPort() (#14093)
- tools/vector_gen/vector_gen.bzl:drake_cc_vector_gen (#14092)
- tools/vector_gen/vector_gen.bzl:drake_vector_gen_lcm_sources (#14092)
- The numpy external (#14116)
Removal of deprecated items
- pydrake.geometry.SceneGraphInspector.GetNameByFrameId (#14128)
- pydrake.geometry.SceneGraphInspector.GetNameByGeometryId (#14128)
- schema::Rotation backwards compatibility for rotation_rpy_deg (#14143)
- Automatic conversion and interop between RigidTransform/Isometry3 (#14128)
- drake::math::RigidTransform::linear
- drake::math::RigidTransform::matrix
- drake::math::RigidTransform::operator Isometry3
- All functions within manipulation/util/bot_core_lcm_encode_decode.h (#14128)
- ::EncodeVector3d
- ::DecodeVector3d
- ::EncodeQuaternion
- ::DecodeQuaternion
- ::EncodePose
- ::DecodePose
- ::EncodeTwist
- ::DecodeTwist
Notes
This release provides pre-compiled binaries named
drake-20201026-{bionic|focal|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.