Skip to content

Commit

Permalink
Replace Doxygen /** with /* for internal API (#21840)
Browse files Browse the repository at this point in the history
  • Loading branch information
sherm1 authored Aug 22, 2024
1 parent 4746323 commit 923a09a
Show file tree
Hide file tree
Showing 11 changed files with 188 additions and 200 deletions.
2 changes: 1 addition & 1 deletion multibody/topology/forest.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#pragma once

/** @file
/* @file
This is the file to #include to use SpanningForest. It includes
subsidiary headers for nested class definitions to keep file sizes
reasonable. */
Expand Down
2 changes: 1 addition & 1 deletion multibody/topology/graph.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#pragma once

/** @file
/* @file
This is the file to #include to use LinkJointGraph. It includes
subsidiary headers for nested class definitions to keep file sizes
reasonable. */
Expand Down
122 changes: 58 additions & 64 deletions multibody/topology/link_joint_graph.h

Large diffs are not rendered by default.

6 changes: 3 additions & 3 deletions multibody/topology/link_joint_graph_defs.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ using JointTraitsIndex = TypeSafeIndex<class JointTraitsTag>;
using LinkCompositeIndex = TypeSafeIndex<class LinkCompositeTag>;
using LoopConstraintIndex = TypeSafeIndex<class LoopConstraintTag>;

