Skip to content

Commit

Permalink
Round up deprecation dates to first of the month (RobotLocomotion#11533)
Browse files Browse the repository at this point in the history
Obeying the intermediate dates not an efficient use of our time.
  • Loading branch information
jwnimmer-tri authored May 23, 2019
1 parent 2cab67d commit 79a096d
Show file tree
Hide file tree
Showing 9 changed files with 28 additions and 28 deletions.
2 changes: 1 addition & 1 deletion bindings/pydrake/math_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ PYBIND11_MODULE(math, m) {
const char* doc_iso3_deprecation =
"DO NOT USE!. We only offer this API for backwards compatibility with "
"Isometry3 and it will be deprecated soon with the resolution of "
"#9865. This will be removed on or around 2019-06-26.";
"#9865. This will be removed on or around 2019-07-01.";

// TODO(eric.cousineau): At present, we only bind doubles.
// In the future, we will bind more scalar types, and enable scalar
Expand Down
4 changes: 2 additions & 2 deletions bindings/pydrake/systems/framework_py_systems.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,13 @@ namespace {

// TODO(eric.cousineau): Remove `*DeprecatedProtectedAlias*` cruft and
// replace `PYDRAKE_TRY_PROTECTED_OVERLOAD` with `PYBIND11_OVERLOAD` once
// deprecated methods are removed (on or around 2019-06-15).
// deprecated methods are removed (on or around 2019-07-01).

// Generates deprecation message pursuant to #9651.
std::string DeprecatedProtectedAliasMessage(
std::string name, std::string verb) {
return fmt::format(
"'_{0}' is deprecated and will be removed on or around 2019-06-15. "
"'_{0}' is deprecated and will be removed on or around 2019-07-01. "
"Please {1} '{0}' instead.",
name, verb);
}
Expand Down
2 changes: 1 addition & 1 deletion geometry/geometry_frame.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class GeometryFrame {
@param frame_group_id The optional frame group identifier. If unspecified,
defaults to the common, 0 group. Must be
non-negative. */
DRAKE_DEPRECATED("2019-06-26",
DRAKE_DEPRECATED("2019-07-01",
"GeometryFrame no longer requires a pose X_PF; prefer the "
"constructor without pose.")
GeometryFrame(const std::string& frame_name, const Isometry3<double>&,
Expand Down
2 changes: 1 addition & 1 deletion math/rigid_transform.h
Original file line number Diff line number Diff line change
Expand Up @@ -308,7 +308,7 @@ class RigidTransform {
#ifndef DRAKE_DOXYGEN_CXX
/// Until #9865 is resolved, this operator temporarily allows users mixing the
/// use of %RigidTransform with Isometry3.
DRAKE_DEPRECATED("2019-06-26",
DRAKE_DEPRECATED("2019-07-01",
"Do not mix RigidTransform with Isometry3. Only use "
"RigidTransform per #9865.")
RigidTransform<T> operator*(const Isometry3<T>& isometry3) const {
Expand Down
20 changes: 10 additions & 10 deletions multibody/plant/multibody_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -1556,7 +1556,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
///
/// @throws std::exception if `p_FP_list` does not have 3 rows.
// TODO(amcastro-tri): Rework this method as per issue #10155.
DRAKE_DEPRECATED("2019-08-17",
DRAKE_DEPRECATED("2019-09-01",
"Use CalcBiasForJacobianTranslationalVelocity().")
VectorX<T> CalcBiasForPointsGeometricJacobianExpressedInWorld(
const systems::Context<T>& context,
Expand Down Expand Up @@ -1830,7 +1830,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
/// @throws std::exception if `J_ABp` is nullptr or if it is not of size
/// `6 x nv`.
// TODO(amcastro-tri): Rework this method as per issue #10155.
DRAKE_DEPRECATED("2019-08-15", "Use CalcJacobianSpatialVelocity().")
DRAKE_DEPRECATED("2019-09-01", "Use CalcJacobianSpatialVelocity().")
void CalcRelativeFrameGeometricJacobian(
const systems::Context<T>& context,
const Frame<T>& frame_B, const Eigen::Ref<const Vector3<T>>& p_BP,
Expand Down Expand Up @@ -3117,7 +3117,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
// #9865. Right now we offer them for backwards compatibility.

DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
void SetFreeBodyPose(systems::Context<T>* context, const Body<T>& body,
Expand All @@ -3126,7 +3126,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
}

DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
void SetFreeBodyPose(const systems::Context<T>& context,
Expand All @@ -3138,7 +3138,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
// Allows having a non-empty X_PF isometry and a nullopt X_BM.
template <template <typename> class JointType, typename... Args>
DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
const JointType<T>& AddJoint(const std::string& name, const Body<T>& parent,
Expand All @@ -3161,7 +3161,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
// Allows having a nullopt X_PF and a non-empty X_BM isometry.
template <template <typename> class JointType, typename... Args>
DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
const JointType<T>& AddJoint(const std::string& name, const Body<T>& parent,
Expand Down Expand Up @@ -3213,7 +3213,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
}

DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
geometry::GeometryId RegisterVisualGeometry(
Expand All @@ -3226,7 +3226,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
}

DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
geometry::GeometryId RegisterVisualGeometry(
Expand All @@ -3239,7 +3239,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
}

DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
geometry::GeometryId RegisterVisualGeometry(
Expand All @@ -3251,7 +3251,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
}

DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
geometry::GeometryId RegisterCollisionGeometry(
Expand Down
8 changes: 4 additions & 4 deletions multibody/tree/fixed_offset_frame.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ class FixedOffsetFrame final : public Frame<T> {

#ifndef DRAKE_DOXYGEN_CXX
DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
FixedOffsetFrame(const std::string& name, const Frame<T>& P,
Expand All @@ -89,22 +89,22 @@ class FixedOffsetFrame final : public Frame<T> {
}

DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
FixedOffsetFrame(const Frame<T>& P, const Isometry3<double>& X_PF)
: FixedOffsetFrame(P, math::RigidTransformd(X_PF)) {}

DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
FixedOffsetFrame(const std::string& name, const Body<T>& bodyB,
const Isometry3<double>& X_BF)
: FixedOffsetFrame(name, bodyB, math::RigidTransformd(X_BF)) {}

DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
FixedOffsetFrame(const Body<T>& bodyB, const Isometry3<double>& X_BF)
Expand Down
2 changes: 1 addition & 1 deletion multibody/tree/weld_joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class WeldJoint final : public Joint<T> {

#ifndef DRAKE_DOXYGEN_CXX
DRAKE_DEPRECATED(
"2019-06-15",
"2019-07-01",
"This Isometry3 overload will be removed pending the resolution of "
"#9865. Use the RigidTransform overload instead.")
WeldJoint(const std::string& name, const Frame<T>& parent_frame_P,
Expand Down
2 changes: 1 addition & 1 deletion setup/mac/binary_distribution/install_prereqs.sh
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ fi

/usr/local/bin/brew update
# TODO(jamiesnape): Remove line uninstalling embree, ospray, and [email protected]
# formulae on or after 2019-06-30.
# formulae on or after 2019-07-01.
/usr/local/bin/brew uninstall --force embree ospray [email protected]
/usr/local/bin/brew bundle --file="${BASH_SOURCE%/*}/Brewfile"

Expand Down
14 changes: 7 additions & 7 deletions systems/framework/leaf_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -2202,15 +2202,15 @@ class LeafSystem : public System<T> {
}

template <class MySystem>
DRAKE_DEPRECATED("2019-06-31", "Please use MakeWitnessFunction().")
DRAKE_DEPRECATED("2019-07-01", "Please use MakeWitnessFunction().")
std::unique_ptr<WitnessFunction<T>> DeclareWitnessFunction(
const std::string& description,
const WitnessFunctionDirection& direction_type,
T (MySystem::*calc)(const Context<T>&) const) const {
return MakeWitnessFunction(description, direction_type, calc);
}

DRAKE_DEPRECATED("2019-06-31", "Please use MakeWitnessFunction().")
DRAKE_DEPRECATED("2019-07-01", "Please use MakeWitnessFunction().")
std::unique_ptr<WitnessFunction<T>> DeclareWitnessFunction(
const std::string& description,
const WitnessFunctionDirection& direction_type,
Expand All @@ -2219,7 +2219,7 @@ class LeafSystem : public System<T> {
}

template <class MySystem>
DRAKE_DEPRECATED("2019-06-31", "Please use MakeWitnessFunction().")
DRAKE_DEPRECATED("2019-07-01", "Please use MakeWitnessFunction().")
std::unique_ptr<WitnessFunction<T>> DeclareWitnessFunction(
const std::string& description,
const WitnessFunctionDirection& direction_type,
Expand All @@ -2231,7 +2231,7 @@ class LeafSystem : public System<T> {
}

template <class MySystem>
DRAKE_DEPRECATED("2019-06-31", "Please use MakeWitnessFunction().")
DRAKE_DEPRECATED("2019-07-01", "Please use MakeWitnessFunction().")
std::unique_ptr<WitnessFunction<T>> DeclareWitnessFunction(
const std::string& description,
const WitnessFunctionDirection& direction_type,
Expand All @@ -2243,7 +2243,7 @@ class LeafSystem : public System<T> {
}

template <class MySystem>
DRAKE_DEPRECATED("2019-06-31", "Please use MakeWitnessFunction().")
DRAKE_DEPRECATED("2019-07-01", "Please use MakeWitnessFunction().")
std::unique_ptr<WitnessFunction<T>> DeclareWitnessFunction(
const std::string& description,
const WitnessFunctionDirection& direction_type,
Expand All @@ -2255,7 +2255,7 @@ class LeafSystem : public System<T> {
}

template <class MySystem>
DRAKE_DEPRECATED("2019-06-31", "Please use MakeWitnessFunction().")
DRAKE_DEPRECATED("2019-07-01", "Please use MakeWitnessFunction().")
std::unique_ptr<WitnessFunction<T>> DeclareWitnessFunction(
const std::string& description,
const WitnessFunctionDirection& direction_type,
Expand All @@ -2264,7 +2264,7 @@ class LeafSystem : public System<T> {
return MakeWitnessFunction(description, direction_type, calc, e);
}

DRAKE_DEPRECATED("2019-06-31", "Please use MakeWitnessFunction().")
DRAKE_DEPRECATED("2019-07-01", "Please use MakeWitnessFunction().")
std::unique_ptr<WitnessFunction<T>> DeclareWitnessFunction(
const std::string& description,
const WitnessFunctionDirection& direction_type,
Expand Down

0 comments on commit 79a096d

Please sign in to comment.