Skip to content

Commit

Permalink
Documentation fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
Jamie Snape committed Oct 17, 2018
1 parent f9f774a commit a157119
Show file tree
Hide file tree
Showing 88 changed files with 298 additions and 271 deletions.
14 changes: 7 additions & 7 deletions attic/multibody/collision/collision_filter_doxygen.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ when bodies occupy the same space and, to a certain extent, quantify the degree
to which they invalidate the collision constraint.
Next topic: @ref collision_filter_concepts
**/
*/

/** @defgroup collision_filter_concepts Collision Filter Concepts
@ingroup collision_concepts
Expand Down Expand Up @@ -108,7 +108,7 @@ This representation is particularly helpful in discussing @ref collision_clique
and in comparing @ref collision_clique with @ref collision_filter_group.
Next topic: @ref collision_clique
**/
*/

/** @defgroup collision_clique Collision Cliques
@ingroup collision_filter_concepts
Expand Down Expand Up @@ -177,7 +177,7 @@ hold `E` and use a weld (fixed) joint to attach `Z` to `B`. `Z` will not be
adjacent to A, so `E` will interact with `A`'s elements.
Next topic: @ref collision_filter_group
**/
*/

/** @defgroup collision_filter_group Collision Filter Groups
@ingroup collision_filter_concepts
Expand Down Expand Up @@ -337,7 +337,7 @@ to bit zero. A collision element can be rendered "invisible" by assigning it
to a group that ignores this universal group.
Next topic: @ref collision_filter_mapping
**/
*/

/** @defgroup collision_filter_mapping Relationship Between Collision Filter Implementations
@ingroup collision_filter_concepts
Expand Down Expand Up @@ -475,7 +475,7 @@ costs and are ideally suited for excluding large classes of bodies from
collision computation.
Next topic: @ref collision_filter_file_semantics
**/
*/

/** @defgroup collision_filter_file_semantics Input File Collision Semantics
@ingroup collision_filter_concepts
Expand All @@ -493,7 +493,7 @@ Next topic: @ref collision_filter_file_semantics
@note This section is incomplete.
Next topic: @ref collision_filter_future
**/
*/

