Skip to content

Commit

Permalink
Push unreleased deprecations back to 2021-04-01 (RobotLocomotion#14430)
Browse files Browse the repository at this point in the history
* Push unreleased deprecations back to 2021-04-01

Because we did not tag a release during November, we should not count that
month toward the deprecation sunset.
  • Loading branch information
jwnimmer-tri authored Dec 9, 2020
1 parent 36f9a51 commit 5b5d6aa
Show file tree
Hide file tree
Showing 14 changed files with 37 additions and 37 deletions.
8 changes: 4 additions & 4 deletions bindings/pydrake/geometry_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -279,7 +279,7 @@ void def_geometry_render(py::module m) {
m, "CameraProperties", doc.CameraProperties.doc_deprecated);
cls // BR
.def(py_init_deprecated<Class, int, int, double, std::string>(
"Deprecated; due to be removed after 2021-03-01. Please use "
"Deprecated; due to be removed after 2021-04-01. Please use "
"ColorRenderCamera instead"),
py::arg("width"), py::arg("height"), py::arg("fov_y"),
py::arg("renderer_name"), doc.CameraProperties.ctor.doc)
Expand All @@ -299,7 +299,7 @@ void def_geometry_render(py::module m) {
cls // BR
.def(py_init_deprecated<Class, int, int, double, std::string, double,
double>(
"Deprecated; due to be removed after 2021-03-01. Please use "
"Deprecated; due to be removed after 2021-04-01. Please use "
"DepthRenderCamera instead"),
py::arg("width"), py::arg("height"), py::arg("fov_y"),
py::arg("renderer_name"), py::arg("z_near"), py::arg("z_far"),
Expand Down Expand Up @@ -490,7 +490,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
WrapDeprecated(
"Please use SceneGraphInspector.SourceIsRegistered("
"source_id=value) instead. This variant will be removed after"
" after 2021-03-01",
" after 2021-04-01",
&Class::SourceIsRegistered),
py::arg("id"), cls_doc.SourceIsRegistered.doc)
.def("GetName",
Expand Down Expand Up @@ -818,7 +818,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
WrapDeprecated("Please use "
"QueryObject.ComputeSignedDistancePairClosestPoints("
"geometry_id_A=value1, geometry_id_B=value2). This "
"variant will be removed on or after 2021-03-01.",
"variant will be removed on or after 2021-04-01.",
&QueryObject<T>::ComputeSignedDistancePairClosestPoints),
py::arg("id_A"), py::arg("id_B"),
cls_doc.ComputeSignedDistancePairClosestPoints.doc)
Expand Down
4 changes: 2 additions & 2 deletions bindings/pydrake/systems/meshcat_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -423,7 +423,7 @@ def DoPublish(self, context, event):
"builder.Connect("
"scene_graph.get_query_output_port(), "
"visualizer.get_geometry_query_input_port())\n"
"instead.", date="2021-03-01")
"instead.", date="2021-04-01")
self._warned_pose_bundle_input_port_connected = True

vis = self.vis[self.prefix]
Expand Down Expand Up @@ -559,7 +559,7 @@ def DoPublish(self, context, event):
_warn_deprecated(
"The pose_bundle input port of MeshcatContactVisualizer is"
"deprecated; use the geometry_query inport port instead.",
date="2021-03-01")
date="2021-04-01")
self._warned_pose_bundle_input_port_connected = True

