Skip to content

Commit fb7eca1

Browse files
jwnimmer-triRussTedrake
authored andcommitted
[multibody] Deprecate FrameBase for removal (RobotLocomotion#21891)
1 parent 38e1049 commit fb7eca1

File tree

4 files changed

+46
-6
lines changed

4 files changed

+46
-6
lines changed

multibody/tree/BUILD.bazel

+2
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,7 @@ drake_cc_library(
9191
"fixed_offset_frame.cc",
9292
"force_element.cc",
9393
"frame.cc",
94+
"frame_base.cc",
9495
"joint.cc",
9596
"joint_actuator.cc",
9697
"linear_bushing_roll_pitch_yaw.cc",
@@ -134,6 +135,7 @@ drake_cc_library(
134135
"fixed_offset_frame.h",
135136
"force_element.h",
136137
"frame.h",
138+
"frame_base.h",
137139
"joint.h",
138140
"joint_actuator.h",
139141
"linear_bushing_roll_pitch_yaw.h",

multibody/tree/frame.h

+3-6
Original file line numberDiff line numberDiff line change
@@ -3,10 +3,10 @@
33
#include <memory>
44
#include <optional>
55
#include <string>
6-
#include <vector>
76

87
#include "drake/common/autodiff.h"
98
#include "drake/common/nice_type_name.h"
9+
#include "drake/multibody/tree/frame_base.h"
1010
#include "drake/multibody/tree/frame_body_pose_cache.h"
1111
#include "drake/multibody/tree/multibody_element.h"
1212
#include "drake/multibody/tree/multibody_tree_indexes.h"
@@ -50,15 +50,12 @@ template<typename T> class RigidBody;
5050
///
5151
/// @tparam_default_scalar
5252
template <typename T>
53-
class Frame : public MultibodyElement<T> {
53+
class Frame : public FrameBase<T> {
5454
public:
5555
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Frame);
5656

5757
~Frame() override;
5858

59-
/// Returns this %Frame's unique index.
60-
FrameIndex index() const { return this->template index_impl<FrameIndex>(); }
61-
6259
/// Returns a const reference to the body associated to this %Frame.
6360
const RigidBody<T>& body() const {
6461
return body_;
@@ -566,7 +563,7 @@ class Frame : public MultibodyElement<T> {
566563
explicit Frame(
567564
const std::string& name, const RigidBody<T>& body,
568565
std::optional<ModelInstanceIndex> model_instance = {})
569-
: MultibodyElement<T>(model_instance.value_or(body.model_instance())),
566+
: FrameBase<T>(model_instance.value_or(body.model_instance())),
570567
name_(internal::DeprecateWhenEmptyName(name, "Frame")),
571568
body_(body) {}
572569

multibody/tree/frame_base.cc

+15
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
#include "drake/multibody/tree/frame_base.h"
2+
3+
#include "drake/common/default_scalars.h"
4+
5+
namespace drake {
6+
namespace multibody {
7+
8+
template <typename T>
9+
FrameBase<T>::~FrameBase() = default;
10+
11+
} // namespace multibody
12+
} // namespace drake
13+
14+
DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
15+
class drake::multibody::FrameBase);

multibody/tree/frame_base.h

+26
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
#pragma once
2+
3+
#include "drake/multibody/tree/multibody_element.h"
4+
#include "drake/multibody/tree/multibody_tree_indexes.h"
5+
6+
namespace drake {
7+
namespace multibody {
8+
9+
/// %FrameBase is deprecated and will be removed on or after 2025-01-01.
10+
/// @tparam_default_scalar
11+
template <typename T>
12+
class FrameBase : public MultibodyElement<T> {
13+
public:
14+
// TODO(jwnimmer-tri) On 2025-01-01 move this into `class Frame`.
15+
/// Returns this element's unique index.
16+
FrameIndex index() const { return this->template index_impl<FrameIndex>(); }
17+
18+
~FrameBase() override;
19+
20+
protected:
21+
explicit FrameBase(ModelInstanceIndex model_instance)
22+
: MultibodyElement<T>(model_instance) {}
23+
};
24+
25+
} // namespace multibody
26+
} // namespace drake

0 commit comments

Comments
 (0)