/** @defgroup collision_filter_future Future Collision Filter Features
@ingroup collision_filter_concepts
Expand All @@ -510,4 +510,4 @@ Next topic: @ref collision_filter_file_semantics
- `SetCanCollide(tree1->bodies[i], tree1->bodies[j]);`
`//` Exception to previous rule, such that body `i` in tree 1 can
collide with body `j` in tree 2.
**/
*/
36 changes: 18 additions & 18 deletions attic/multibody/collision/model.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ namespace collision {
typedef std::pair<ElementId, ElementId> ElementIdPair;

/** Model is an abstract base class of a collision model. Child classes of Model
implement the actual collision detection logic. **/
implement the actual collision detection logic. */
class Model {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Model)
Expand All @@ -40,15 +40,15 @@ class Model {
@return A pointer to the added element.
@throws std::runtime_error if there was a problem (e.g., duplicate element
id, error configuring collision model, etc.) **/
id, error configuring collision model, etc.) */
Element* AddElement(std::unique_ptr<Element> element);

/** Removes a collision element from this model.
@param id The id of the element that will be removed.
@return True if the element is successfully removed, false if the model does
not contain an element with the given id. **/
not contain an element with the given id. */
bool RemoveElement(ElementId id);

/** Gets a read-only pointer to a collision element in this model.
Expand All @@ -57,7 +57,7 @@ class Model {
@return A read-only pointer to the collision element corresponding to
the given `id` or `nullptr` if no such collision element is present in the
model. **/
model. */
virtual const Element* FindElement(ElementId id) const;

/** Gets a pointer to a mutable collision element in this model.
Expand All @@ -67,7 +67,7 @@ class Model {
@returns A pointer to a mutable collision element corresponding to
the given `id` or `nullptr` if no such collision element is present in the
model. **/
model. */
virtual Element* FindMutableElement(ElementId id);

void GetTerrainContactPoints(ElementId id0, Eigen::Matrix3Xd* terrain_points);
Expand All @@ -81,7 +81,7 @@ class Model {
virtual void NotifyFilterCriteriaChanged(ElementId) {}

/** Updates the collision model. This method is typically called after changes
are made to its collision elements. **/
are made to its collision elements. */
virtual void UpdateModel() = 0;

/** Updates the stored transformation from a collision element's canonical
Expand All @@ -94,7 +94,7 @@ class Model {
@param X_WL The new value for the local-to-world transform. It reflects the
current world pose of the parent body in a given context.
@return Whether the update was successful. **/
@return Whether the update was successful. */
virtual bool UpdateElementWorldTransform(
ElementId id, const Eigen::Isometry3d& X_WL);

Expand All @@ -110,7 +110,7 @@ class Model {
@param[out] closest_points A reference to a vector of PointPair objects that
contains the closest point information after this method is called
@return Whether this method successfully ran. **/
@return Whether this method successfully ran. */
virtual bool ClosestPointsAllToAll(
const std::vector<ElementId>& ids_to_check, bool use_margins,
std::vector<PointPair<double>>* closest_points) = 0;
Expand All @@ -124,7 +124,7 @@ class Model {
@param[out] closest_points A reference to a vector of PointPair objects
that contains the closest point information after this method is called.
@returns Whether this method successfully ran. **/
@returns Whether this method successfully ran. */
virtual bool ComputeMaximumDepthCollisionPoints(
bool use_margins, std::vector<PointPair<double>>* closest_points) = 0;

Expand All @@ -141,7 +141,7 @@ class Model {
that contains the closest point information after this method is
called
@return Whether this method successfully ran. **/
@return Whether this method successfully ran. */
virtual bool ClosestPointsPairwise(
const std::vector<ElementIdPair>& id_pairs, bool use_margins,
std::vector<PointPair<double>>* closest_points) = 0;
Expand All @@ -159,7 +159,7 @@ class Model {
Clearing cached results allows the collision model to perform a fresh
computation without any coupling with previous history.
@see drake/multibody/collision/test/model_test.cc. **/
@see drake/multibody/collision/test/model_test.cc. */
virtual void ClearCachedResults(bool use_margins) = 0;

/** Computes the closest distance from each point to any surface in the
Expand All @@ -172,7 +172,7 @@ class Model {
model with collision margins.
@param[out] closest_points A vector of `N` PointPair instances such that the
i'th instance reports the query result for the i'th input point. **/
i'th instance reports the query result for the i'th input point. */
virtual void CollisionDetectFromPoints(
const Eigen::Matrix3Xd& points, bool use_margins,
std::vector<PointPair<double>>* closest_points) = 0;
Expand All @@ -198,7 +198,7 @@ class Model {
collide with the model within the specified threshold.
@see drake/matlab/systems/plants/test/collidingPointsTest.m for a MATLAB
%test. **/
%test. */
virtual std::vector<size_t> CollidingPoints(
const std::vector<Eigen::Vector3d>& input_points,
double collision_threshold) = 0;
Expand All @@ -219,7 +219,7 @@ class Model {
@param collision_threshold The radius of a control sphere around each point
used to check for collisions with the model.
@return Whether any of the points positively checks for collision. **/
@return Whether any of the points positively checks for collision. */
virtual bool CollidingPointsCheckOnly(
const std::vector<Eigen::Vector3d>& input_points,
double collision_threshold) = 0;
Expand All @@ -239,7 +239,7 @@ class Model {
@param[out] distance The distance to the first collision, or -1 if no
collision occurs.
@return Whether this method successfully ran. **/
@return Whether this method successfully ran. */
virtual bool CollisionRaycast(const Eigen::Matrix3Xd& origin,
const Eigen::Matrix3Xd& ray_endpoint,
bool use_margins, Eigen::VectorXd* distances,
Expand All @@ -254,7 +254,7 @@ class Model {
@param transform_body_to_joint The transform from the collision element's
link's frame to the joint's coordinate frame.
@return Whether the collision element was successfully updated. **/
@return Whether the collision element was successfully updated. */
virtual bool TransformCollisionFrame(
const drake::multibody::collision::ElementId& eid,
const Eigen::Isometry3d& transform_body_to_joint);
Expand All @@ -268,15 +268,15 @@ class Model {
@param element The element that has been added.
@throws std::runtime_error If there was a problem processing the element. **/
@throws std::runtime_error If there was a problem processing the element. */
virtual void DoAddElement(const Element& element);

/** Allows sub-classes to do additional processing when elements are
removed from the collision model. This is called by Model::RemoveElement()
prior to removing id from elements. The derived class should not do this
removal.
@param id The id of the element that will be removed. **/
@param id The id of the element that will be removed. */
virtual void DoRemoveElement(ElementId id);

// Protected member variables are forbidden by the style guide.
Expand Down
20 changes: 10 additions & 10 deletions attic/multibody/collision/point_pair.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ namespace drake {
namespace multibody {
namespace collision {

/** Structure containing the results of a collision query. **/
/** Structure containing the results of a collision query. */
template <typename T>
struct PointPair {
PointPair() {}
Expand All @@ -23,35 +23,35 @@ struct PointPair {
normal(normal_in),
distance(distance_in) {}

/** Scalar-converting copy constructor. **/
/** Scalar-converting copy constructor. */
template <typename U>
explicit PointPair(const PointPair<U>& other)
: PointPair<T>(other.elementA, other.elementB, other.ptA, other.ptB,
other.normal, other.distance) {}

/** Element A in the pair participating in the collision. **/
/** Element A in the pair participating in the collision. */
const Element* elementA{nullptr};

/** Element B in the pair participating in the collision. **/
/** Element B in the pair participating in the collision. */
const Element* elementB{nullptr};

/** Id of element A participating in the collision. **/
/** Id of element A participating in the collision. */
ElementId idA{0};

/** Id of element B participating in the collision. **/
/** Id of element B participating in the collision. */
ElementId idB{0};

/** Collision point on the surface of body A. **/
/** Collision point on the surface of body A. */
Vector3<T> ptA;

/** Collision point on the surface of body B. **/
/** Collision point on the surface of body B. */
Vector3<T> ptB;

/** Outwards normal on body B. On body A it points in the opposite
direction. **/
direction. */
Vector3<T> normal;

/** Distance between the point on body A and the point on body B. **/
/** Distance between the point on body A and the point on body B. */
T distance{};
};

Expand Down
4 changes: 2 additions & 2 deletions attic/multibody/rigid_body_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,15 +27,15 @@ extern Eigen::Vector2d default_tspan;
class RigidBodyConstraint {
public:
/* In each category, constraint classes share the same function interface,
* this value needs to be in consistent with that in MATLAB*/
* this value needs to be in consistent with that in MATLAB. */
static const int SingleTimeKinematicConstraintCategory = -1;
static const int MultipleTimeKinematicConstraintCategory = -2;
static const int QuasiStaticConstraintCategory = -3;
static const int PostureConstraintCategory = -4;
static const int MultipleTimeLinearPostureConstraintCategory = -5;
static const int SingleTimeLinearPostureConstraintCategory = -6;
/* Each non-abstrac RigidBodyConstraint class has a unique type. Make sure
* this value stays in consistent with the value in MATLAB*/
* this value stays in consistent with the value in MATLAB. */
static const int QuasiStaticConstraintType = 1;
static const int PostureConstraintType = 2;
static const int SingleTimeLinearPostureConstraintType = 3;
Expand Down
2 changes: 1 addition & 1 deletion attic/multibody/rigid_body_plant/compliant_material.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
namespace drake {
namespace systems {

// TODO(SeanCurtis-TRI): Investigate templatizing this on scalar.
/** The set of per-object compliant material parameters with one material
applied to each collision object. The material parameters include:
- Young's modulus with units of pascals (i.e.,N/m²). This is a measure of the
Expand Down Expand Up @@ -50,7 +51,6 @@ namespace systems {
```
See @ref drake_contacts for semantics of these properties for dynamics. */
// TODO(SeanCurtis-TRI): Investigate templatizing this on scalar.
class CompliantMaterial {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(CompliantMaterial)
Expand Down
2 changes: 1 addition & 1 deletion attic/multibody/rigid_body_tree.h
Original file line number Diff line number Diff line change
Expand Up @@ -1265,7 +1265,7 @@ class RigidBodyTree {
@throws std::runtime_error based on the criteria of DiscardZeroGradient()
only if @p throws_if_missing_gradient is true.
**/
*/
template <typename U>
std::vector<drake::multibody::collision::PointPair<U>>
ComputeMaximumDepthCollisionPoints(const KinematicsCache<U>& cache,
Expand Down
15 changes: 8 additions & 7 deletions attic/multibody/shapes/geometry.h
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,7 @@ class Mesh : public Geometry {

/** Constructs a representation of a mesh to be loaded from
@p resolved_filename. @p uri provides a unique identifier used to interact
with BotVisualizer. **/
with BotVisualizer. */
Mesh(const std::string& uri, const std::string& resolved_filename);
virtual ~Mesh() {}
Mesh* clone() const override;
Expand Down Expand Up @@ -239,11 +239,12 @@ class Mesh : public Geometry {
a set of *equivalent* triangles. It places certain requirements on the
mesh for the triangulation to be valid. If these requirements are not met,
an exception is thrown. These requirements are:
1. Non-triangular faces cannot contain a sequence of co-linear vertices.
2. Non-triangular faces must be close to planar; the decomposed triangles
normals can deviate by no more than 30 degrees from their edge-adjacent
neighbors.
3. Decomposed triangles must have an area larger than 10⁻¹⁰ m².
1. Non-triangular faces cannot contain a sequence of co-linear vertices.
2. Non-triangular faces must be close to planar; the decomposed triangles
normals can deviate by no more than 30 degrees from their edge-adjacent
neighbors.
3. Decomposed triangles must have an area larger than 10⁻¹⁰ m².
@note The triangulation method is simple. Even if these requirements are met,
triangulation might fail.
Expand All @@ -256,7 +257,7 @@ class Mesh : public Geometry {
On output, `vertices.size()` corresponds to the number of vertices in the mesh
while `triangles.size()` corresponds to the number of triangles in the mesh.
**/
*/
void LoadObjFile(
PointsVector* vertices, TrianglesVector* triangles,
TriangulatePolicy triangulate = TriangulatePolicy::kFailOnNonTri) const;
Expand Down
5 changes: 4 additions & 1 deletion automotive/curve2.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,8 +72,11 @@ class Curve2 {
/// The @p position_dot derivative, when evaluated exactly at a waypoint,
/// will be congruent with the direction of one of the (max two) segments
/// that neighbor the waypoint. (At the first and last waypoints, there
/// is only one neighboring segment.) TODO(jwnimmer-tri) This will no
/// is only one neighboring segment.)
/// @cond
/// TODO(jwnimmer-tri) This will no
/// longer be true once this class uses a spline.
/// @endcond
PositionResult GetPosition(const T& path_distance) const {
using std::max;

Expand Down
9 changes: 5 additions & 4 deletions automotive/maliput/api/lane_data.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,8 @@ struct LaneEnd {
/// text-logging. It is not intended for serialization.
std::ostream& operator<<(std::ostream& out, const LaneEnd::Which& which_end);

/// A 3-dimensional rotation.
// TODO(Mitiguy) Rename/move this class to drake/math alongside RotationMatrix.
/// A 3-dimensional rotation.
class Rotation {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(Rotation)
Expand Down Expand Up @@ -204,9 +204,10 @@ auto operator!=(const GeoPositionT<T>& lhs, const GeoPositionT<T>& rhs) {
}

/// A 3-dimensional position in a `Lane`-frame, consisting of three components:
/// * s is longitudinal position, as arc-length along a Lane's reference line.
/// * r is lateral position, perpendicular to the reference line at s.
/// * h is height above the road surface.
///
/// * s is longitudinal position, as arc-length along a Lane's reference line.
/// * r is lateral position, perpendicular to the reference line at s.
/// * h is height above the road surface.
///
/// Instantiated templates for the following kinds of T's are provided:
///
Expand Down
Loading

0 comments on commit a157119

Please sign in to comment.