/** Link properties that can affect how the forest model gets built. Or-ing
/* Link properties that can affect how the forest model gets built. Or-ing
these also produces a LinkFlags object. */
enum class LinkFlags : uint32_t {
kDefault = 0,
Expand All @@ -34,14 +34,14 @@ enum class LinkFlags : uint32_t {
kShadow = 1 << 3 ///< Link is a shadow (internal use only).
};

/** Joint properties that can affect how the SpanningForest gets built. Or-ing
/* Joint properties that can affect how the SpanningForest gets built. Or-ing
these also produces a JointFlags object. */
enum class JointFlags : uint32_t {
kDefault = 0,
kMustBeModeled = 1 << 0 ///< Model explicitly even if ignorable weld.
};

/** Options for how to build the SpanningForest. Or-ing these also produces a
/* Options for how to build the SpanningForest. Or-ing these also produces a
ForestBuildingOptions object. These can be provided as per-model instance
options to locally override global options. */
enum class ForestBuildingOptions : uint32_t {
Expand Down
28 changes: 14 additions & 14 deletions multibody/topology/link_joint_graph_joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,39 +18,39 @@ class LinkJointGraph::Joint {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(Joint);

/** Returns this %Joint's unique index in the graph. This is persistent after
/* Returns this %Joint's unique index in the graph. This is persistent after
the %Joint has been allocated. */
JointIndex index() const { return index_; }

/** Returns the current value of this %Joint's ordinal (position in the
/* Returns the current value of this %Joint's ordinal (position in the
joints() vector). This can change as %Joints are removed. */
JointOrdinal ordinal() const { return ordinal_; }

/** Returns this %Joint's model instance. */
/* Returns this %Joint's model instance. */
ModelInstanceIndex model_instance() const { return model_instance_; }

/** Returns this %Joint's name, unique within model_instance(). */
/* Returns this %Joint's name, unique within model_instance(). */
const std::string& name() const { return name_; }

/** Returns the index of this %Joint's parent Link. */
/* Returns the index of this %Joint's parent Link. */
LinkIndex parent_link_index() const { return parent_link_index_; }

/** Returns the index of this %Joint's child Link. */
/* Returns the index of this %Joint's child Link. */
LinkIndex child_link_index() const { return child_link_index_; }

/** Returns `true` if this is a Weld %Joint. */
/* Returns `true` if this is a Weld %Joint. */
bool is_weld() const { return traits_index() == weld_joint_traits_index(); }

/** Returns the index of this %Joint's traits. */
/* Returns the index of this %Joint's traits. */
JointTraitsIndex traits_index() const { return traits_index_; }

/** Returns `true` if either the parent or child Link of this %Joint is
/* Returns `true` if either the parent or child Link of this %Joint is
the specified `link`. */
bool connects(LinkIndex link) const {
return link == parent_link_index() || link == child_link_index();
}

/** Returns `true` if this %Joint connects the two given Links. That is, if
/* Returns `true` if this %Joint connects the two given Links. That is, if
one of these is the parent Link and the other is the child Link, in either
order. */
bool connects(LinkIndex link1, LinkIndex link2) const {
Expand All @@ -62,7 +62,7 @@ class LinkJointGraph::Joint {
// return link_index ^ (parent_link_index ^ child_link_index);
// with the second term precalculated. Consider that if performance warrants.

/** Given one of the Links connected by this %Joint, returns the other one.
/* Given one of the Links connected by this %Joint, returns the other one.
@pre `link_index` is either the parent or child */
LinkIndex other_link_index(LinkIndex link_index) const {
DRAKE_DEMAND((parent_link_index() == link_index) ||
Expand All @@ -71,21 +71,21 @@ class LinkJointGraph::Joint {
: parent_link_index();
}

/** Returns `true` if this %Joint was added with
/* Returns `true` if this %Joint was added with
JointFlags::kMustBeModeled. */
bool must_be_modeled() const {
return static_cast<bool>(flags_ & JointFlags::kMustBeModeled);
}

/** Returns the index of the Mobod whose inboard mobilizer models this
/* Returns the index of the Mobod whose inboard mobilizer models this
%Joint, if any. If this %Joint is unmodeled then the returned index is
invalid. */
MobodIndex mobod_index() const {
if (!std::holds_alternative<MobodIndex>(how_modeled_)) return MobodIndex();
return std::get<MobodIndex>(how_modeled_);
}

/** (Internal use only) During construction of the forest, this is used
/* (Internal use only) During construction of the forest, this is used
to check whether this %Joint has already been modeled. */
bool has_been_processed() const {
return !std::holds_alternative<std::monostate>(how_modeled_);
Expand Down
40 changes: 20 additions & 20 deletions multibody/topology/link_joint_graph_link.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ namespace multibody {
// TODO(sherm1) Promote from internal once API has stabilized: issue #11307.
namespace internal {

/** Represents a %Link in the LinkJointGraph. This includes Links provided via
/* Represents a %Link in the LinkJointGraph. This includes Links provided via
user input and also those added during forest building as Shadow links created
when we cut a user %Link in order to break a kinematic loop. Links may be
modeled individually or can be combined into LinkComposites comprising groups
Expand All @@ -23,47 +23,47 @@ class LinkJointGraph::Link {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(Link);

/** Returns this %Link's unique index in the graph. This is persistent after
/* Returns this %Link's unique index in the graph. This is persistent after
the %Link has been allocated. */
LinkIndex index() const { return index_; }

/** Returns the current value of this %Link's ordinal (position in the
/* Returns the current value of this %Link's ordinal (position in the
links() vector). This can change as %Links are removed. */
LinkOrdinal ordinal() const { return ordinal_; }

/** Returns this %Link's model instance. */
/* Returns this %Link's model instance. */
ModelInstanceIndex model_instance() const { return model_instance_; }

/** Returns this %Link's name, unique within model_instance(). */
/* Returns this %Link's name, unique within model_instance(). */
const std::string& name() const { return name_; }

/** Returns indexes of all the Joints that connect to this %Link. This is
/* Returns indexes of all the Joints that connect to this %Link. This is
the union of joints_as_parent() and joints_as_child(). */
const std::vector<JointIndex>& joints() const { return joints_; }

/** Returns indexes of all the Joints that connect to this %Link in which
/* Returns indexes of all the Joints that connect to this %Link in which
this is the parent %Link. */
const std::vector<JointIndex>& joints_as_parent() const {
return joints_as_parent_;
}

/** Returns indexes of all the joints that connect to this %Link in which
/* Returns indexes of all the joints that connect to this %Link in which
this is the child %Link. */
const std::vector<JointIndex>& joints_as_child() const {
return joints_as_child_;
}

/** Returns indexes of all the LoopConstraints that connect to this %Link. */
/* Returns indexes of all the LoopConstraints that connect to this %Link. */
const std::vector<LoopConstraintIndex>& loop_constraints() const {
return loop_constraints_;
}

/** Returns `true` only if this is the World %Link. Static Links and Links
/* Returns `true` only if this is the World %Link. Static Links and Links
in the World Composite are not included; see is_anchored() if you want to
include everything that is fixed with respect to World. */
bool is_world() const { return index_ == LinkIndex(0); }

/** After modeling, returns `true` if this %Link is fixed with respect to
/* After modeling, returns `true` if this %Link is fixed with respect to
World. That includes World itself, static Links, and any Link that is part
of the World Composite (that is, it is directly or indirectly welded to
World). */
Expand All @@ -72,38 +72,38 @@ class LinkJointGraph::Link {
(composite() == LinkCompositeIndex(0));
}

/** Returns `true` if this %Link was added with LinkFlags::kStatic. */
/* Returns `true` if this %Link was added with LinkFlags::kStatic. */
bool is_static_flag_set() const {
return static_cast<bool>(flags_ & LinkFlags::kStatic);
}

/** Returns `true` if this %Link was added with LinkFlags::kMustBeBaseBody. */
/* Returns `true` if this %Link was added with LinkFlags::kMustBeBaseBody. */
bool must_be_base_body() const {
return static_cast<bool>(flags_ & LinkFlags::kMustBeBaseBody);
}

/** Returns `true` if this %Link was added with LinkFlags::kMassless.
/* Returns `true` if this %Link was added with LinkFlags::kMassless.
However, this %Link may still be _effectively_ massful if it is welded
into a massful composite. See
LinkJointGraph::link_and_its_composite_are_massless() for the full story. */
bool is_massless() const {
return static_cast<bool>(flags_ & LinkFlags::kMassless);
}

/** Returns `true` if this is a shadow Link added by BuildForest(). */
/* Returns `true` if this is a shadow Link added by BuildForest(). */
bool is_shadow() const {
return static_cast<bool>(flags_ & LinkFlags::kShadow);
}

/** If this %Link is a shadow, returns the primary %Link it shadows. If
/* If this %Link is a shadow, returns the primary %Link it shadows. If
not a shadow then it is its own primary %Link so returns index(). */
LinkIndex primary_link() const { return primary_link_; }

/** If this is a primary %Link (not a shadow) returns the number of Shadow
/* If this is a primary %Link (not a shadow) returns the number of Shadow
Links that were added due to loop breaking. */
int num_shadows() const { return ssize(shadow_links_); }

/** Returns the index of the mobilized body (Mobod) that mobilizes this %Link.
/* Returns the index of the mobilized body (Mobod) that mobilizes this %Link.
If this %Link is part of a LinkComposite, this is the Mobod that mobilizes the
LinkComposite as a whole via the composite's active %Link. If you ask
this Mobod what Joint it represents, it will report the Joint that was used
Expand All @@ -112,13 +112,13 @@ class LinkJointGraph::Link {
%Link to its LinkComposite. */
MobodIndex mobod_index() const { return mobod_; }

/** Returns the Joint that was used to associate this %Link with its
/* Returns the Joint that was used to associate this %Link with its
mobilized body. If this %Link is part of a LinkComposite, returns the Joint
that connects this %Link to the Composite, not necessarily the Joint that is
modeled by the Mobod returned by mobod_index(). */
JointIndex inboard_joint_index() const { return joint_; }

/** Returns the index of the LinkComposite this %Link is part of, if any.
/* Returns the index of the LinkComposite this %Link is part of, if any.
World is always in LinkComposite 0; any other link is in a Composite only if
it is connected by a weld joint to another link. */
std::optional<LinkCompositeIndex> composite() const {
Expand Down
2 changes: 1 addition & 1 deletion multibody/topology/link_joint_graph_loop_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ namespace multibody {
// TODO(sherm1) Promote from internal once API has stabilized: issue #11307.
namespace internal {

/** A weld constraint used to close a topological loop (cycle) in the input
/* A weld constraint used to close a topological loop (cycle) in the input
graph after modeling as a forest. The parent/child ordering sets the sign
convention for the constraint multipliers. Added welds between a primary %Link
and one of its shadow Links always make the primary %Link the parent. */
Expand Down
Loading

0 comments on commit 923a09a

Please sign in to comment.