Skip to content

Commit

Permalink
Merge pull request RobotLocomotion#9678 from jamiesnape/more-document…
Browse files Browse the repository at this point in the history
…ation-fixes

More documentation and markup fixes
  • Loading branch information
jamiesnape authored Oct 16, 2018
2 parents 8f5ab0c + 7188838 commit 1ed27f0
Show file tree
Hide file tree
Showing 57 changed files with 139 additions and 91 deletions.
5 changes: 3 additions & 2 deletions attic/multibody/rigid_body_plant/contact_detail.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,9 @@ namespace systems {
@tparam T The scalar type. It must be a valid Eigen scalar.
Instantiated templates for the following ScalarTypes are provided:
- double
- AutoDiffXd
- double
- AutoDiffXd
*/
template <typename T>
class ContactDetail {
Expand Down
1 change: 1 addition & 0 deletions attic/multibody/rigid_body_plant/contact_force.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ namespace systems {
@tparam T The scalar type. Must be a valid Eigen scalar.
Instantiated templates for the following ScalarTypes are provided:
- double
- AutoDiffXd
*/
Expand Down
1 change: 1 addition & 0 deletions attic/multibody/rigid_body_plant/contact_info.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ namespace systems {
@tparam T The scalar type. It must be a valid Eigen scalar.
Instantiated templates for the following ScalarTypes are provided:
- double
- AutoDiffXd
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,12 +26,15 @@ namespace systems {
Center of Pressure (more precisely center of normal forces for planar contact)
==============================================================================
For point `P` to be a center of pressure (as returned by this class):
- The normal components of all forces must lie in the same direction, `n`.
- The points, where each force is applied, must lie on one plane, `F`.
- Plane `F` must be perpendicular to `n`.
If these conditions are met, `P` will be the center of pressure and lie on
plane `F`, and the minimum moment due to the normal forces will be zero.
Note: this class does not rely on a center of pressure *existing*.
@note This class does not rely on a center of pressure *existing*.
Usage
=====
Expand All @@ -41,10 +44,12 @@ namespace systems {
is processed and a contact force is computed, the details of the contact force
are provided to the calculator (via calls to AddForce).
Currently, the contact force is defined by four values (see ContactForce):
- position of the force's point of application from a common origin O,
- normal component of the contact force (i.e., in the *normal* direction),
- tangential component of the contact force (e.g., friction force), and
- Optional torque term (e.g., torsional friction).
All input vectors must be expressed in a common frame and the position vector
must be measured from that frame's origin.
Expand Down Expand Up @@ -134,8 +139,9 @@ namespace systems {
@tparam T The scalar type. Must be a valid Eigen scalar.
Instantiated templates for the following ScalarTypes are provided:
- double
- AutoDiffXd
- double
- AutoDiffXd
*/
template <typename T>
class ContactResultantForceCalculator {
Expand Down
5 changes: 3 additions & 2 deletions attic/multibody/rigid_body_plant/contact_results.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,9 @@ class RigidBodyPlant;
@tparam T The scalar type. It must be a valid Eigen scalar.
Instantiated templates for the following ScalarTypes are provided:
- double
- AutoDiffXd
- double
- AutoDiffXd
*/
template <typename T>
class ContactResults {
Expand Down
5 changes: 3 additions & 2 deletions attic/multibody/rigid_body_plant/point_contact_detail.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,9 @@ namespace systems {
@tparam T The scalar type. It must be a valid Eigen scalar.
Instantiated templates for the following ScalarTypes are provided:
- double
- AutoDiffXd
- double
- AutoDiffXd
*/
template <typename T>
class PointContactDetail : public ContactDetail<T> {
Expand Down
1 change: 1 addition & 0 deletions attic/multibody/rigid_body_plant/rigid_body_plant_bridge.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,7 @@ namespace systems {
@tparam T The scalar type. Must be a valid Eigen scalar.
Instantiated templates for the following kinds of T's are provided:
- double
- AutoDiffXd
Expand Down
18 changes: 9 additions & 9 deletions attic/multibody/rigid_body_tree.h
Original file line number Diff line number Diff line change
Expand Up @@ -380,7 +380,7 @@ class RigidBodyTree {
/// Computes the pose `X_WB` of @p body's frame B in the world frame W.
/// @param cache Reference to the KinematicsCache.
/// @param body Reference to the RigidBody.
/// @retval `X_WB`
/// @retval X_WB
drake::Isometry3<T> CalcBodyPoseInWorldFrame(
const KinematicsCache<T>& cache, const RigidBody<T>& body) const {
return CalcFramePoseInWorldFrame(
Expand All @@ -393,7 +393,7 @@ class RigidBodyTree {
/// RigidBodyTree.
/// @param cache Reference to the KinematicsCache.
/// @param frame_F Reference to the RigidBodyFrame.
/// @retval `X_WF`
/// @retval X_WF
drake::Isometry3<T> CalcFramePoseInWorldFrame(
const KinematicsCache<T>& cache, const RigidBodyFrame<T>& frame_F) const {
return CalcFramePoseInWorldFrame(cache, frame_F.get_rigid_body(),
Expand All @@ -405,7 +405,7 @@ class RigidBodyTree {
/// @param cache Reference to the KinematicsCache.
/// @param body Reference to the RigidBody.
/// @param X_BF The pose of frame F in body frame B.
/// @retval `X_WF`
/// @retval X_WF
drake::Isometry3<T> CalcFramePoseInWorldFrame(
const KinematicsCache<T>& cache, const RigidBody<T>& body,
const drake::Isometry3<T>& X_BF) const;
Expand All @@ -414,7 +414,7 @@ class RigidBodyTree {
/// expressed in the world frame W.
/// @param cache Reference to the KinematicsCache.
/// @param body Reference to the RigidBody.
/// @retval `V_WB`
/// @retval V_WB
drake::Vector6<T> CalcBodySpatialVelocityInWorldFrame(
const KinematicsCache<T>& cache, const RigidBody<T>& body) const;

Expand All @@ -424,7 +424,7 @@ class RigidBodyTree {
/// @p frame_F attaches to has to be owned by this RigidBodyTree.
/// @param cache Reference to the KinematicsCache.
/// @param frame_F Reference to the RigidBodyFrame.
/// @retval `V_WF`
/// @retval V_WF
drake::Vector6<T> CalcFrameSpatialVelocityInWorldFrame(
const KinematicsCache<T>& cache, const RigidBodyFrame<T>& frame_F) const {
return CalcFrameSpatialVelocityInWorldFrame(
Expand All @@ -437,7 +437,7 @@ class RigidBodyTree {
/// @param cache Reference to the KinematicsCache.
/// @param body Reference to the RigidBody.
/// @param X_BF The pose of frame F in body frame B.
/// @retval `V_WF`
/// @retval V_WF
drake::Vector6<T> CalcFrameSpatialVelocityInWorldFrame(
const KinematicsCache<T>& cache, const RigidBody<T>& body,
const drake::Isometry3<T>& X_BF) const;
Expand All @@ -452,7 +452,7 @@ class RigidBodyTree {
/// @param in_terms_of_qdot `true` for `J_WF` computed with respect to the
/// time derivative of the generalized position such that
/// `V_WF = J_WF * qdot`. `false` for `J_WF` computed with respect to `v`.
/// @retval `J_WF`
/// @retval J_WF
drake::Matrix6X<T> CalcFrameSpatialVelocityJacobianInWorldFrame(
const KinematicsCache<T>& cache, const RigidBody<T>& body,
const drake::Isometry3<T>& X_BF,
Expand Down Expand Up @@ -485,7 +485,7 @@ class RigidBodyTree {
/// @param in_terms_of_qdot `true` for `J_WF` computed with respect to the
/// time derivative of the generalized position such that
/// `V_WF = J_WF * qdot`. `false` for `J_WF` computed with respect to `v`.
/// @retval `J_WF`
/// @retval J_WF
drake::Matrix6X<T> CalcFrameSpatialVelocityJacobianInWorldFrame(
const KinematicsCache<T>& cache, const RigidBodyFrame<T>& frame_F,
bool in_terms_of_qdot = false) const {
Expand Down Expand Up @@ -524,7 +524,7 @@ class RigidBodyTree {
/// @param in_terms_of_qdot `true` for `J_WB` computed with respect to the
/// time derivative of the generalized position such that
/// `V_WB = J_WB * qdot`. `false` for `J_WB` computed with respect to `v`.
/// @retval `J_WB`
/// @retval J_WB
drake::Matrix6X<T> CalcBodySpatialVelocityJacobianInWorldFrame(
const KinematicsCache<T>& cache, const RigidBody<T>& body,
bool in_terms_of_qdot = false) const {
Expand Down
2 changes: 1 addition & 1 deletion automotive/maliput/dragway/lane.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class Segment;
the surface itself. The origin of the lane's frame is defined by the `o` along
the above-shown `s = 0` line.
Note: Each dragway lane has a teleportation feature at both ends: the
@note Each dragway lane has a teleportation feature at both ends: the
(default) ongoing lane for LaneEnd::kFinish is LaneEnd::kStart of the same
lane, and vice versa.
**/
Expand Down
21 changes: 12 additions & 9 deletions common/trajectories/piecewise_polynomial.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,11 @@ namespace trajectories {
* They cannot be divided because Polynomials are not closed
* under division.
*
* @tparam T is a scalar type. Explicit instantiations are provided for:
* - double
* @tparam T is a scalar type.
*
* Explicit instantiations are provided for:
*
* - double
*/
template <typename T>
class PiecewisePolynomial final : public PiecewiseTrajectory<T> {
Expand Down Expand Up @@ -98,7 +101,7 @@ class PiecewisePolynomial final : public PiecewiseTrajectory<T> {
* is used as a knot point, and
* knots.cols() == breaks.size().
*
* @overloads PiecewisePolynomial<T> ZeroOrderHold(breaks, knots)
* @overload PiecewisePolynomial<T> ZeroOrderHold(breaks, knots)
*/
static PiecewisePolynomial<T> ZeroOrderHold(
const Eigen::Ref<const Eigen::VectorXd>& breaks,
Expand All @@ -122,7 +125,7 @@ class PiecewisePolynomial final : public PiecewiseTrajectory<T> {
* is used as a knot point, and
* knots.cols() == breaks.size().
*
* @overloads PiecewisePolynomial<T> FirstOrderHold(breaks, knots)
* @overload PiecewisePolynomial<T> FirstOrderHold(breaks, knots)
*/
static PiecewisePolynomial<T> FirstOrderHold(
const Eigen::Ref<const Eigen::VectorXd>& breaks,
Expand Down Expand Up @@ -174,7 +177,7 @@ class PiecewisePolynomial final : public PiecewiseTrajectory<T> {
* where each column of knots is used as a knot point, and
* knots.cols() == breaks.size().
*
* @overloads PiecewisePolynomial<T> Pchip(breaks, knots,
* @overload PiecewisePolynomial<T> Pchip(breaks, knots,
* zero_end_point_derivatives)
*/
static PiecewisePolynomial<T> Pchip(
Expand Down Expand Up @@ -209,8 +212,8 @@ class PiecewisePolynomial final : public PiecewiseTrajectory<T> {
* where each column of knots is used as a knot point, and
* knots.cols() == breaks.size().
*
* @overloads PiecewisePolynomial<T> Cubic(breaks, knots, knots_dot_start,
* knots_dot_end)
* @overload PiecewisePolynomial<T> Cubic(breaks, knots, knots_dot_start,
* knots_dot_end)
*/
static PiecewisePolynomial<T> Cubic(
const Eigen::Ref<const Eigen::VectorXd>& breaks,
Expand Down Expand Up @@ -242,7 +245,7 @@ class PiecewisePolynomial final : public PiecewiseTrajectory<T> {
* and knots_dot are used as the knot point/derivative.
* knots.cols() == knots_dot.cols() == breaks.size().
*
* @overloads PiecewisePolynomial<T> Cubic(breaks, knots, knots_dot)
* @overload PiecewisePolynomial<T> Cubic(breaks, knots, knots_dot)
*/
static PiecewisePolynomial<T> Cubic(
const Eigen::Ref<const Eigen::VectorXd>& breaks,
Expand Down Expand Up @@ -290,7 +293,7 @@ class PiecewisePolynomial final : public PiecewiseTrajectory<T> {
* Eigen version of Cubic(breaks, knots) where each column of knots is used
* as a knot point and knots.cols() == breaks.size().
*
* @overloads PiecewisePolynomial<T> Cubic(breaks, knots)
* @overload PiecewisePolynomial<T> Cubic(breaks, knots)
*/
static PiecewisePolynomial<T> Cubic(
const Eigen::Ref<const Eigen::VectorXd>& breaks,
Expand Down
3 changes: 2 additions & 1 deletion common/trajectories/piecewise_quaternion.h
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,8 @@ class PiecewiseQuaternionSlerp final : public PiecewiseTrajectory<T> {

/**
* Getter for the internal quaternion knots.
* Note: the returned quaternions might be different from the ones used for
*
* @note The returned quaternions might be different from the ones used for
* construction because the internal representations are set to always be
* the "closest" w.r.t to the previous one.
*
Expand Down
2 changes: 1 addition & 1 deletion examples/compass_gait/compass_gait.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ namespace compass_gait {
/// These are helpful for outputting the floating-base model coordinate, e.g.
/// for visualization.
///
/// Note: This model only supports walking downhill on the ramp, because that
/// @note This model only supports walking downhill on the ramp, because that
/// restriction enables a clean / numerically robust implementation of the foot
/// collision witness function that avoids falls detections on the "foot
/// scuffing" collision.
Expand Down
3 changes: 2 additions & 1 deletion examples/rod2d/rod2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,7 @@ this class, please refer to https://drake.mit.edu/cxx_inl.html.
@tparam T The vector element type, which must be a valid Eigen scalar.
Instantiated templates for the following scalar types @p T are provided:
- double
They are already available to link against in the containing library.
Expand All @@ -142,7 +143,7 @@ States: planar position (state indices 0 and 1) and orientation (state
index 2), and planar linear velocity (state indices 3 and 4) and
scalar angular velocity (state index 5) in units of m, radians,
m/s, and rad/s, respectively. Orientation is measured counter-
clockwise with respect to the x-axis.
clockwise with respect to the x-axis.
Outputs: Output Port 0 corresponds to the state vector; Output Port 1
corresponds to a PoseVector giving the 3D pose of the rod in the world
Expand Down
4 changes: 3 additions & 1 deletion examples/scene_graph/dev/solar_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,9 @@ X_EL →├───┘ │ S │ X_MP → ├───┘
@tparam T The vector element type, which must be a valid Eigen scalar.
Instantiated templates for the following kinds of T's are provided:
- double */
- double
*/
template <typename T>
class SolarSystem : public systems::LeafSystem<T> {
public:
Expand Down
4 changes: 3 additions & 1 deletion examples/scene_graph/solar_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,9 @@ X_EL →├───┘ │ S │ X_MP → ├───┘
@tparam T The vector element type, which must be a valid Eigen scalar.
Instantiated templates for the following kinds of T's are provided:
- double */
- double
*/
template <typename T>
class SolarSystem : public systems::LeafSystem<T> {
public:
Expand Down
1 change: 1 addition & 0 deletions geometry/dev/geometry_context.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ namespace dev {
@tparam T The scalar type. Must be a valid Eigen scalar.
Instantiated templates for the following kinds of T's are provided:
- double
- AutoDiffXd
Expand Down
1 change: 1 addition & 0 deletions geometry/dev/geometry_state.h
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,7 @@ using FrameIdSet = std::unordered_set<FrameId>;
@tparam T The scalar type. Must be a valid Eigen scalar.
Instantiated templates for the following kinds of T's are provided:
- double
- AutoDiffXd
Expand Down
1 change: 1 addition & 0 deletions geometry/dev/proximity_engine.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ class GeometryStateCollisionFilterAttorney;
@tparam T The scalar type. Must be a valid Eigen scalar.
Instantiated templates for the following kinds of T's are provided:
- double
- AutoDiffXd
Expand Down
9 changes: 5 additions & 4 deletions geometry/dev/query_object.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ class SceneGraph;
@tparam T The scalar type. Must be a valid Eigen scalar.
Instantiated templates for the following kinds of T's are provided:
- double
- AutoDiffXd
Expand Down Expand Up @@ -143,8 +144,8 @@ class QueryObject {
If the objects do not overlap (i.e., A ⋂ B = ∅), φ > 0 and represents the
minimal distance between the two objects. More formally:
φ = min(|Aₚ - Bₚ|)
∀ Aₚ ∈ A and Bₚ ∈ B.
Note: the pair (Aₚ, Bₚ) is a "witness" of the distance.
∀ Aₚ ∈ A and Bₚ ∈ B.
@note The pair (Aₚ, Bₚ) is a "witness" of the distance.
The pair need not be unique (think of two parallel planes).
If the objects touch or overlap (i.e., A ⋂ B ≠ ∅), φ ≤ 0 and can be
Expand All @@ -162,7 +163,7 @@ class QueryObject {
This method is affected by collision filtering; geometry pairs that
have been filtered will not produce signed distance query results.
Note: the signed distance function is a continuous function with respect to
@note the signed distance function is a continuous function with respect to
the pose of the objects.
*/

Expand All @@ -174,7 +175,7 @@ class QueryObject {
* and penetrating geometries. Notice that this is an O(N²) operation, where N
* is the number of geometries remaining in the world after applying collision
* filter. We report the distance between dynamic objects, and between dynamic
* and anchored objects. We DO NOT report the distance between two anchored
* and anchored objects. We DO NOT report the distance between two anchored
* objects.
* @retval near_pairs The signed distance for all unfiltered geometry pairs.
* TODO(hongkai.dai): add a distance bound as an optional input, such that the
Expand Down
1 change: 1 addition & 0 deletions geometry/dev/scene_graph.h
Original file line number Diff line number Diff line change
Expand Up @@ -192,6 +192,7 @@ class QueryObject;
@tparam T The scalar type. Must be a valid Eigen scalar.
Instantiated templates for the following kinds of T's are provided:
- double
- AutoDiffXd
Expand Down
1 change: 1 addition & 0 deletions geometry/frame_kinematics_vector.h
Original file line number Diff line number Diff line change
Expand Up @@ -243,6 +243,7 @@ class FrameKinematicsVector {
@tparam T The scalar type. Must be a valid Eigen scalar.
Instantiated templates for the following kinds of T's are provided:
- double
- AutoDiffXd
Expand Down
Loading

0 comments on commit 1ed27f0

Please sign in to comment.