contact_results = self.EvalAbstractInput(context, 1).get_value()
Expand Down
2 changes: 1 addition & 1 deletion examples/manipulation_station/manipulation_station.h
Original file line number Diff line number Diff line change
Expand Up @@ -272,7 +272,7 @@ class ManipulationStation : public systems::Diagram<T> {
/// camera body, RGB, and depth image frames are related.
/// @param properties Properties for the RGBD camera.
/// @pydrake_mkdoc_identifier{single_properties}
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"CameraProperties are being deprecated. Please use the "
"DepthRenderCamera variant.")
void RegisterRgbdSensor(
Expand Down
6 changes: 3 additions & 3 deletions geometry/geometry_state.h
Original file line number Diff line number Diff line change
Expand Up @@ -502,7 +502,7 @@ class GeometryState {
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
/** Implementation of QueryObject::RenderColorImage().
@pre All poses have already been updated. */
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"CameraProperties are being deprecated. Please use the "
"ColorRenderCamera variant.")
void RenderColorImage(const render::CameraProperties& camera,
Expand All @@ -512,7 +512,7 @@ class GeometryState {

/** Implementation of QueryObject::RenderDepthImage().
@pre All poses have already been updated. */
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"CameraProperties are being deprecated. Please use the "
"DepthRenderCamera variant.")
void RenderDepthImage(const render::DepthCameraProperties& camera,
Expand All @@ -521,7 +521,7 @@ class GeometryState {

/** Implementation of QueryObject::RenderLabelImage().
@pre All poses have already been updated. */
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"CameraProperties are being deprecated. Please use the "
"ColorRenderCamera variant.")
void RenderLabelImage(const render::CameraProperties& camera,
Expand Down
6 changes: 3 additions & 3 deletions geometry/geometry_visualization.h
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ class GeometryVisualizationImpl {
@see geometry::DispatchLoadMessage()
@ingroup visualization
*/
DRAKE_DEPRECATED("2021-03-01", "Please use DrakeVisualizer::AddToBuilder().")
DRAKE_DEPRECATED("2021-04-01", "Please use DrakeVisualizer::AddToBuilder().")
systems::lcm::LcmPublisherSystem* ConnectDrakeVisualizer(
systems::DiagramBuilder<double>* builder,
const SceneGraph<double>& scene_graph,
Expand All @@ -113,7 +113,7 @@ systems::lcm::LcmPublisherSystem* ConnectDrakeVisualizer(
@see ConnectDrakeVisualizer().
*/
DRAKE_DEPRECATED("2021-03-01", "Please use DrakeVisualizer::AddToBuilder().")
DRAKE_DEPRECATED("2021-04-01", "Please use DrakeVisualizer::AddToBuilder().")
systems::lcm::LcmPublisherSystem* ConnectDrakeVisualizer(
systems::DiagramBuilder<double>* builder,
const SceneGraph<double>& scene_graph,
Expand All @@ -129,7 +129,7 @@ systems::lcm::LcmPublisherSystem* ConnectDrakeVisualizer(
LCM channel "DRAKE_VIEWER_LOAD_ROBOT".
@see geometry::ConnectDrakeVisualizer() */
DRAKE_DEPRECATED("2021-03-01", "Please use DrakeVisualizer::SendLoadMessage().")
DRAKE_DEPRECATED("2021-04-01", "Please use DrakeVisualizer::SendLoadMessage().")
void DispatchLoadMessage(const SceneGraph<double>& scene_graph,
lcm::DrakeLcmInterface* lcm,
Role role = Role::kIllustration);
Expand Down
12 changes: 6 additions & 6 deletions geometry/query_object.h
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ class QueryObject {
const math::RigidTransform<T>& GetPoseInWorld(FrameId frame_id) const;

/** Deprecated variant of GetPoseInWorld(FrameId). */
DRAKE_DEPRECATED("2021-03-01", "Please use GetPoseInWorld(FrameId) instead.")
DRAKE_DEPRECATED("2021-04-01", "Please use GetPoseInWorld(FrameId) instead.")
const math::RigidTransform<T>& X_WF(FrameId id) const;

/** Reports the position of the frame indicated by `frame_id` relative to its
Expand All @@ -124,7 +124,7 @@ class QueryObject {
const math::RigidTransform<T>& GetPoseInParent(FrameId frame_id) const;

/** Deprecated variant of GetPoseInParent(). */
DRAKE_DEPRECATED("2021-03-01", "Please use GetPoseInParent(FrameId) instead.")
DRAKE_DEPRECATED("2021-04-01", "Please use GetPoseInParent(FrameId) instead.")
const math::RigidTransform<T>& X_PF(FrameId id) const;

/** Reports the position of the geometry indicated by `geometry_id` relative
Expand All @@ -133,7 +133,7 @@ class QueryObject {
const math::RigidTransform<T>& GetPoseInWorld(GeometryId geometry_id) const;

/** Deprecated variant of GetPoseInWorld(GeometryId). */
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"Please use GetPoseInWorld(GeometryId) instead.")
const math::RigidTransform<T>& X_WG(GeometryId id) const;

Expand Down Expand Up @@ -514,7 +514,7 @@ class QueryObject {
@param X_PC The pose of the camera body in the parent frame.
@param show_window If true, the render window will be displayed.
@param[out] color_image_out The rendered color image. */
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"CameraProperties are being deprecated. Please use the "
"ColorRenderCamera variant.")
void RenderColorImage(const render::CameraProperties& camera,
Expand Down Expand Up @@ -548,7 +548,7 @@ class QueryObject {
@param parent_frame The id for the camera's parent frame.
@param X_PC The pose of the camera body in the parent frame.
@param[out] depth_image_out The rendered depth image. */
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"CameraProperties are being deprecated. Please use the "
"DepthRenderCamera variant.")
void RenderDepthImage(const render::DepthCameraProperties& camera,
Expand Down Expand Up @@ -582,7 +582,7 @@ class QueryObject {
@param X_PC The pose of the camera body in the parent frame.
@param show_window If true, the render window will be displayed.
@param[out] label_image_out The rendered label image. */
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"CameraProperties are being deprecated. Please use the "
"ColorRenderCamera variant.")
void RenderLabelImage(const render::CameraProperties& camera,
Expand Down
4 changes: 2 additions & 2 deletions geometry/render/camera_properties.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace render {
The focal length is inferred by the sensor format (width and height) and the
field of view along the y-axis. */
struct DRAKE_DEPRECATED("2021-03-01",
struct DRAKE_DEPRECATED("2021-04-01",
"CameraProperties are being deprecated. Please use "
"ColorRenderCamera.") CameraProperties {
CameraProperties(int width_in, int height_in, double fov_y_in,
Expand All @@ -45,7 +45,7 @@ struct DRAKE_DEPRECATED("2021-03-01",
intrinsic properties of the render camera but extended with additional
depth-specific parameters.
@see CameraProperties */
struct DRAKE_DEPRECATED("2021-03-01",
struct DRAKE_DEPRECATED("2021-04-01",
"DepthCameraProperties are being deprecated. Please "
"use DepthRenderCamera.")
DepthCameraProperties : public CameraProperties {
Expand Down
6 changes: 3 additions & 3 deletions geometry/render/render_engine.h
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,7 @@ class RenderEngine : public ShapeReifier {
@param show_window If true, the render window will be displayed.
@param[out] color_image_out The rendered color image.
@pydrake_mkdoc_identifier{deprecated} */
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"CameraProperties are being deprecated. Prefer the "
"ColorRenderCamera variant; implement the protected "
"DoRenderColorImage() method.")
Expand All @@ -252,7 +252,7 @@ class RenderEngine : public ShapeReifier {
@param camera The intrinsic properties of the camera.
@param[out] depth_image_out The rendered depth image. */
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"DepthCameraProperties are being deprecated. Prefer the "
"DepthRenderCamera variant; implement the protected "
"DoRenderDepthImage() method.")
Expand All @@ -271,7 +271,7 @@ class RenderEngine : public ShapeReifier {
@param show_window If true, the render window will be displayed.
@param[out] label_image_out The rendered label image.
@pydrake_mkdoc_identifier{deprecated} */
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"CameraProperties are being deprecated. Prefer the "
"ColorRenderCamera variant; implement the protected "
"DoRenderLabelImage() method.")
Expand Down
2 changes: 1 addition & 1 deletion geometry/render/test/render_engine_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -381,7 +381,7 @@ GTEST_TEST(RenderEngine, DetectDoCloneFailure) {
}

// Test infrastructure to support deprecation efforts. After completing the
// deprecation (2021-03-01), all of this test infrastructure can/should simply
// deprecation (2021-04-01), all of this test infrastructure can/should simply
// go away. In the deprecation period there are three possible configurations of
// a child RenderEngine class:
//
Expand Down
2 changes: 1 addition & 1 deletion geometry/scene_graph.h
Original file line number Diff line number Diff line change
Expand Up @@ -298,7 +298,7 @@ class SceneGraph final : public systems::LeafSystem<T> {
@param data_as_state `true` stores the data as State; `false` stores it as a
Parameter. */
DRAKE_DEPRECATED(
"2021-02-01",
"2021-04-01",
"The choice of storing geometry data as State has been deprecated. "
"Please use the default constructor which sets the geometry data as a "
"Parameter. If this doesn't work for you please submit an issue in Drake "
Expand Down
2 changes: 1 addition & 1 deletion geometry/scene_graph_inspector.h
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,7 @@ class SceneGraphInspector {

/** Reports the name for the source with the given `id`.
@throws std::logic_error if `id` does not map to a registered source. */
DRAKE_DEPRECATED("2021-03-01", "Please use GetName(SourceId) instead.")
DRAKE_DEPRECATED("2021-04-01", "Please use GetName(SourceId) instead.")
const std::string& GetSourceName(SourceId id) const {
DRAKE_DEMAND(state_ != nullptr);
return state_->GetName(id);
Expand Down
12 changes: 6 additions & 6 deletions solvers/symbolic_extraction.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ void AppendToVector(const typename Derived::Scalar& s,
/*
* Adds context to symbolic expression-related errors.
*/
class DRAKE_DEPRECATED("2021-03-01",
class DRAKE_DEPRECATED("2021-04-01",
"Use SymbolicError in common/symbolic_decompose.h")
SymbolicError : public std::runtime_error {
public:
Expand All @@ -65,7 +65,7 @@ class DRAKE_DEPRECATED("2021-03-01",
* `vars`, and map_var_to_index[vars(i).get_id()] = i. This invariance holds
* for map_var_to_index both as the input and as the output.
*/
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"Use ExtractAndAppendVariablesFromExpression() in "
"common/symbolic_decompose.h")
void ExtractAndAppendVariablesFromExpression(
Expand All @@ -79,7 +79,7 @@ void ExtractAndAppendVariablesFromExpression(
* from the variable ID to the index in pair.first, such that
* pair.second[pair.first(i).get_id()] = i
*/
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"Use ExtractAndVariablesFromExpression() in "
"common/symbolic_decompose.h")
std::pair<VectorXDecisionVariable,
Expand All @@ -99,7 +99,7 @@ ExtractVariablesFromExpression(const symbolic::Expression& e);
* `b` should be `num_variables * 1`.
* @param c[out] The constant term of the quadratic expression.
*/
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"Use DecomposeQuadraticPolynomial() in "
"common/symbolic_decompose.h")
void DecomposeQuadraticPolynomial(
Expand All @@ -115,7 +115,7 @@ void DecomposeQuadraticPolynomial(
* @param[out] b The vector containing all the constant terms.
* @param[out] vars All variables.
*/
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"Use DecomposeAffineExpressions() in "
"common/symbolic_decompose.h")
void DecomposeLinearExpression(
Expand Down Expand Up @@ -148,7 +148,7 @@ void DecomposeLinearExpression(
* has 1 variable, 2 * x(0) + 3 * x(1) - 2 * x(0) has 1 variable.
*/
template <typename Derived>
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"Use DecomposeAffineExpression() in "
"common/symbolic_decompose.h")
typename std::enable_if<std::is_same<typename Derived::Scalar, double>::value,
Expand Down
2 changes: 1 addition & 1 deletion systems/framework/diagram.h
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ class Diagram : public System<T>, internal::SystemParentServiceInterface {

/// Returns an arbitrary "locator" for one of the subsystem input ports that
/// were exported to the @p port_index input port for the Diagram.
DRAKE_DEPRECATED("2021-03-01", "Use GetInputPortLocators() instead.")
DRAKE_DEPRECATED("2021-04-01", "Use GetInputPortLocators() instead.")
InputPortLocator get_input_port_locator(InputPortIndex port_index) const;

/// Returns the "locator" for the subsystem output port that was exported as
Expand Down
6 changes: 3 additions & 3 deletions systems/sensors/rgbd_sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ class RgbdSensor final : public LeafSystem<double> {

/** Specifies poses of cameras with respect ot the sensor base `B`.
*/
struct DRAKE_DEPRECATED("2021-03-01",
struct DRAKE_DEPRECATED("2021-04-01",
"The constructors that take poses explicitly have been "
"deprecated. Pose is now part of the RenderCamera "
"interface. See the RenderCamera-based RgbdSensor "
Expand Down Expand Up @@ -141,7 +141,7 @@ class RgbdSensor final : public LeafSystem<double> {
off-screen rendering is executed. The default is false.
@pydrake_mkdoc_identifier{legacy_individual_intrinsics}
*/
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"CameraProperties are being deprecated. Please use the "
"RenderCamera variant.")
RgbdSensor(geometry::FrameId parent_id,
Expand All @@ -156,7 +156,7 @@ class RgbdSensor final : public LeafSystem<double> {
properties, and all of `properties` for depth properties.
@pydrake_mkdoc_identifier{legacy_combined_intrinsics}
*/
DRAKE_DEPRECATED("2021-03-01",
DRAKE_DEPRECATED("2021-04-01",
"CameraProperties are being deprecated. Please use the "
"RenderCamera variant.")
RgbdSensor(geometry::FrameId parent_id, const math::RigidTransformd& X_PB,
Expand Down

0 comments on commit 5b5d6aa

Please sign in to comment.