Skip to content

Commit

Permalink
Miscellaneous documentation fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
Jamie Snape committed Oct 18, 2018
1 parent cdb7eb6 commit bd8a8dc
Show file tree
Hide file tree
Showing 31 changed files with 64 additions and 82 deletions.
8 changes: 6 additions & 2 deletions attic/multibody/kinematics_cache.h
Original file line number Diff line number Diff line change
Expand Up @@ -86,8 +86,10 @@ class KinematicsCache {
bool inertias_cached;

public:
/// Preallocated scratch pad variables. These variables are used to prevent
/// dynamic memory allocation during runtime.
/// @name Preallocated scratch pad variables.
/// These variables are used to prevent dynamic memory allocation during
/// runtime.
/// @{

/// Preallocated variables used in GeometricJacobian. Preallocated as the size
/// of the path is dependent on the base body/frame and end effector
Expand All @@ -112,6 +114,8 @@ class KinematicsCache {
mutable DataInCalcFrameSpatialVelocityJacobianInWorldFrame
spatial_velocity_jacobian_temp;

/// @}

/// Constructor for a KinematicsCache given the number of positions and
/// velocities per body in the vectors @p num_joint_positions and
/// @p num_joint_velocities, respectively.
Expand Down
8 changes: 4 additions & 4 deletions attic/multibody/rigid_body_plant/kinematics_results.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,17 +69,17 @@ class KinematicsResults {
TwistVector<T> get_twist_in_world_aligned_body_frame(
const RigidBody<T>& body) const;

// TODO(tkoolen) should pass in joint instead of body, but that's currently
// not convenient.
/// Returns the joint position vector associated with the joint between
/// @p body and @p body's parent.
/// TODO(tkoolen) should pass in joint instead of body, but that's currently
/// not convenient.
Eigen::VectorBlock<const VectorX<T>> get_joint_position(
const RigidBody<T>& body) const;

// TODO(tkoolen): should pass in joint instead of body, but that's currently
// not convenient.
/// Returns the joint velocity vector associated with the joint between
/// @p body and @p body's parent.
/// TODO(tkoolen) should pass in joint instead of body, but that's currently
/// not convenient.
Eigen::VectorBlock<const VectorX<T>> get_joint_velocity(
const RigidBody<T>& body) const;

Expand Down
3 changes: 2 additions & 1 deletion automotive/curve2.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@ namespace automotive {
///
/// They are already available to link against in the containing library.
///
/// TODO(jwnimmer-tri) We will soon trace the path using a spline, but
/// <!-- TODO(jwnimmer-tri) -->
/// @note We will soon trace the path using a spline, but
/// for now it's easiest to just interpolate straight segments, as a
/// starting point. Callers should not yet rely on <em>how</em> we
/// are traversing between the waypoints.
Expand Down
5 changes: 2 additions & 3 deletions automotive/maliput/api/lane.h
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,8 @@ class Lane {
return DoToGeoPosition(lane_pos);
}

// TODO(jadecastro): Apply this implementation in all the subclasses of
// `api::Lane`.
/// Generalization of ToGeoPosition to arbitrary scalar types, where the
/// structures `LanePositionT<T>` and `GeoPositionT<T>` are used in place of
/// `LanePosition` and `GeoPosition`, respectively.
Expand All @@ -123,9 +125,6 @@ class Lane {
///
/// @note This is an experimental API that is not necessarily implemented in
/// all back-end implementations.

// TODO(jadecastro): Apply this implementation in all the subclasses of
// `api::Lane`.
template <typename T>
GeoPositionT<T> ToGeoPositionT(const LanePositionT<T>& lane_pos) const;

Expand Down
1 change: 0 additions & 1 deletion automotive/maliput/multilane/cubic_polynomial.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@ class CubicPolynomial {
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(CubicPolynomial)

/// Default constructor, all zero coefficients.

CubicPolynomial() : CubicPolynomial(0., 0., 0., 0.) {}

/// Constructs a cubic polynomial given all four coefficients.
Expand Down
9 changes: 4 additions & 5 deletions common/drake_bool_deprecated.h
Original file line number Diff line number Diff line change
Expand Up @@ -189,13 +189,12 @@ operator!(const Bool<T>& b) {
return Bool<T>{!b.value()};
}

// Note that we need to have `#include "drake/common/autodiff.h"` atop this
// file because, in case of T = AutoDiffXd, this template function calls
// another template function defined in common/autodiff.h. See
// https://clang.llvm.org/compatibility.html#dep_lookup for more information.
/// Allows users to use `if_then_else` with a conditional of `Bool<T>` type in
/// addition to `Bool<T>::value_type`.
///
/// Note that we need to have `#include "drake/common/autodiff.h"` atop this
/// file because, in case of T = AutoDiffXd, this template function calls
/// another template function defined in common/autodiff.h. See
/// https://clang.llvm.org/compatibility.html#dep_lookup for more information.
template <typename T>
DRAKE_DEPRECATED("Bool<T> is deprecated")
T if_then_else(const Bool<T>& b, const T& v_then, const T& v_else) {
Expand Down
2 changes: 1 addition & 1 deletion common/proto/call_matlab.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ namespace common {

/// Serialize our favorite data types into the matlab_array structure.
/// To support a calling call_matlab for a new data type, simply implement
/// another one of these methods.
/// another one of these methods.

class MatlabRemoteVariable;

Expand Down
3 changes: 1 addition & 2 deletions common/reset_after_move.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

namespace drake {

// TODO(sherm1) Upgrade this to match reset_on_copy (e.g. noexcept).
/// Type wrapper that performs value-initialization on the wrapped type, and
/// guarantees that when moving from this type that the donor object is reset
/// to its value-initialized value.
Expand Down Expand Up @@ -44,8 +45,6 @@ namespace drake {
/// and MoveAssignable and must not throw exceptions during construction or
/// assignment.
/// @see reset_on_copy

// TODO(sherm1) Upgrade this to match reset_on_copy (e.g. noexcept).
template <typename T>
class reset_after_move {
public:
Expand Down
19 changes: 9 additions & 10 deletions common/reset_on_copy.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,15 @@

namespace drake {

// NOTE(sherm1) to future implementers: if you decide to extend this adapter for
// use with class types, be sure to think carefully about the semantics of copy
// and move and how to explain that to users. Be aware that for class types T,
// the implementation of `T{}` (the default constructor, which may have been
// user-supplied) won't necessarily reset T's members to zero, nor even
// necessarily value-initialize T's members. Also, the "noexcept" reasoning
// below is more than we need with the std::is_scalar<T> restriction, but is
// strictly necessary for class types if you want std::vector to choose move
// construction (content-preserving) over copy construction (resetting).
/// Type wrapper that performs value-initialization on copy construction or
/// assignment.
///
Expand Down Expand Up @@ -67,16 +76,6 @@ namespace drake {
///
/// @tparam T must satisfy `std::is_scalar<T>`.
/// @see reset_after_move

// NOTE(sherm1) to future implementers: if you decide to extend this adapter for
// use with class types, be sure to think carefully about the semantics of copy
// and move and how to explain that to users. Be aware that for class types T,
// the implementation of `T{}` (the default constructor, which may have been
// user-supplied) won't necessarily reset T's members to zero, nor even
// necessarily value-initialize T's members. Also, the "noexcept" reasoning
// below is more than we need with the std::is_scalar<T> restriction, but is
// strictly necessary for class types if you want std::vector to choose move
// construction (content-preserving) over copy construction (resetting).
template <typename T>
class reset_on_copy {
public:
Expand Down
1 change: 0 additions & 1 deletion common/symbolic_variables.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@ namespace symbolic {
* checking functions (Variables::IsSubsetOf, Variables::IsSupersetOf,
* Variables::IsStrictSubsetOf, Variables::IsStrictSupersetOf).
*/

class Variables {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(Variables)
Expand Down
3 changes: 2 additions & 1 deletion common/trig_poly.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,8 @@
*
* NOTE: Certain analyses may not succeed when individual Monomials contain
* both x and sin(x) or cos(x) terms. This restriction is not currently
* enforced programmatically; TODO(ggould-tri) fix this in the future.
* enforced programmatically.
* <!-- TODO(ggould-tri): Fix this in the future. -->
*/
template <typename _CoefficientType = double>
class TrigPoly final {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@ used to prevent an algebraic loop between the plant and the plan interpolator.
│ └────────────────────────────────────────────────────────────┘ │
└────────────────────────────────────────────────────────────────┘
*/

class MonolithicPickAndPlaceSystem : public systems::Diagram<double> {
public:
MonolithicPickAndPlaceSystem(
Expand Down
1 change: 0 additions & 1 deletion examples/kuka_iiwa_arm/dev/pick_and_place/lcm_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,6 @@ The block diagram for a system with a single arm is shown below:
│ │
└───────────────────────────────────────────────┘
*/

class LcmPlant : public systems::Diagram<double> {
public:
LcmPlant(
Expand Down
6 changes: 3 additions & 3 deletions geometry/dev/query_object.h
Original file line number Diff line number Diff line change
Expand Up @@ -169,6 +169,9 @@ class QueryObject {

//@{

// TODO(hongkai.dai): add a distance bound as an optional input, such that the
// function doesn't return the pairs whose signed distance is larger than the
// distance bound.
/**
* Computes the signed distance together with the nearest points across all
* pairs of geometries in the world. Reports both the separating geometries
Expand All @@ -178,9 +181,6 @@ class QueryObject {
* 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
* function doesn't return the pairs whose signed distance is larger than the
* distance bound.
*/
std::vector<SignedDistancePair<double>>
ComputeSignedDistancePairwiseClosestPoints() const;
Expand Down
3 changes: 2 additions & 1 deletion geometry/frame_kinematics_vector.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,8 @@ struct KinematicsValueInitializer<Isometry3<S>> {
is consumed by SceneGraph.
<!--
TODO: The FrameVelocityVector and FrameAccelerationVector are still to come.
TODO(SeanCurtis-TRI): The FrameVelocityVector and FrameAccelerationVector
are still to come.
-->
The usage of this method would be in the allocation and calculation
Expand Down
6 changes: 3 additions & 3 deletions geometry/query_object.h
Original file line number Diff line number Diff line change
Expand Up @@ -150,6 +150,9 @@ class QueryObject {

//@{

// TODO(hongkai.dai): add a distance bound as an optional input, such that the
// function doesn't return the pairs whose signed distance is larger than the
// distance bound.
/**
* Computes the signed distance together with the nearest points across all
* pairs of geometries in the world. Reports both the separating geometries
Expand All @@ -159,9 +162,6 @@ class QueryObject {
* 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
* function doesn't return the pairs whose signed distance is larger than the
* distance bound.
*/
std::vector<SignedDistancePair<double>>
ComputeSignedDistancePairwiseClosestPoints() const;
Expand Down
15 changes: 7 additions & 8 deletions manipulation/scene_generation/random_clutter_generator.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,19 +24,18 @@ namespace scene_generation {
*
* NOTES:
* 1. Current version only ensures bounded clutter for the case of all model
* instances on the tree containing the QuaternionFloatingJoint.
* instances on the tree containing the QuaternionFloatingJoint.
* 2. The current version has only been tested with SNOPT.
* 3. The solvability of the problem is strongly dependent on the dimensions
* of the clutter bounding volume as specified in clutter_size and the number
* and geometry of the clutter model instances that are to be dealt with. There
* is no explicit time-out on the execution and the GenerateFloatingClutter
* will keep attempting to find a solution, if any.
* of the clutter bounding volume as specified in clutter_size and the
* number and geometry of the clutter model instances that are to be dealt
* with. There is no explicit time-out on the execution and the
* GenerateFloatingClutter will keep attempting to find a solution, if any.
* 4. There are no explicit guarantees on the solvability.
* 5. The underlying IK computations utilize the bullet collision library and
* as such only process the convex-hull of the geometry. The resulting IK
* solution will be subject to this simplification.
* as such only process the convex-hull of the geometry. The resulting IK
* solution will be subject to this simplification.
*/

class RandomClutterGenerator {
public:
/**
Expand Down
1 change: 0 additions & 1 deletion math/rigid_transform.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ namespace math {
/// @authors Drake team (see https://drake.mit.edu/credits).
///
/// @tparam T The underlying scalar type. Must be a valid Eigen scalar.

template <typename T>
class RigidTransform {
public:
Expand Down
4 changes: 2 additions & 2 deletions multibody/inverse_kinematics/inverse_kinematics.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,12 @@

namespace drake {
namespace multibody {
// TODO(hongkai.dai) The bounds on the generalized positions (i.e., joint
// limits) should be imposed automatically.
/**
* Solves an inverse kinematics (IK) problem on a MultibodyPlant, to find the
* postures of the robot satisfying certain constraints.
* The decision variables include the generalized position of the robot.
* TODO(hongkai.dai) The bounds on the generalized positions (i.e., joint
* limits) should be imposed automatially.
*/
class InverseKinematics {
public:
Expand Down
1 change: 0 additions & 1 deletion solvers/indeterminate.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@ using VectorIndeterminate = MatrixIndeterminate<rows, 1>;
* Eigen::Matrix<symbolic::Variable, Eigen::Dynamic, Eigen::Dynamic>.
* @see MatrixIndeterminate<int, int>
*/

using MatrixXIndeterminate =
MatrixIndeterminate<Eigen::Dynamic, Eigen::Dynamic>;

Expand Down
2 changes: 0 additions & 2 deletions solvers/mathematical_program.h
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,6 @@ namespace solvers {
* (note that some have free licenses for academics).
* @}
*/

class MathematicalProgram;

enum ProgramAttributes {
Expand Down Expand Up @@ -672,7 +671,6 @@ class MathematicalProgram {
* The name of the indeterminates is only used for the user in order to ease
* readability.
*/

template <int rows, int cols>
MatrixIndeterminate<rows, cols> NewIndeterminates(
const std::string& name = "X") {
Expand Down
4 changes: 2 additions & 2 deletions solvers/non_convex_optimization_util.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@

namespace drake {
namespace solvers {
// TODO(hongkai.dai): templatize this function, to avoid dynamic memory
// allocation.
/**
* For a non-convex homogeneous quadratic form xᵀQx, where Q is not necessarily
* a positive semidefinite matrix, we decompose it as a difference between two
Expand Down Expand Up @@ -37,8 +39,6 @@ namespace solvers {
* @param Q A square matrix.
* @throws std::runtime_error if Q is not square.
* @return The optimal decomposition (Q₁, Q₂)
* TODO(hongkai.dai): templatize this function, to avoid dynamic memory
* allocation.
*/
std::pair<Eigen::MatrixXd, Eigen::MatrixXd> DecomposeNonConvexQuadraticForm(
const Eigen::Ref<const Eigen::MatrixXd>& Q);
Expand Down
14 changes: 6 additions & 8 deletions systems/analysis/integrator_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -1318,13 +1318,12 @@ class IntegratorBase {
*/
virtual void DoReset() {}

// TODO(hidmic): Make pure virtual and override on each subclass, as
// the 'optimal' dense output scheme is only known by the specific
// integration scheme being implemented.
/**
* Derived classes can override this method to provide a continuous
* extension of their own when StartDenseIntegration() is called.
*
* TODO(hidmic): Make pure virtual and override on each subclass, as
* the 'optimal' dense output scheme is only known by the specific
* integration scheme being implemented.
*/
virtual
std::unique_ptr<StepwiseDenseOutput<T>> DoStartDenseIntegration() {
Expand Down Expand Up @@ -1362,6 +1361,9 @@ class IntegratorBase {
*/
virtual bool DoStep(const T& dt) = 0;

// TODO(hidmic): Make pure virtual and override on each subclass, as
// the 'optimal' dense output scheme is only known by the specific
// integration scheme being implemented.
/**
* Derived classes may implement this method to (1) integrate the continuous
* portion of this system forward by a single step of size @p dt, (2) set the
Expand All @@ -1373,10 +1375,6 @@ class IntegratorBase {
* unable to take a single step of size @p dt or to advance
* its dense output an equal step.
* @sa DoStep()
*
* TODO(hidmic): Make pure virtual and override on each subclass, as
* the 'optimal' dense output scheme is only known by the specific
* integration scheme being implemented.
*/
virtual bool DoDenseStep(const T& dt) {
const ContinuousState<T>& state = context_->get_continuous_state();
Expand Down
5 changes: 2 additions & 3 deletions systems/controllers/linear_model_predictive_controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@ class LinearModelPredictiveController : public LeafSystem<T> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(LinearModelPredictiveController)

// TODO(jadecastro) Implement a version that regulates to an arbitrary
// trajectory.
/// Constructor for an unconstrained MPC formulation with linearization
/// occurring about the provided base_context. Since this formulation is
/// devoid of any externally-imposed input/state constraints, the controller
Expand All @@ -59,9 +61,6 @@ class LinearModelPredictiveController : public LeafSystem<T> {
/// @pre base_context must have discrete states set as appropriate for the
/// given @p model. The input must also be initialized via
/// `base_context->FixInputPort(0, u0)`, or otherwise initialized via Diagram.

// TODO(jadecastro) Implement a version that regulates to an arbitrary
// trajectory.
LinearModelPredictiveController(
std::unique_ptr<systems::System<double>> model,
std::unique_ptr<systems::Context<double>> base_context,
Expand Down
Loading

0 comments on commit bd8a8dc

Please sign in to comment.