Announcements
- This release introduces support for macOS 12 (“Monterey”).
- This configuration is not yet tested by our Jenkins continuous integration builds, so should be considered to be “experimental” for the moment. We expect to provide full support as of our next release.
Breaking changes since v0.35.0
- This release removes support for MacOS 10.15 (“Catalina”), officially ending Drake support for MacOS 10 (#16041, #16055).
- Users should upgrade to MacOS 11 (“Big Sur”).
- We now return
const VectorX&rather thanVectorBlockfromport.Eval()and similar methods, where possible (#16031).- This is a breaking change in cases where callers explicitly denote the return type as a
VectorBlock; we expect that most callers are not relying onVectorBlocksemantics. - Virtuals defined by
VectorSystemstill takeVectorBlockparameters, so user subclasses will not be affected.
- This is a breaking change in cases where callers explicitly denote the return type as a
- Unused models (sphere, box, etc.) removed from sensors directory (#15975)
Changes since v0.35.0
Dynamical Systems
New features
- Add
systems::sensors::OptitrackReceiver(#16011) - Add
VectorX-returning value methods tosystems::framework::BasicVectorandsystems::framework::DiscreteValues(#16051) - DiagramBuilder fails-fast if used after Build (#16082)
Fixes
- None
Mathematical Program
New features
- Add
IrisInConfigurationSpacewith Ibex geometry optimization (#15789) - Add
GetGraphvizStringtoGraphOfConvexSets(#16017) - Cleanup memory management in
GraphOfConvexSets; this includes API-breaking changes (allowable as this is an unstable experimental API) removingVertexIds()(UseVertices()instead) and changing the return value ofEdges(). (#16016)
Fixes
- Toppra: Use one solver for every optimization and fix zero velocity bug (#15964)
Multibody Dynamics and Geometry
New features
- Add
MeshcatPointCloudVisualizer(#15938) - Add recording methods to
MeshcatVisualizerCpp(#15937) - Add
MeshcatContactVisualizer(#15968) - Add
Meshcat::SetLineandMeshcat::SetLineSegments(#16063) - Add
Meshcat::SetTriangleMeshandMeshcat::SetObject(TriangleSurfaceMesh)(#16077) - New hydroelastic contact model in progress (#16009, #15962)
Fixes
- None
Tutorials and examples
- Add perception role for PendulumGeometry (#16100)
Miscellaneous features and fixes
- Add sugar to read and write yaml-serialized files (#15902, #16000, #16096)
- Allow yaml-serializing a top-level map with no enclosing struct (#16059)
- Allow LCM handlers for
Subscribeto throw exceptions (#16027) - Convert package URIs to use top-level drake manifest; all package URIs used within Drake’s publicly accessible data now use
package://drake/...URIs (#15947)
pydrake bindings
New features
- Add
symbolic.Expression.Unapplyto allow visitor patterns (#16014)
Fixes
- Port values borrowed from a Context keep the Context alive (this prevents premature frees at cell boundaries in jupyter notebooks) (#16095)
Newly bound
geometry::optimization::GraphOfConvexSets(#15974)geometry::optimization::HPolyhedron::CartesianPower(#15999)geometry::optimization::HPolyhedron::CartesianProduct(#15999)symbolic::uninterpreted_function(#16015)symbolic::Expression.get_kind(#16012)systems::framework::CacheEntryValue(#15983)systems::framework::CacheEntry(#15983)systems::framework::ContextBase(#15979)systems::framework::SystemBase.DeclareCacheEntry(#15983)systems::framework::ValueProducer(#15983)perception::DepthImageToPointCloud.camera_pose_input_port(#16048)- All C++ lcm message type serializers (#16026)
drake::experimental_lcmt_deformable_tridrake::experimental_lcmt_deformable_tri_mesh_initdrake::experimental_lcmt_deformable_tri_mesh_updatedrake::experimental_lcmt_deformable_tri_meshes_initdrake::experimental_lcmt_deformable_tri_meshes_updatedrake::lcmt_acrobot_udrake::lcmt_acrobot_xdrake::lcmt_acrobot_ydrake::lcmt_allegro_commanddrake::lcmt_allegro_statusdrake::lcmt_call_pythondrake::lcmt_call_python_datadrake::lcmt_contact_results_for_vizdrake::lcmt_drake_signaldrake::lcmt_force_torquedrake::lcmt_headerdrake::lcmt_hydroelastic_contact_surface_for_vizdrake::lcmt_hydroelastic_contact_surface_tri_for_vizdrake::lcmt_hydroelastic_quadrature_per_point_data_for_vizdrake::lcmt_iiwa_commanddrake::lcmt_iiwa_statusdrake::lcmt_iiwa_status_telemetrydrake::lcmt_imagedrake::lcmt_image_arraydrake::lcmt_jaco_commanddrake::lcmt_jaco_statusdrake::lcmt_panda_commanddrake::lcmt_panda_statusdrake::lcmt_planar_gripper_commanddrake::lcmt_planar_gripper_finger_commanddrake::lcmt_planar_gripper_finger_face_assignmentdrake::lcmt_planar_gripper_finger_face_assignmentsdrake::lcmt_planar_gripper_finger_statusdrake::lcmt_planar_gripper_statusdrake::lcmt_planar_manipuland_statusdrake::lcmt_planar_plant_statedrake::lcmt_pointdrake::lcmt_point_clouddrake::lcmt_point_cloud_fielddrake::lcmt_point_pair_contact_info_for_vizdrake::lcmt_quaterniondrake::lcmt_robot_plandrake::lcmt_robot_statedrake::lcmt_schunk_wsg_commanddrake::lcmt_schunk_wsg_statusdrake::lcmt_scopedrake::lcmt_viewer_commanddrake::lcmt_viewer_drawdrake::lcmt_viewer_geometry_datadrake::lcmt_viewer_link_datadrake::lcmt_viewer_load_robot
- All scalar templates of Polynomial and Trajectory + subclasses (#16067):
math::Polynomialtrajectories::BsplineTrajectorytrajectories::PiecewisePolynomialtrajectories::PiecewisePosetrajectories::PiecewiseQuaternionSlerptrajectories::PiecewiseTrajectorytrajectories::Trajectory
Build system
- Enable support for macOS 12 Monterey (experimental) (#16068)
- Drop support for macOS Catalina (#16041, #16055)
- Build ibex 2.8.6 from source (#15963)
- Include
HAVE_SPDLOGcompile definition for cmake consumers (#16044) - Fix missing
SONAMEfields forlibdrake.soandlibdrake_marker.so(#16002) - Add
:drake_shared_librarytarget todrake_bazel_installed(#16072) - Improve
drake_bazel_installedcompatibility with ‘apt install drake-dev’ (#16070) - Display a disclaimer when ‘apt-get update’ is broken (#16086)
- Document the latest Drake-compatible CLion and Bazel versions (#16081)
Build dependencies
- Upgrade
buildifierto latest release 4.2.3 (#16004) - Upgrade
common_robotics_utilitiesto latest commit (#16004) - Upgrade
ghc_filesystemto latest release v1.5.10 (#16004) - Upgrade
ignition_mathto latest release 6.9.2 (#16004) - Upgrade
lcmto latest commit (#16034) - Upgrade
pycodestyleto latest release 2.8.0 (#16004) - Upgrade
rules_pythonto latest release 0.5.0 (#16004) - Upgrade
tinyobjloaderto latest commit (#16004) - Upgrade
uritemplate_pyto latest release 4.1.1 (#16004) - Upgrade
uwebsocketsto latest release v20.6.0 (#16004) - Upgrade
voxelized_geometry_toolsto latest commit (#15951)
Newly-deprecated APIs
lcm::DrakeMockLcm(#16078)multibody::parsing::ModelWeldErrorFunction(#15949)manipulation::perception::OptitrackPoseExtractor(#16011)systems::controllers::CartesianSetpoint(#16006, #16023)systems::controllers::VectorSetpoint(#16006, #16023)systems::framework::System::EvalEigenVectorInput(#16042)testing::ExpectRotMat(#16007)testing::CompareTransforms(#16007)yaml::YamlReadArchiveconstructors that accept aYAML::Node(#16057)pydrake.multibody.plant.MultibodyPlant.RegisterVisualGeometryoverload that usesIsometry3(#16008)pydrake.multibody.plant.MultibodyPlant.SetFreeBodyPoseoverload that usesIsometry3(#16008)pydrake.multibody.plant.MultibodyPlant.WeldFramesoverload that usesIsometry3(#16008)pydrake.multibody.tree.FixedOffsetFrame.__init__overload that usesIsometry3(#16008)pydrake.multibody.tree.WeldJoint.__init__overload that usesIsometry3(#16008)
Newly-deprecated configurations
- Deprecate the use of package URIs other than
package://drake/...to refer to Drake resources (#15947):package://allegro_hand_descriptionpackage://franka_descriptionpackage://iiwa_descriptionpackage://jaco_descriptionpackage://manipulation_stationpackage://wsg_50_descriptionpackage://ycb
- Deprecate installed use of kuka_simulation and kuka_plan_runner (#16061)
- Deprecate the use of uncommon primitive types during
yaml::YamlReadArchive(#16057) - Deprecate the colab installer helper script; use
pip install drakeinstead (#16073)
Removal of deprecated items
ExtractDoubleOrThrowon generic types (per-type specializations remain) (#16021)geometry::SceneGraph::ExcludeCollisionsBetweenandgeometry::SceneGraph::ExcludeCollisionsWithin(#16029)mathematicalprogram.Binding_{Type}aliases (#16038):mathematicalprogram.Binding_BoundingBoxConstraintmathematicalprogram.Binding_Constraintmathematicalprogram.Binding_Costmathematicalprogram.Binding_EvaluatorBasemathematicalprogram.Binding_ExponentialConeConstraintmathematicalprogram.Binding_L2NormCostmathematicalprogram.Binding_LinearComplementarityConstraintmathematicalprogram.Binding_LinearConstraintmathematicalprogram.Binding_LinearCostmathematicalprogram.Binding_LinearEqualityConstraintmathematicalprogram.Binding_LinearMatrixInequalityConstraintmathematicalprogram.Binding_LorentzConeConstraintmathematicalprogram.Binding_PositiveSemidefiniteConstraintmathematicalprogram.Binding_QuadraticCostmathematicalprogram.Binding_RotatedLorentzConeConstraintmathematicalprogram.Binding_VisualizationCallback
solvers::MosekSolver::set_stream_logging(#16020)systems::framework::System<T>::DeclareCacheEntry(Moved to protected access) (#15985)systems::framework::LeafSystem::DeclareAbstractOutputPortvariant with amakecallback (#16021)systems::framework::SystemBase::DeclareCacheEntryvariants with amakecallback (#16021)systems::framework::SystemBase::DeclareCacheEntryvariants with a non-voidcalccallback (#16021)systems::framework::SystemScalarConverter(..., GuaranteedSubtypePreservation)(#16021)systems::lcm::ConnectLcmScope(#16021)- The “lcm_visualization” (
PoseBundle) port ofpydrake.systems.planar_scenegraph_visualizer.PlanarSceneGraphVisualizer(#16039) - The
expose_all_files.bzlbazel macro (#16018)
This release provides pre-compiled binaries named
drake-20211116-{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.