From c1f13a12ce22eb0b3da9d19937e35dfe41082cb5 Mon Sep 17 00:00:00 2001 From: Eric Cousineau Date: Tue, 11 Apr 2023 18:51:09 -0400 Subject: [PATCH 01/18] DNM Disable CI --- tools/workspace/cc/repository.bzl | 1 + 1 file changed, 1 insertion(+) diff --git a/tools/workspace/cc/repository.bzl b/tools/workspace/cc/repository.bzl index a0d829ce4726..c9655352c1ef 100644 --- a/tools/workspace/cc/repository.bzl +++ b/tools/workspace/cc/repository.bzl @@ -55,6 +55,7 @@ def _check_compiler_version(compiler_id, actual_version, supported_version): )) def _impl(repository_ctx): + fail("Disable CI") file_content = """# DO NOT EDIT: generated by cc_repository() # This file exists to make our directory into a Bazel package, so that our From adca1bf4043454c0cb2e6d2479e8b276fab5f191 Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Wed, 6 Nov 2024 15:27:06 -0800 Subject: [PATCH 02/18] relnotes --action=create --version=v1.35.0 --prior_version=v1.34.0 --- doc/_release-notes/v1.35.0.md | 133 ++++++++++++++++++++++++++++++++++ 1 file changed, 133 insertions(+) create mode 100644 doc/_release-notes/v1.35.0.md diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md new file mode 100644 index 000000000000..9c877d84feb4 --- /dev/null +++ b/doc/_release-notes/v1.35.0.md @@ -0,0 +1,133 @@ +--- +title: Drake v1.35.0 +date: 2099-12-31 +released: YYYY-MM-DD +--- + +# Announcements + +* TBD + +# Breaking changes since v1.34.0 + +* TBD + +Refer to our [Drake Stability Guidelines](/stable.html) for our policy +on API changes. + +# Changes since v1.34.0 + +## Dynamical Systems + + + + +New features + +* TBD + +Fixes + +* TBD + +## Mathematical Program + + + + +New features + +* TBD + +Fixes + +* TBD + +## Multibody Dynamics and Geometry + + + + +New features + +* TBD + +Fixes + +* TBD + +## Planning + + + + +New features + +* TBD + +Fixes + +* TBD + +## Tutorials and examples + + + +* TBD + +## Miscellaneous features and fixes + + + +* TBD + +## pydrake bindings + + + + +New features + +* TBD + +Fixes + +* TBD + +## Build system + + + +* TBD + +## Build dependencies + + + +* TBD + +## Newly-deprecated APIs + +* TBD + +## Removal of deprecated items + +* TBD + +# Notes + + +This release provides [pre-compiled binaries](https://github.com/RobotLocomotion/drake/releases/tag/v1.35.0) named +``drake-1.35.0-{jammy|noble|mac-arm64}.tar.gz``. See [Stable Releases](/from_binary.html#stable-releases) for instructions on how to use them. + +Drake binary releases incorporate a pre-compiled version of [SNOPT](https://ccom.ucsd.edu/~optimizers/solvers/snopt/) as part of the +[Mathematical Program toolbox](https://drake.mit.edu/doxygen_cxx/group__solvers.html). Thanks to +Philip E. Gill and Elizabeth Wong for their kind support. + + + + + From 3d9fe3ecb16d49ed8452a4b88c48e96829839bbc Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Wed, 6 Nov 2024 15:40:36 -0800 Subject: [PATCH 03/18] relnotes --action=update --version=v1.35.0 --- doc/_release-notes/v1.35.0.md | 62 ++++++++++++++++++++++++++++++++++- 1 file changed, 61 insertions(+), 1 deletion(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index 9c877d84feb4..49acd60e7150 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -21,6 +21,7 @@ on API changes. +* [fix] TBD [systems] Fix RgbdSensor image size parameterization crash ([#22065][_#22065]) # Also add missing ValidateContext checks on public functions. New features @@ -34,6 +35,16 @@ Fixes +* [fix] TBD [solvers] Throw when IpoptSolver options are invalid ([#22062][_#22062]) +* [feature] TBD Solve mathematical programs in parallel ([#21957][_#21957]) # Adds convenience methods for solving batches of MathematicalProgram in parallel. Co-authored-by: Jeremy Nimmer +* [newly deprecated feature] TBD [solvers] Add CommonSolverOption::to_string ([#22079][_#22079]) # Deprecate operator<<. +* [fix] TBD Use the preprocessing solver options even if a specific preprocessing solver is not specified ([#22077][_#22077]) +* [fix] TBD [solvers] Fix Gurobi console logging obey our defaults again ([#22108][_#22108]) +* [feature] TBD [experimental] Implicit Graphs of Convex Sets ([#22074][_#22074]) # Resolves #22033. Implements a base class defining the Successor() method, and a number of simple tests showing how to create various types of implicit graphs. +* [fix] TBD Fix bug where empty HPolyhedra are reported to be unbounded ([#22117][_#22117]) # There are three progressively more expensive checks to see if an HPolyhedron is unbounded. However, certain empty HPolyhedra can trigger all three of these checks, so we must check emptiness first. +* [fix feature] TBD Leverage parallelization where possible when checking boundedness of a ConvexSet ([#22084][_#22084]) # This parallelizes the generic method for checking boundedness of a convex set, which is sometimes used by various derived classes of ConvexSet. Also fixes a bug in the boundedness check of MinkowskiSum. +* [fix] TBD Fix a Bug in GCS When Passing in a Trivially-Infeasible Upper Bound ([#22090][_#22090]) +* [feature] TBD Set gradient sparsity pattern in LorentzConeConstraint and RotatedLorentzConeConstraint ([#22125][_#22125]) New features @@ -47,6 +58,10 @@ Fixes +* [fix] TBD Bug fixes for holonomic and weld constraints ([#22057][_#22057]) # Fixes wrong frames in the Jacobian computation in SapDriver::AddWeldConstraints(). Fixes usage of variables in constructor of SapHolonomicCosnstraint after they were moved. +* [removal of deprecated] TBD [multibody,systems,geometry] Remove deprecated code 2024-11 ([#22086][_#22086]) +* [fix] TBD [geometry] Fix refine_mesh for cwd-relative paths ([#22106][_#22106]) # When the user does 'bazel run :refine_mesh' we should still allow a relative path for input or output. We call chdir here to undo the chdir performed by 'bazel run' into the runfiles tree. +* [fix feature] TBD [multibody,geometry] Improve exception message for bad geometry (zero volume mesh) in .obj file ([#21929][_#21929]) # Co-Authored-By: mitiguy Co-Authored-By: Rick Poyner Co-Authored-By: Sean Curtis New features @@ -79,12 +94,15 @@ Fixes +* [feature] TBD Implements FunctionHandleTrajectory ([#21093][_#21093]) # Resolves #20699. +* [fix] TBD [perception,common,geometry,math] [math] Add requires clause to RigidTransform and RotationMatrix cast ([#22094][_#22094]) # Both classes' documentation specifically disallows non-default scalars. * TBD ## pydrake bindings +* [feature] TBD [drake_gym] Add info_handler callback ([#21900][_#21900]) New features @@ -98,12 +116,29 @@ Fixes +* [fix] TBD [doc,tools] [setup] Upgrade Bazel to latest release 7.4.0 ([#22066][_#22066]) +* [fix] TBD [tools,geometry,systems,examples,common] [render_vtk] Use EGL by default on Ubuntu ([#22081][_#22081]) # This also fixes RenderEngineGltfClient to not require a DISPLAY. +* [fix] TBD [setup,workspace] [workspace] Upgrade bazelisk to latest release v1.22.1 ([#22119][_#22119]) * TBD ## Build dependencies +* [fix] TBD [workspace] Force-disable CoinUtils debugging hooks ([#22063][_#22063]) +* [fix] TBD [workspace] Upgrade openusd_internal to latest release 24.11 ([#22082][_#22082]) +* [fix] TBD [workspace] Upgrade drake_models to latest commit ([#22103][_#22103]) +* [fix] TBD [workspace] Upgrade crate_universe to latest ([#22119][_#22119]) +* [fix] TBD [workspace] Upgrade dm_control_internal to latest release 1.0.24 ([#22119][_#22119]) +* [fix] TBD [workspace] Upgrade msgpack_internal to latest release cpp-7.0.0 ([#22119][_#22119]) +* [fix] TBD [workspace] Upgrade mujoco_menagerie_internal to latest commit ([#22119][_#22119]) +* [fix] TBD [workspace] Upgrade mypy_internal to latest release v1.13.0 ([#22119][_#22119]) +* [fix] TBD [workspace] Upgrade statsjs to latest commit ([#22119][_#22119]) +* [fix] TBD [workspace] Upgrade suitesparse_internal to latest release v7.8.3 ([#22119][_#22119]) +* [fix] TBD [workspace] Upgrade tinyobjloader_internal to latest commit ([#22119][_#22119]) +* [fix] TBD [workspace] Upgrade vtk_internal to latest commit ([#22119][_#22119]) +* [fix] TBD [workspace] Upgrade rules_rust to latest release 0.53.0 ([#22119][_#22119]) +* [fix] TBD [workspace] Upgrade abseil_cpp_internal to latest commit ([#22118][_#22118]) * TBD ## Newly-deprecated APIs @@ -125,9 +160,34 @@ Drake binary releases incorporate a pre-compiled version of [SNOPT](https://ccom Philip E. Gill and Elizabeth Wong for their kind support. +[_#21093]: https://github.com/RobotLocomotion/drake/pull/21093 +[_#21900]: https://github.com/RobotLocomotion/drake/pull/21900 +[_#21929]: https://github.com/RobotLocomotion/drake/pull/21929 +[_#21957]: https://github.com/RobotLocomotion/drake/pull/21957 +[_#22057]: https://github.com/RobotLocomotion/drake/pull/22057 +[_#22062]: https://github.com/RobotLocomotion/drake/pull/22062 +[_#22063]: https://github.com/RobotLocomotion/drake/pull/22063 +[_#22065]: https://github.com/RobotLocomotion/drake/pull/22065 +[_#22066]: https://github.com/RobotLocomotion/drake/pull/22066 +[_#22074]: https://github.com/RobotLocomotion/drake/pull/22074 +[_#22077]: https://github.com/RobotLocomotion/drake/pull/22077 +[_#22079]: https://github.com/RobotLocomotion/drake/pull/22079 +[_#22081]: https://github.com/RobotLocomotion/drake/pull/22081 +[_#22082]: https://github.com/RobotLocomotion/drake/pull/22082 +[_#22084]: https://github.com/RobotLocomotion/drake/pull/22084 +[_#22086]: https://github.com/RobotLocomotion/drake/pull/22086 +[_#22090]: https://github.com/RobotLocomotion/drake/pull/22090 +[_#22094]: https://github.com/RobotLocomotion/drake/pull/22094 +[_#22103]: https://github.com/RobotLocomotion/drake/pull/22103 +[_#22106]: https://github.com/RobotLocomotion/drake/pull/22106 +[_#22108]: https://github.com/RobotLocomotion/drake/pull/22108 +[_#22117]: https://github.com/RobotLocomotion/drake/pull/22117 +[_#22118]: https://github.com/RobotLocomotion/drake/pull/22118 +[_#22119]: https://github.com/RobotLocomotion/drake/pull/22119 +[_#22125]: https://github.com/RobotLocomotion/drake/pull/22125 From 2e89493dee480af6603475bbef1749ab9210a6c3 Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Wed, 6 Nov 2024 19:06:59 -0800 Subject: [PATCH 04/18] Polishing the release notes: Dynamical Systems, Mathematical Program --- doc/_pages/release_playbook.md | 6 +----- doc/_release-notes/v1.35.0.md | 29 +++++++++++++---------------- 2 files changed, 14 insertions(+), 21 deletions(-) diff --git a/doc/_pages/release_playbook.md b/doc/_pages/release_playbook.md index c7444f8e9b64..89276728a71d 100644 --- a/doc/_pages/release_playbook.md +++ b/doc/_pages/release_playbook.md @@ -86,15 +86,11 @@ the main body of the document: * Use exactly the same wording for the boilerplate items: * Every dependency upgrade line should be "Upgrade libfoobar to latest release 1.2.3" or "Upgrade funrepo to latest commit". - * Dependencies should be referred to by their workspace name. + * Dependencies should be referred to by their ``workspace`` name. * Only one dependency change per line. Even if both meshcat and meshcat-python were upgraded in the same pull request, they each should get their own line in the release notes. -* Some features under development (eg, deformables as of this writing) may - have no-release-notes policies, as their APIs although public are not yet - fully supported. Be sure to take note of which these are, or ask on - `#platform_review` slack. * Keep all bullet points to one line. * Using hard linebreaks to stay under 80 columns makes the bullet lists hard to maintain over time. diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index 49acd60e7150..9e86e078b2e3 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -21,38 +21,35 @@ on API changes. -* [fix] TBD [systems] Fix RgbdSensor image size parameterization crash ([#22065][_#22065]) # Also add missing ValidateContext checks on public functions. - New features * TBD Fixes -* TBD +* Fix `RgbdSensor` image size parameterization crash ([#22065][_#22065]) ## Mathematical Program -* [fix] TBD [solvers] Throw when IpoptSolver options are invalid ([#22062][_#22062]) -* [feature] TBD Solve mathematical programs in parallel ([#21957][_#21957]) # Adds convenience methods for solving batches of MathematicalProgram in parallel. Co-authored-by: Jeremy Nimmer -* [newly deprecated feature] TBD [solvers] Add CommonSolverOption::to_string ([#22079][_#22079]) # Deprecate operator<<. -* [fix] TBD Use the preprocessing solver options even if a specific preprocessing solver is not specified ([#22077][_#22077]) -* [fix] TBD [solvers] Fix Gurobi console logging obey our defaults again ([#22108][_#22108]) -* [feature] TBD [experimental] Implicit Graphs of Convex Sets ([#22074][_#22074]) # Resolves #22033. Implements a base class defining the Successor() method, and a number of simple tests showing how to create various types of implicit graphs. -* [fix] TBD Fix bug where empty HPolyhedra are reported to be unbounded ([#22117][_#22117]) # There are three progressively more expensive checks to see if an HPolyhedron is unbounded. However, certain empty HPolyhedra can trigger all three of these checks, so we must check emptiness first. -* [fix feature] TBD Leverage parallelization where possible when checking boundedness of a ConvexSet ([#22084][_#22084]) # This parallelizes the generic method for checking boundedness of a convex set, which is sometimes used by various derived classes of ConvexSet. Also fixes a bug in the boundedness check of MinkowskiSum. -* [fix] TBD Fix a Bug in GCS When Passing in a Trivially-Infeasible Upper Bound ([#22090][_#22090]) -* [feature] TBD Set gradient sparsity pattern in LorentzConeConstraint and RotatedLorentzConeConstraint ([#22125][_#22125]) New features -* TBD +* Solve mathematical programs in parallel ([#21957][_#21957]) +* Add `CommonSolverOption::to_string` ([#22079][_#22079]) +* Introduce `ImplicitGraphOfConvexSets` ([#22074][_#22074]) +* Leverage parallelization where possible when checking boundedness of a `ConvexSet` ([#22084][_#22084]) +* Set gradient sparsity pattern in `LorentzConeConstraint` and `RotatedLorentzConeConstraint` ([#22125][_#22125]) Fixes -* TBD +* Throw when `IpoptSolver` options are invalid ([#22062][_#22062]) +* Use `GraphOfConvexSetsOptions::preprocessing_solver_options` even if a specific `preprocessing_solver` is not specified ([#22077][_#22077]) +* Fix Gurobi console logging to obey our defaults again ([#22108][_#22108]) +* Fix bugs where empty `HPolyhedron`'s were reported to be unbounded ([#22117][_#22117]) +* Fix the boundedness check of `MinkowskiSum` ([#22084][_#22084]) +* Fix `GraphOfConvexSets` when passing in a trivially-infeasible upper bound ([#22090][_#22090]) ## Multibody Dynamics and Geometry @@ -143,7 +140,7 @@ Fixes ## Newly-deprecated APIs -* TBD +* `CommonSolverOption::operator<<` ([#22079][_#22079]) ## Removal of deprecated items From 14341f651405bf0cac8bc699080a443b0651eb1c Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Mon, 11 Nov 2024 19:39:57 -0800 Subject: [PATCH 05/18] Polishing 5 sections: - Multibody Dynamics and Geometry - Miscellaneous features and fixes - pydrake bindings - Build system - Removal of deprecated items --- doc/_release-notes/v1.35.0.md | 39 +++++++++++++++++++++-------------- 1 file changed, 24 insertions(+), 15 deletions(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index 9e86e078b2e3..a9ed39a38eb7 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -55,18 +55,15 @@ Fixes -* [fix] TBD Bug fixes for holonomic and weld constraints ([#22057][_#22057]) # Fixes wrong frames in the Jacobian computation in SapDriver::AddWeldConstraints(). Fixes usage of variables in constructor of SapHolonomicCosnstraint after they were moved. -* [removal of deprecated] TBD [multibody,systems,geometry] Remove deprecated code 2024-11 ([#22086][_#22086]) -* [fix] TBD [geometry] Fix refine_mesh for cwd-relative paths ([#22106][_#22106]) # When the user does 'bazel run :refine_mesh' we should still allow a relative path for input or output. We call chdir here to undo the chdir performed by 'bazel run' into the runfiles tree. -* [fix feature] TBD [multibody,geometry] Improve exception message for bad geometry (zero volume mesh) in .obj file ([#21929][_#21929]) # Co-Authored-By: mitiguy Co-Authored-By: Rick Poyner Co-Authored-By: Sean Curtis - New features * TBD Fixes -* TBD +* Bug fixes for `SapHolonomicCosnstraint` and `SapDriver::AddWeldConstraints()` ([#22057][_#22057]) +* Fix `//geometry/proximity:refine_mesh` for cwd-relative paths ([#22106][_#22106]) +* Improve exception message for bad geometry (zero volume mesh) in .obj file ([#21929][_#21929]) ## Planning @@ -91,15 +88,16 @@ Fixes -* [feature] TBD Implements FunctionHandleTrajectory ([#21093][_#21093]) # Resolves #20699. -* [fix] TBD [perception,common,geometry,math] [math] Add requires clause to RigidTransform and RotationMatrix cast ([#22094][_#22094]) # Both classes' documentation specifically disallows non-default scalars. -* TBD +* Implement `drake::trajectories::FunctionHandleTrajectory` ([#21093][_#21093]) +* Add requires clause to `drake::math::RigidTransform` and `drake::math::RotationMatrix` cast ([#22094][_#22094]) + ## pydrake bindings -* [feature] TBD [drake_gym] Add info_handler callback ([#21900][_#21900]) +* Bind `pydrake.trajectories.FunctionHandleTrajectory` ([#21093][_#21093]) +* Add `info_handler` callback to `pydrake.gym.DrakeGymEnv` ([#21900][_#21900]) New features @@ -113,10 +111,9 @@ Fixes -* [fix] TBD [doc,tools] [setup] Upgrade Bazel to latest release 7.4.0 ([#22066][_#22066]) -* [fix] TBD [tools,geometry,systems,examples,common] [render_vtk] Use EGL by default on Ubuntu ([#22081][_#22081]) # This also fixes RenderEngineGltfClient to not require a DISPLAY. -* [fix] TBD [setup,workspace] [workspace] Upgrade bazelisk to latest release v1.22.1 ([#22119][_#22119]) -* TBD +* Upgrade Bazel to latest release 7.4.0 ([#22066][_#22066]) +* Use EGL by default on Ubuntu ([#22081][_#22081]) +* Upgrade bazelisk to latest release v1.22.1 ([#22119][_#22119]) ## Build dependencies @@ -144,7 +141,19 @@ Fixes ## Removal of deprecated items -* TBD +* `//multibody/plant:deformable_contact_info` ([#22086][_#22086]) +* `//multibody/plant:hydroelastic_contact_info` ([#22086][_#22086]) +* `//multibody/plant:hydroelastic_quadrature_point_data` ([#22086][_#22086]) +* `//multibody/plant:hydroelastic_traction` ([#22086][_#22086]) +* `//multibody/plant:point_pair_contact_info` ([#22086][_#22086]) +* `drake::geometry::MeshcatVisualizer::ResetRealtimeRateCalculator()` ([#22086][_#22086]) +* `drake::multibody::HydroelasticContactInfo::HydroelasticContactInfo()` with `quadrature_point_data` argument ([#22086][_#22086]) +* `drake::multibody::HydroelasticContactInfo()::quadrature_point_data()` ([#22086][_#22086]) +* `drake::multibody::CalcSpatialInertia()` with the default density value ([#22086][_#22086]) +* `drake::systems::VectorSystem::VectorSystem()` without `direct_feedthrough` argument ([#22086][_#22086]) +* `pydrake.geometry.MeshcatVisualizer.ResetRealtimeRateCalculator()` ([#22086][_#22086]) +* `pydrake.systems.framework.VectorSystem()` without `direct_feedthrough` argument ([#22086][_#22086]) +* # Notes From 2357a2a75e5ac08a03d6cfaf62633b3b77187226 Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Tue, 12 Nov 2024 17:30:50 -0800 Subject: [PATCH 06/18] Polish "Build dependencies" --- doc/_release-notes/v1.35.0.md | 30 ++++++++++++++---------------- 1 file changed, 14 insertions(+), 16 deletions(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index a9ed39a38eb7..b985cddfe5a7 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -119,21 +119,20 @@ Fixes -* [fix] TBD [workspace] Force-disable CoinUtils debugging hooks ([#22063][_#22063]) -* [fix] TBD [workspace] Upgrade openusd_internal to latest release 24.11 ([#22082][_#22082]) -* [fix] TBD [workspace] Upgrade drake_models to latest commit ([#22103][_#22103]) -* [fix] TBD [workspace] Upgrade crate_universe to latest ([#22119][_#22119]) -* [fix] TBD [workspace] Upgrade dm_control_internal to latest release 1.0.24 ([#22119][_#22119]) -* [fix] TBD [workspace] Upgrade msgpack_internal to latest release cpp-7.0.0 ([#22119][_#22119]) -* [fix] TBD [workspace] Upgrade mujoco_menagerie_internal to latest commit ([#22119][_#22119]) -* [fix] TBD [workspace] Upgrade mypy_internal to latest release v1.13.0 ([#22119][_#22119]) -* [fix] TBD [workspace] Upgrade statsjs to latest commit ([#22119][_#22119]) -* [fix] TBD [workspace] Upgrade suitesparse_internal to latest release v7.8.3 ([#22119][_#22119]) -* [fix] TBD [workspace] Upgrade tinyobjloader_internal to latest commit ([#22119][_#22119]) -* [fix] TBD [workspace] Upgrade vtk_internal to latest commit ([#22119][_#22119]) -* [fix] TBD [workspace] Upgrade rules_rust to latest release 0.53.0 ([#22119][_#22119]) -* [fix] TBD [workspace] Upgrade abseil_cpp_internal to latest commit ([#22118][_#22118]) -* TBD +* Force-disable CoinUtils debugging hooks ([#22063][_#22063]) +* Upgrade openusd_internal to latest release 24.11 ([#22082][_#22082]) +* Upgrade drake_models to latest commit ([#22103][_#22103]) +* Upgrade crate_universe to latest releases ([#22119][_#22119]) +* Upgrade dm_control_internal to latest release 1.0.24 ([#22119][_#22119]) +* Upgrade msgpack_internal to latest release cpp-7.0.0 ([#22119][_#22119]) +* Upgrade mujoco_menagerie_internal to latest commit ([#22119][_#22119]) +* Upgrade mypy_internal to latest release v1.13.0 ([#22119][_#22119]) +* Upgrade statsjs to latest commit ([#22119][_#22119]) +* Upgrade suitesparse_internal to latest release v7.8.3 ([#22119][_#22119]) +* Upgrade tinyobjloader_internal to latest commit ([#22119][_#22119]) +* Upgrade vtk_internal to latest commit ([#22119][_#22119]) +* Upgrade rules_rust to latest release 0.53.0 ([#22119][_#22119]) +* Upgrade abseil_cpp_internal to latest commit ([#22118][_#22118]) ## Newly-deprecated APIs @@ -153,7 +152,6 @@ Fixes * `drake::systems::VectorSystem::VectorSystem()` without `direct_feedthrough` argument ([#22086][_#22086]) * `pydrake.geometry.MeshcatVisualizer.ResetRealtimeRateCalculator()` ([#22086][_#22086]) * `pydrake.systems.framework.VectorSystem()` without `direct_feedthrough` argument ([#22086][_#22086]) -* # Notes From 73b8c5ec4e5693f147275889d4b6ee00f2f1fbe9 Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Tue, 12 Nov 2024 17:42:50 -0800 Subject: [PATCH 07/18] Sort "Build system", "Build dependencies", "Removal of deprecated items" --- doc/_release-notes/v1.35.0.md | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index b985cddfe5a7..a9c65029f81d 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -111,28 +111,28 @@ Fixes +* Upgrade bazelisk to latest release v1.22.1 ([#22119][_#22119]) * Upgrade Bazel to latest release 7.4.0 ([#22066][_#22066]) * Use EGL by default on Ubuntu ([#22081][_#22081]) -* Upgrade bazelisk to latest release v1.22.1 ([#22119][_#22119]) ## Build dependencies * Force-disable CoinUtils debugging hooks ([#22063][_#22063]) -* Upgrade openusd_internal to latest release 24.11 ([#22082][_#22082]) -* Upgrade drake_models to latest commit ([#22103][_#22103]) +* Upgrade abseil_cpp_internal to latest commit ([#22118][_#22118]) * Upgrade crate_universe to latest releases ([#22119][_#22119]) * Upgrade dm_control_internal to latest release 1.0.24 ([#22119][_#22119]) +* Upgrade drake_models to latest commit ([#22103][_#22103]) * Upgrade msgpack_internal to latest release cpp-7.0.0 ([#22119][_#22119]) * Upgrade mujoco_menagerie_internal to latest commit ([#22119][_#22119]) * Upgrade mypy_internal to latest release v1.13.0 ([#22119][_#22119]) +* Upgrade openusd_internal to latest release 24.11 ([#22082][_#22082]) +* Upgrade rules_rust to latest release 0.53.0 ([#22119][_#22119]) * Upgrade statsjs to latest commit ([#22119][_#22119]) * Upgrade suitesparse_internal to latest release v7.8.3 ([#22119][_#22119]) * Upgrade tinyobjloader_internal to latest commit ([#22119][_#22119]) * Upgrade vtk_internal to latest commit ([#22119][_#22119]) -* Upgrade rules_rust to latest release 0.53.0 ([#22119][_#22119]) -* Upgrade abseil_cpp_internal to latest commit ([#22118][_#22118]) ## Newly-deprecated APIs @@ -140,16 +140,16 @@ Fixes ## Removal of deprecated items +* `drake::geometry::MeshcatVisualizer::ResetRealtimeRateCalculator()` ([#22086][_#22086]) +* `drake::multibody::CalcSpatialInertia()` with the default density value ([#22086][_#22086]) +* `drake::multibody::HydroelasticContactInfo::HydroelasticContactInfo()` with `quadrature_point_data` argument ([#22086][_#22086]) +* `drake::multibody::HydroelasticContactInfo()::quadrature_point_data()` ([#22086][_#22086]) +* `drake::systems::VectorSystem::VectorSystem()` without `direct_feedthrough` argument ([#22086][_#22086]) * `//multibody/plant:deformable_contact_info` ([#22086][_#22086]) * `//multibody/plant:hydroelastic_contact_info` ([#22086][_#22086]) * `//multibody/plant:hydroelastic_quadrature_point_data` ([#22086][_#22086]) * `//multibody/plant:hydroelastic_traction` ([#22086][_#22086]) * `//multibody/plant:point_pair_contact_info` ([#22086][_#22086]) -* `drake::geometry::MeshcatVisualizer::ResetRealtimeRateCalculator()` ([#22086][_#22086]) -* `drake::multibody::HydroelasticContactInfo::HydroelasticContactInfo()` with `quadrature_point_data` argument ([#22086][_#22086]) -* `drake::multibody::HydroelasticContactInfo()::quadrature_point_data()` ([#22086][_#22086]) -* `drake::multibody::CalcSpatialInertia()` with the default density value ([#22086][_#22086]) -* `drake::systems::VectorSystem::VectorSystem()` without `direct_feedthrough` argument ([#22086][_#22086]) * `pydrake.geometry.MeshcatVisualizer.ResetRealtimeRateCalculator()` ([#22086][_#22086]) * `pydrake.systems.framework.VectorSystem()` without `direct_feedthrough` argument ([#22086][_#22086]) From e90c69cb5c8b6a683bd5cb180bdd68ebe25f979e Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Tue, 12 Nov 2024 17:44:13 -0800 Subject: [PATCH 08/18] Fix typo --- doc/_release-notes/v1.35.0.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index a9c65029f81d..2abca0b49c12 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -143,7 +143,7 @@ Fixes * `drake::geometry::MeshcatVisualizer::ResetRealtimeRateCalculator()` ([#22086][_#22086]) * `drake::multibody::CalcSpatialInertia()` with the default density value ([#22086][_#22086]) * `drake::multibody::HydroelasticContactInfo::HydroelasticContactInfo()` with `quadrature_point_data` argument ([#22086][_#22086]) -* `drake::multibody::HydroelasticContactInfo()::quadrature_point_data()` ([#22086][_#22086]) +* `drake::multibody::HydroelasticContactInfo::quadrature_point_data()` ([#22086][_#22086]) * `drake::systems::VectorSystem::VectorSystem()` without `direct_feedthrough` argument ([#22086][_#22086]) * `//multibody/plant:deformable_contact_info` ([#22086][_#22086]) * `//multibody/plant:hydroelastic_contact_info` ([#22086][_#22086]) From 1a8845cfa92f1055faca56c6ac90ec2234219730 Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Tue, 12 Nov 2024 17:59:17 -0800 Subject: [PATCH 09/18] bazel-bin/tools/release_engineering/relnotes --action=update --version=v1.35.0 --- doc/_release-notes/v1.35.0.md | 30 +++++++++++++++++++++++++++++- 1 file changed, 29 insertions(+), 1 deletion(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index 2abca0b49c12..f06887869701 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -33,6 +33,9 @@ Fixes +* [fix] TBD Move the warning on small-size PSD matrix to each solver backend ([#22136][_#22136]) +* [feature] TBD Update single entry of coefficients in LinearCost and QuadraticCost ([#22152][_#22152]) +* [feature] TBD Parallelize the Pairwise Set Intersection Checking for GCS (with or without Continuous Revolute Joints) ([#22142][_#22142]) # Note that the parallelism here is used in two ways -- the computation of AABBs of the constituent sets is handled with a parallel for loop, and then the pairwise intersections themselves are checked with SolveInParallel. New features @@ -55,6 +58,9 @@ Fixes +* [feature] TBD [multibody,geometry] Update parsing infrastructure ([#22102][_#22102]) # 1. MultibodyPlant::RegisterVisualGeometry() can now take a GeometryInstance. - Clean up documentation. - Extend tests to include what is *actually* done. 2. SDF parser makes use of new API. - Stop returning optional> (simply return the unique ptr). - Instead of constructing, deconstructing, and reconstructing geometry instances, we just pass the instance. +* [feature] TBD [geometry] Add precomputed values to VolumeMesh and MeshFieldLinear ([#22097][_#22097]) +* [feature] TBD Allow floating bodies to use RpyFloating joints ([#21973][_#21973]) # Also supports using Weld joints instead of floating joints for unattached bodies. New features * TBD @@ -69,6 +75,7 @@ Fixes +* [feature] TBD Add Expression Costs and Formula Constraints to Subgraphs in GcsTrajectoryOptimization ([#22091][_#22091]) # Adds placeholder variables to subgraphs, that can be used to construct costs and constraints to each vertex or edge. Note that this includes the fix Fix a Bug in GCS When Passing in a Trivially-Infeasible Upper Bound #22090, since the conjunctive formula used in a test case creates an instance of this bug. Co-Authored-By: Russ Tedrake New features @@ -88,6 +95,8 @@ Fixes +* [feature] TBD [schema] Add Rotation::Sample ([#22113][_#22113]) # This bring it on par with Transform::Sample. +* [feature] TBD Trim PiecewisePolynomials ([#22099][_#22099]) * Implement `drake::trajectories::FunctionHandleTrajectory` ([#21093][_#21093]) * Add requires clause to `drake::math::RigidTransform` and `drake::math::RotationMatrix` cast ([#22094][_#22094]) @@ -96,6 +105,8 @@ Fixes +* [fix] TBD [py perception] Add bindings for PointCloud copy ([#22148][_#22148]) +* [fix] TBD Adds missing sparse UpdateCoefficient binding to LinearEqualityConstraint ([#22151][_#22151]) * Bind `pydrake.trajectories.FunctionHandleTrajectory` ([#21093][_#21093]) * Add `info_handler` callback to `pydrake.gym.DrakeGymEnv` ([#21900][_#21900]) @@ -119,6 +130,9 @@ Fixes +* [fix] TBD [workspace] Upgrade nanoflann_internal to latest release v1.6.2 ([#22130][_#22130]) +* [fix] TBD [workspace] Upgrade gymnasium_py to latest release v1.0.0 ([#22121][_#22121]) # Co-Authored-By: Rick Poyner +* [fix] TBD [workspace] Upgrade rules_python to 0.36.0 ([#22129][_#22129]) # * pin to never upgrade again Co-Authored-By: Jeremy Nimmer * Force-disable CoinUtils debugging hooks ([#22063][_#22063]) * Upgrade abseil_cpp_internal to latest commit ([#22118][_#22118]) * Upgrade crate_universe to latest releases ([#22119][_#22119]) @@ -168,6 +182,7 @@ Philip E. Gill and Elizabeth Wong for their kind support. [_#21900]: https://github.com/RobotLocomotion/drake/pull/21900 [_#21929]: https://github.com/RobotLocomotion/drake/pull/21929 [_#21957]: https://github.com/RobotLocomotion/drake/pull/21957 +[_#21973]: https://github.com/RobotLocomotion/drake/pull/21973 [_#22057]: https://github.com/RobotLocomotion/drake/pull/22057 [_#22062]: https://github.com/RobotLocomotion/drake/pull/22062 [_#22063]: https://github.com/RobotLocomotion/drake/pull/22063 @@ -181,17 +196,30 @@ Philip E. Gill and Elizabeth Wong for their kind support. [_#22084]: https://github.com/RobotLocomotion/drake/pull/22084 [_#22086]: https://github.com/RobotLocomotion/drake/pull/22086 [_#22090]: https://github.com/RobotLocomotion/drake/pull/22090 +[_#22091]: https://github.com/RobotLocomotion/drake/pull/22091 [_#22094]: https://github.com/RobotLocomotion/drake/pull/22094 +[_#22097]: https://github.com/RobotLocomotion/drake/pull/22097 +[_#22099]: https://github.com/RobotLocomotion/drake/pull/22099 +[_#22102]: https://github.com/RobotLocomotion/drake/pull/22102 [_#22103]: https://github.com/RobotLocomotion/drake/pull/22103 [_#22106]: https://github.com/RobotLocomotion/drake/pull/22106 [_#22108]: https://github.com/RobotLocomotion/drake/pull/22108 +[_#22113]: https://github.com/RobotLocomotion/drake/pull/22113 [_#22117]: https://github.com/RobotLocomotion/drake/pull/22117 [_#22118]: https://github.com/RobotLocomotion/drake/pull/22118 [_#22119]: https://github.com/RobotLocomotion/drake/pull/22119 +[_#22121]: https://github.com/RobotLocomotion/drake/pull/22121 [_#22125]: https://github.com/RobotLocomotion/drake/pull/22125 +[_#22129]: https://github.com/RobotLocomotion/drake/pull/22129 +[_#22130]: https://github.com/RobotLocomotion/drake/pull/22130 +[_#22136]: https://github.com/RobotLocomotion/drake/pull/22136 +[_#22142]: https://github.com/RobotLocomotion/drake/pull/22142 +[_#22148]: https://github.com/RobotLocomotion/drake/pull/22148 +[_#22151]: https://github.com/RobotLocomotion/drake/pull/22151 +[_#22152]: https://github.com/RobotLocomotion/drake/pull/22152 From 721e33c3650f1ddf910ddb9d6a65fa835e08b678 Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Tue, 12 Nov 2024 18:57:05 -0800 Subject: [PATCH 10/18] Polish 6 sections: - Mathematical Program - Multibody Dynamics and Geometry - Planning - Miscellaneous features and fixes - pydrake bindings - Build dependencies --- doc/_release-notes/v1.35.0.md | 32 +++++++++++++++----------------- 1 file changed, 15 insertions(+), 17 deletions(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index f06887869701..b4872cac6df2 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -33,10 +33,6 @@ Fixes -* [fix] TBD Move the warning on small-size PSD matrix to each solver backend ([#22136][_#22136]) -* [feature] TBD Update single entry of coefficients in LinearCost and QuadraticCost ([#22152][_#22152]) -* [feature] TBD Parallelize the Pairwise Set Intersection Checking for GCS (with or without Continuous Revolute Joints) ([#22142][_#22142]) # Note that the parallelism here is used in two ways -- the computation of AABBs of the constituent sets is handled with a parallel for loop, and then the pairwise intersections themselves are checked with SolveInParallel. - New features * Solve mathematical programs in parallel ([#21957][_#21957]) @@ -44,6 +40,8 @@ New features * Introduce `ImplicitGraphOfConvexSets` ([#22074][_#22074]) * Leverage parallelization where possible when checking boundedness of a `ConvexSet` ([#22084][_#22084]) * Set gradient sparsity pattern in `LorentzConeConstraint` and `RotatedLorentzConeConstraint` ([#22125][_#22125]) +* Update single entry of coefficients in `LinearCost` and `QuadraticCost` ([#22152][_#22152]) +* Parallelize `ComputePairwiseIntersections()` for Graph of Convex Sets (with or without continuous revolute joints) ([#22142][_#22142]) Fixes @@ -53,17 +51,17 @@ Fixes * Fix bugs where empty `HPolyhedron`'s were reported to be unbounded ([#22117][_#22117]) * Fix the boundedness check of `MinkowskiSum` ([#22084][_#22084]) * Fix `GraphOfConvexSets` when passing in a trivially-infeasible upper bound ([#22090][_#22090]) +* Move the warning on small-size PSD matrix to each solver backend ([#22136][_#22136]) ## Multibody Dynamics and Geometry -* [feature] TBD [multibody,geometry] Update parsing infrastructure ([#22102][_#22102]) # 1. MultibodyPlant::RegisterVisualGeometry() can now take a GeometryInstance. - Clean up documentation. - Extend tests to include what is *actually* done. 2. SDF parser makes use of new API. - Stop returning optional> (simply return the unique ptr). - Instead of constructing, deconstructing, and reconstructing geometry instances, we just pass the instance. -* [feature] TBD [geometry] Add precomputed values to VolumeMesh and MeshFieldLinear ([#22097][_#22097]) -* [feature] TBD Allow floating bodies to use RpyFloating joints ([#21973][_#21973]) # Also supports using Weld joints instead of floating joints for unattached bodies. New features -* TBD +* Update parsing infrastructure ([#22102][_#22102]) +* Add precomputed values to `VolumeMesh` and `MeshFieldLinear` ([#22097][_#22097]) +* Allow floating bodies to use `RpyFloatingJoint` ([#21973][_#21973]) Fixes @@ -75,7 +73,7 @@ Fixes -* [feature] TBD Add Expression Costs and Formula Constraints to Subgraphs in GcsTrajectoryOptimization ([#22091][_#22091]) # Adds placeholder variables to subgraphs, that can be used to construct costs and constraints to each vertex or edge. Note that this includes the fix Fix a Bug in GCS When Passing in a Trivially-Infeasible Upper Bound #22090, since the conjunctive formula used in a test case creates an instance of this bug. Co-Authored-By: Russ Tedrake +* Add `symbolic::Expression` costs and `symbolic::Formula` constraints to `Subgraphs` in `GcsTrajectoryOptimization` ([#22091][_#22091]) New features @@ -95,20 +93,20 @@ Fixes -* [feature] TBD [schema] Add Rotation::Sample ([#22113][_#22113]) # This bring it on par with Transform::Sample. -* [feature] TBD Trim PiecewisePolynomials ([#22099][_#22099]) * Implement `drake::trajectories::FunctionHandleTrajectory` ([#21093][_#21093]) * Add requires clause to `drake::math::RigidTransform` and `drake::math::RotationMatrix` cast ([#22094][_#22094]) +* Add `drake::schema::Rotation::Sample()` ([#22113][_#22113]) +* Trim `drake::trajectories::PiecewisePolynomial` ([#22099][_#22099]) ## pydrake bindings -* [fix] TBD [py perception] Add bindings for PointCloud copy ([#22148][_#22148]) -* [fix] TBD Adds missing sparse UpdateCoefficient binding to LinearEqualityConstraint ([#22151][_#22151]) -* Bind `pydrake.trajectories.FunctionHandleTrajectory` ([#21093][_#21093]) * Add `info_handler` callback to `pydrake.gym.DrakeGymEnv` ([#21900][_#21900]) +* Bind `copy` for `pydrake.perception.PointCloud` ([#22148][_#22148]) +* Bind `pydrake.trajectories.FunctionHandleTrajectory` ([#21093][_#21093]) +* Bind `pydrake.solvers.LinearEqualityConstraint.UpdateCoefficients` with a sparse matrix ([#22151][_#22151]) New features @@ -130,9 +128,9 @@ Fixes -* [fix] TBD [workspace] Upgrade nanoflann_internal to latest release v1.6.2 ([#22130][_#22130]) -* [fix] TBD [workspace] Upgrade gymnasium_py to latest release v1.0.0 ([#22121][_#22121]) # Co-Authored-By: Rick Poyner -* [fix] TBD [workspace] Upgrade rules_python to 0.36.0 ([#22129][_#22129]) # * pin to never upgrade again Co-Authored-By: Jeremy Nimmer +* Upgrade nanoflann_internal to latest release v1.6.2 ([#22130][_#22130]) +* Upgrade gymnasium_py to latest release v1.0.0 ([#22121][_#22121]) +* Upgrade rules_python to 0.36.0 ([#22129][_#22129]) * Force-disable CoinUtils debugging hooks ([#22063][_#22063]) * Upgrade abseil_cpp_internal to latest commit ([#22118][_#22118]) * Upgrade crate_universe to latest releases ([#22119][_#22119]) From 119b67b25d340c4701bafd7f3d1c4cebbe9bb29f Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Tue, 12 Nov 2024 19:03:58 -0800 Subject: [PATCH 11/18] Minor fix and sort "pydrake bindings" and "Build dependencies" --- doc/_release-notes/v1.35.0.md | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index b4872cac6df2..18526271e344 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -73,11 +73,9 @@ Fixes -* Add `symbolic::Expression` costs and `symbolic::Formula` constraints to `Subgraphs` in `GcsTrajectoryOptimization` ([#22091][_#22091]) - New features -* TBD +* Add `symbolic::Expression` costs and `symbolic::Formula` constraints to `Subgraphs` in `GcsTrajectoryOptimization` ([#22091][_#22091]) Fixes @@ -105,8 +103,8 @@ Fixes * Add `info_handler` callback to `pydrake.gym.DrakeGymEnv` ([#21900][_#21900]) * Bind `copy` for `pydrake.perception.PointCloud` ([#22148][_#22148]) -* Bind `pydrake.trajectories.FunctionHandleTrajectory` ([#21093][_#21093]) * Bind `pydrake.solvers.LinearEqualityConstraint.UpdateCoefficients` with a sparse matrix ([#22151][_#22151]) +* Bind `pydrake.trajectories.FunctionHandleTrajectory` ([#21093][_#21093]) New features @@ -128,18 +126,18 @@ Fixes -* Upgrade nanoflann_internal to latest release v1.6.2 ([#22130][_#22130]) -* Upgrade gymnasium_py to latest release v1.0.0 ([#22121][_#22121]) -* Upgrade rules_python to 0.36.0 ([#22129][_#22129]) * Force-disable CoinUtils debugging hooks ([#22063][_#22063]) * Upgrade abseil_cpp_internal to latest commit ([#22118][_#22118]) * Upgrade crate_universe to latest releases ([#22119][_#22119]) * Upgrade dm_control_internal to latest release 1.0.24 ([#22119][_#22119]) * Upgrade drake_models to latest commit ([#22103][_#22103]) +* Upgrade gymnasium_py to latest release v1.0.0 ([#22121][_#22121]) * Upgrade msgpack_internal to latest release cpp-7.0.0 ([#22119][_#22119]) * Upgrade mujoco_menagerie_internal to latest commit ([#22119][_#22119]) * Upgrade mypy_internal to latest release v1.13.0 ([#22119][_#22119]) +* Upgrade nanoflann_internal to latest release v1.6.2 ([#22130][_#22130]) * Upgrade openusd_internal to latest release 24.11 ([#22082][_#22082]) +* Upgrade rules_python to 0.36.0 ([#22129][_#22129]) * Upgrade rules_rust to latest release 0.53.0 ([#22119][_#22119]) * Upgrade statsjs to latest commit ([#22119][_#22119]) * Upgrade suitesparse_internal to latest release v7.8.3 ([#22119][_#22119]) From c5aef08b161a225319fba04fef2ea0b9539cf4ef Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Tue, 12 Nov 2024 19:51:20 -0800 Subject: [PATCH 12/18] Fix "pydrake bindings" --- doc/_release-notes/v1.35.0.md | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index 18526271e344..dc81dd91d81a 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -101,18 +101,15 @@ Fixes -* Add `info_handler` callback to `pydrake.gym.DrakeGymEnv` ([#21900][_#21900]) -* Bind `copy` for `pydrake.perception.PointCloud` ([#22148][_#22148]) -* Bind `pydrake.solvers.LinearEqualityConstraint.UpdateCoefficients` with a sparse matrix ([#22151][_#22151]) -* Bind `pydrake.trajectories.FunctionHandleTrajectory` ([#21093][_#21093]) - New features -* TBD +* Add `info_handler` callback to `pydrake.gym.DrakeGymEnv` ([#21900][_#21900]) +* Bind `pydrake.trajectories.FunctionHandleTrajectory` ([#21093][_#21093]) Fixes -* TBD +* Bind `copy` for `pydrake.perception.PointCloud` ([#22148][_#22148]) +* Bind `pydrake.solvers.LinearEqualityConstraint.UpdateCoefficients` with a sparse matrix ([#22151][_#22151]) ## Build system From bc67fc736e25a4c0a95871311149c5f330f4dbcd Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Wed, 13 Nov 2024 13:51:19 -0800 Subject: [PATCH 13/18] Reviewable --- doc/_release-notes/v1.35.0.md | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index dc81dd91d81a..70bb0a456f12 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -6,11 +6,11 @@ released: YYYY-MM-DD # Announcements -* TBD +* None # Breaking changes since v1.34.0 -* TBD +* None Refer to our [Drake Stability Guidelines](/stable.html) for our policy on API changes. @@ -23,7 +23,7 @@ on API changes. New features -* TBD +* None Fixes @@ -59,7 +59,7 @@ Fixes New features -* Update parsing infrastructure ([#22102][_#22102]) +* Allow `GeometryInstance` to be registered through `MultibodyPlant` with clarifications on the related semantics ([#22102][_#22102]) * Add precomputed values to `VolumeMesh` and `MeshFieldLinear` ([#22097][_#22097]) * Allow floating bodies to use `RpyFloatingJoint` ([#21973][_#21973]) @@ -79,13 +79,13 @@ New features Fixes -* TBD +* None ## Tutorials and examples -* TBD +* None ## Miscellaneous features and fixes @@ -94,7 +94,7 @@ Fixes * Implement `drake::trajectories::FunctionHandleTrajectory` ([#21093][_#21093]) * Add requires clause to `drake::math::RigidTransform` and `drake::math::RotationMatrix` cast ([#22094][_#22094]) * Add `drake::schema::Rotation::Sample()` ([#22113][_#22113]) -* Trim `drake::trajectories::PiecewisePolynomial` ([#22099][_#22099]) +* Add `SliceByTime()` for `drake::trajectories::PiecewisePolynomial` ([#22099][_#22099]) ## pydrake bindings @@ -115,8 +115,6 @@ Fixes -* Upgrade bazelisk to latest release v1.22.1 ([#22119][_#22119]) -* Upgrade Bazel to latest release 7.4.0 ([#22066][_#22066]) * Use EGL by default on Ubuntu ([#22081][_#22081]) ## Build dependencies @@ -125,6 +123,8 @@ Fixes * Force-disable CoinUtils debugging hooks ([#22063][_#22063]) * Upgrade abseil_cpp_internal to latest commit ([#22118][_#22118]) +* Upgrade bazel to latest release 7.4.0 ([#22066][_#22066]) +* Upgrade bazelisk to latest release v1.22.1 ([#22119][_#22119]) * Upgrade crate_universe to latest releases ([#22119][_#22119]) * Upgrade dm_control_internal to latest release 1.0.24 ([#22119][_#22119]) * Upgrade drake_models to latest commit ([#22103][_#22103]) From b141b84b44b8d0834af91bedf39b45502f9ad804 Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Wed, 13 Nov 2024 15:15:48 -0800 Subject: [PATCH 14/18] Announcements --- doc/_release-notes/v1.35.0.md | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index 70bb0a456f12..0a0f64c0f8df 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -6,7 +6,14 @@ released: YYYY-MM-DD # Announcements -* None +* MultibodyPlant now provides function SetBaseBodyJointType() which can be + called pre-Finalize to control what type of joint is used for connecting + unattached bodies to World ([#21973][_#21973]). + * The default choice remains QuaternionFloatingJoint but RpyFloatingJoint + and WeldJoint are options that can be set globally or for particular + Model Instances. + * The Joint API is extended to permit setting pose and velocity + generically without knowing the underlying joint type. # Breaking changes since v1.34.0 From a8373de3a184bf4739275ee8ccb996f8306f3440 Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Wed, 13 Nov 2024 17:24:18 -0800 Subject: [PATCH 15/18] Reviewable: mathematical programs in parallel 21957 --- doc/_release-notes/v1.35.0.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index 0a0f64c0f8df..6568766bc6f5 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -42,7 +42,7 @@ Fixes New features -* Solve mathematical programs in parallel ([#21957][_#21957]) +* Add a convenience method for solving mathematical programs in parallel in both C++ and Python ([#21957][_#21957]) * Add `CommonSolverOption::to_string` ([#22079][_#22079]) * Introduce `ImplicitGraphOfConvexSets` ([#22074][_#22074]) * Leverage parallelization where possible when checking boundedness of a `ConvexSet` ([#22084][_#22084]) From 6f7cfa5d0498e7b9f4915ef6420b79b20afb9853 Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Wed, 13 Nov 2024 18:34:37 -0800 Subject: [PATCH 16/18] bazel-bin/tools/release_engineering/relnotes --action=update --version=v1.35.0 --- doc/_release-notes/v1.35.0.md | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index 6568766bc6f5..4529917f0a7e 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -40,6 +40,8 @@ Fixes +* [feature] TBD Retrieve dual solution for LMI constraint for Mosek ([#22144][_#22144]) +* [feature] TBD Parallelize the GCS Preprocessing Stage ([#21965][_#21965]) # Co-Authored-By: amice New features * Add a convenience method for solving mathematical programs in parallel in both C++ and Python ([#21957][_#21957]) @@ -182,6 +184,7 @@ Philip E. Gill and Elizabeth Wong for their kind support. [_#21900]: https://github.com/RobotLocomotion/drake/pull/21900 [_#21929]: https://github.com/RobotLocomotion/drake/pull/21929 [_#21957]: https://github.com/RobotLocomotion/drake/pull/21957 +[_#21965]: https://github.com/RobotLocomotion/drake/pull/21965 [_#21973]: https://github.com/RobotLocomotion/drake/pull/21973 [_#22057]: https://github.com/RobotLocomotion/drake/pull/22057 [_#22062]: https://github.com/RobotLocomotion/drake/pull/22062 @@ -214,6 +217,7 @@ Philip E. Gill and Elizabeth Wong for their kind support. [_#22130]: https://github.com/RobotLocomotion/drake/pull/22130 [_#22136]: https://github.com/RobotLocomotion/drake/pull/22136 [_#22142]: https://github.com/RobotLocomotion/drake/pull/22142 +[_#22144]: https://github.com/RobotLocomotion/drake/pull/22144 [_#22148]: https://github.com/RobotLocomotion/drake/pull/22148 [_#22151]: https://github.com/RobotLocomotion/drake/pull/22151 [_#22152]: https://github.com/RobotLocomotion/drake/pull/22152 @@ -221,5 +225,5 @@ Philip E. Gill and Elizabeth Wong for their kind support. From e3ba058ecd06ae3bdf80cfd53710516c85ab63a4 Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Wed, 13 Nov 2024 18:50:28 -0800 Subject: [PATCH 17/18] Polish 22144 and 21965 --- doc/_release-notes/v1.35.0.md | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index 4529917f0a7e..8ac56be69a6b 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -40,8 +40,7 @@ Fixes -* [feature] TBD Retrieve dual solution for LMI constraint for Mosek ([#22144][_#22144]) -* [feature] TBD Parallelize the GCS Preprocessing Stage ([#21965][_#21965]) # Co-Authored-By: amice + New features * Add a convenience method for solving mathematical programs in parallel in both C++ and Python ([#21957][_#21957]) @@ -51,6 +50,9 @@ New features * Set gradient sparsity pattern in `LorentzConeConstraint` and `RotatedLorentzConeConstraint` ([#22125][_#22125]) * Update single entry of coefficients in `LinearCost` and `QuadraticCost` ([#22152][_#22152]) * Parallelize `ComputePairwiseIntersections()` for Graph of Convex Sets (with or without continuous revolute joints) ([#22142][_#22142]) +* Retrieve dual solution for `LinearMatrixInequalityConstraint` for Mosek ([#22144][_#22144]) +* Parallelize the `GraphOfConvexSets` preprocessing stage ([#21965][_#21965]) + Fixes From dd6b335287627908ad1c9928aab17c359f4e575e Mon Sep 17 00:00:00 2001 From: damrongguoy Date: Thu, 14 Nov 2024 11:03:44 -0800 Subject: [PATCH 18/18] Get the last commit for the Nightly Production from last night: bazel-bin/tools/release_engineering/relnotes --action=update --version=v1.35.0 \ --target_commit=36133672b4e2ba86e89157828a80207abe488234 --- doc/_release-notes/v1.35.0.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/_release-notes/v1.35.0.md b/doc/_release-notes/v1.35.0.md index 8ac56be69a6b..e00e677f0b91 100644 --- a/doc/_release-notes/v1.35.0.md +++ b/doc/_release-notes/v1.35.0.md @@ -227,5 +227,5 @@ Philip E. Gill and Elizabeth Wong for their kind support.