Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[WIP] Squash doxygen errors. #357

Merged
merged 13 commits into from
Mar 5, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

* Common

* Cleaned up doxygen errors: [#357](https://github.com/personalrobotics/aikido/pull/357)
* Fixed bug in StepSequence::getMaxSteps(): [#305](https://github.com/personalrobotics/aikido/pull/305)
* Fixed bug in StepSequence iterator: [#320](https://github.com/personalrobotics/aikido/pull/320)

Expand Down
1 change: 1 addition & 0 deletions include/aikido/common/PseudoInverse.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ namespace common {
/// Computes the Moore-Penrose pseudoinverse of a matrix.
///
/// \param mat input matrix
/// \param eps represents tolerance
/// \return pseudo-inverse of \c mat
Eigen::MatrixXd pseudoinverse(const Eigen::MatrixXd& mat, double eps = 1e-6);

Expand Down
2 changes: 0 additions & 2 deletions include/aikido/common/Spline.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,13 +91,11 @@ class SplineND

/// Sets the times of all knot points.
///
/// \param _index index of a knot point.
/// \param _t new times, must be monotone increasing
void setTimes(TimeVector&& _t);

/// Sets the times of all knot points.
///
/// \param _index index of a knot point.
/// \param _t new times, must be monotone increasing
void setTimes(const TimeVector& _t);

Expand Down
4 changes: 2 additions & 2 deletions include/aikido/common/string.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ namespace aikido {
namespace common {

/// Splits (tokenizes) a string into substrings that are divided by the given
/// delimiters.
/// delimiter tokens.
///
/// Example:
/// \code
Expand All @@ -23,7 +23,7 @@ namespace common {
/// \param[in] delimiters Delimiters where any character in this string is
/// considered a delimiter, i.e. the string is interpreted as a set of delimiter
/// characters, not as a single multi-character delimiter.
/// \return The splitted substrings. Space and tap (\t) are the default.
/// \return The splitted substrings. Space and tab are the default.
std::vector<std::string> split(
const std::string& string, const std::string& delimiters = " \t");

Expand Down
2 changes: 1 addition & 1 deletion include/aikido/constraint/RejectionSampleable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ class RejectionSampleable : public Sampleable
/// Constructor.
/// \param _stateSpace StateSpace in which both
/// sampleable and testable operate.
/// \prarm _sampleable Sampleable for robot configuration.
/// \param _sampleable Sampleable for robot configuration.
/// \param _testable Testable for each configuration.
/// \param _maxTrialPerSample Max number of trials to generate each sample.
/// If all _maxTrialPerSample fails to pass _testable,
Expand Down
2 changes: 2 additions & 0 deletions include/aikido/constraint/Satisfied.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@ class Satisfied : public constraint::Differentiable,
/// Returns \c true.
///
/// \param state a state in \c getStateSpace()
/// \param outcome object to populate with information about satisfiability
/// result.
bool isSatisfied(
const statespace::StateSpace::State* state,
TestableOutcome* outcome = nullptr) const override;
Expand Down
4 changes: 2 additions & 2 deletions include/aikido/constraint/TestableIntersection.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@ class TestableIntersection : public Testable
{
public:
/// Construct a TestableIntersection on a specific StateSpace.
/// \param statespace StateSpace this constraint operates in.
/// \param constraints Set of constraints.
/// \param _stateSpace StateSpace this constraint operates in.
/// \param _constraints Set of constraints.
TestableIntersection(
statespace::StateSpacePtr _stateSpace,
std::vector<TestablePtr> _constraints = std::vector<TestablePtr>());
Expand Down
12 changes: 6 additions & 6 deletions include/aikido/constraint/dart/CollisionFree.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,25 +60,25 @@ class CollisionFree : public Testable
std::unique_ptr<TestableOutcome> createOutcome() const override;

/// Checks collision between group1 and group2.
/// \param group1 First collision group.
/// \param group2 Second collision group.
/// \param _group1 First collision group.
/// \param _group2 Second collision group.
void addPairwiseCheck(
std::shared_ptr<::dart::collision::CollisionGroup> _group1,
std::shared_ptr<::dart::collision::CollisionGroup> _group2);

/// Remove collision check between group1 and group2.
/// \param group1 First collision group.
/// \param group2 Second collision group.
/// \param _group1 First collision group.
/// \param _group2 Second collision group.
void removePairwiseCheck(
std::shared_ptr<::dart::collision::CollisionGroup> _group1,
std::shared_ptr<::dart::collision::CollisionGroup> _group2);

/// Checks collision within group.
/// \param group Collision group.
/// \param _group Collision group.
void addSelfCheck(std::shared_ptr<::dart::collision::CollisionGroup> _group);

/// Remove self-collision check within group.
/// \param group Collision group.
/// \param _group Collision group.
void removeSelfCheck(
std::shared_ptr<::dart::collision::CollisionGroup> _group);

Expand Down
1 change: 0 additions & 1 deletion include/aikido/constraint/dart/TSR.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,6 @@ class TSR : public Sampleable,
statespace::StateSpace::State* _out) const override;

/// Get the testable tolerance used in isSatisfiable.
/// \param[out] _out Testable tolerance, double.
double getTestableTolerance();

/// Set the testable tolerance used in isSatisfiable.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,8 +82,9 @@ class BarrettFingerKinematicSimulationPositionCommandExecutor
/// is reached, or collision is detected.
void step(const std::chrono::system_clock::time_point& timepoint) override;

/// \copydoc
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Let's figure out how to fix this so we don't need to duplicate the \copydocs.

/// BarrettHandKinematicSimulationPositionCommandExecutor::setCollideWith()
// clang-format off
/// \copydoc BarrettHandKinematicSimulationPositionCommandExecutor::setCollideWith()
// clang-format on
bool setCollideWith(::dart::collision::CollisionGroupPtr collideWith);

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,9 @@ class BarrettFingerKinematicSimulationSpreadCommandExecutor
/// collision is detected.
void step(const std::chrono::system_clock::time_point& timepoint) override;

/// \copydoc
/// BarrettHandKinematicSimulationPositionCommandExecutor::setCollideWith()
// clang-format off
/// \copydoc BarrettHandKinematicSimulationPositionCommandExecutor::setCollideWith()
// clang-format on
bool setCollideWith(::dart::collision::CollisionGroupPtr collideWith);

private:
Expand Down
2 changes: 1 addition & 1 deletion include/aikido/control/TrajectoryExecutor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class TrajectoryExecutor
/// is already running, raise an exception unless the executor supports
/// queuing.
///
/// \param traj Trajectory to be executed.
/// \param _traj Trajectory to be executed.
/// \return future<void> for trajectory execution. If trajectory terminates
/// before completion, future will be set to a runtime_error.
virtual std::future<void> execute(trajectory::TrajectoryPtr _traj) = 0;
Expand Down
2 changes: 1 addition & 1 deletion include/aikido/control/ros/RosJointStateClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class RosJointStateClient
dart::dynamics::SkeletonPtr _skeleton,
::ros::NodeHandle _nodeHandle,
const std::string& _topicName,
std::size_t capacity);
std::size_t _capacity);

/// Update mBuffer with any JointState messages that have been received.
void spin();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class RosPositionCommandExecutor
/// Constructor
/// \param[in] node ROS node handle for action client.
/// \param[in] serverName Name of the server to send trajectory to.
/// \param[in] The names of the joints to set position targets for
/// \param[in] jointNames The names of the joints to set position targets for
/// \param[in] connectionTimeout Timeout for server connection.
/// \param[in] connectionPollingPeriod Polling period for server connection.
RosPositionCommandExecutor(
Expand Down
9 changes: 5 additions & 4 deletions include/aikido/io/KinBodyParser.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,14 +26,15 @@ namespace io {
/// \endcode
/// Elements marked with `*` are required.
///
/// <render>, <data>, or <collision> contain the relative path to a mesh file
/// "<render>", "<data>", or "<collision>" contain the relative path to a mesh
/// file
/// and optionally a single float (for all three axes) or three float's (for the
/// x, y, and z-axes) for the scale.
///
/// Example forms:
/// <Render>my/mesh/file.stl<Render>
/// <Render>my/mesh/file.stl 0.25<Render> <!--scale for all three axes-->
/// <Render>my/mesh/file.stl 0.25 0.5 2.0<Render>
/// "<Render>my/mesh/file.stl<Render>"
/// "<Render>my/mesh/file.stl 0.25<Render> <!--scale for all three axes-->"
/// "<Render>my/mesh/file.stl 0.25 0.5 2.0<Render>"
///
/// If the scale is not provided then (1, 1, 1) is used by default.
///
Expand Down
3 changes: 1 addition & 2 deletions include/aikido/perception/PerceptionModule.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,7 @@ class PerceptionModule
/// new objects, compute their pose, and update the list of DART Skeletons
/// that represents the world.
///
/// \param[in,out] skeleton_list The set of skeletons currently in context. It
/// will either be added to or updated.
/// \param[in] env World to add perceived objects to.
/// \param[in] timeout The duration up to which to wait for the transform.
/// Returns false if none of the markers get correctly transformed
/// \param[in] timestamp Only detections more recent than this timestamp will
Expand Down
12 changes: 6 additions & 6 deletions include/aikido/planner/ompl/CRRT.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ class CRRT : public ::ompl::base::Planner
/// Constructor
/// \param _si Information about the planning space
/// \param _name A name for this planner
CRRT(const ::ompl::base::SpaceInformationPtr& _si, const std::string& name);
CRRT(const ::ompl::base::SpaceInformationPtr& _si, const std::string& _name);

/// Destructor
virtual ~CRRT();
Expand All @@ -32,7 +32,7 @@ class CRRT : public ::ompl::base::Planner
/// calls to this function will update data (only additions are made). This is
/// useful to see what changed in the exploration datastructure, between calls
/// to solve(), for example (without calling clear() in between).
/// \param[out] data Data about the current run of the motion planner
/// \param[out] _data Data about the current run of the motion planner
void getPlannerData(::ompl::base::PlannerData& _data) const override;

/// Function that can solve the motion planning problem. This function can be
Expand All @@ -44,12 +44,12 @@ class CRRT : public ::ompl::base::Planner
/// addition of starting or goal states (but not changing previously added
/// start/goal states). The function terminates if the call to ptc returns
/// true.
/// \param ptc Conditions for terminating planning before a solution is found
/// \param _ptc Conditions for terminating planning before a solution is found
::ompl::base::PlannerStatus solve(
const ::ompl::base::PlannerTerminationCondition& _ptc) override;

/// Solve the motion planning problem in the given time
/// \param solveTime The maximum allowable time to solve the planning problem
/// \param _solveTime The maximum allowable time to solve the planning problem
::ompl::base::PlannerStatus solve(double _solveTime);

/// Clear all internal datastructures. Planner settings are not affected.
Expand All @@ -70,7 +70,7 @@ class CRRT : public ::ompl::base::Planner
/// Set the range the planner is supposed to use. This parameter greatly
/// influences the runtime of the algorithm. It represents the maximum length
/// of a motion to be added in the tree of motions.
/// \param distance The maximum length of a motion to be added in the tree of
/// \param _distance The maximum length of a motion to be added in the tree of
/// motions
void setRange(double _distance);

Expand Down Expand Up @@ -172,7 +172,7 @@ class CRRT : public ::ompl::base::Planner
/// \param returnlast If true, return the last node added to the tree,
/// otherwise return the node added that was nearest the goal
/// \param[out] dist The closest distance this extension got to the goal
/// \param[out] True if the extension reached the goal.
/// \param[out] foundgoal True if the extension reached the goal.
/// \return fmotion If returnlast is true, the last node on the extension,
/// otherwise the closest node along the extension to the goal
Motion* constrainedExtend(
Expand Down
10 changes: 5 additions & 5 deletions include/aikido/planner/ompl/CRRTConnect.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ class CRRTConnect : public CRRT
/// calls to this function will update data (only additions are made). This is
/// useful to see what changed in the exploration datastructure, between calls
/// to solve(), for example (without calling clear() in between).
/// \param[out] data Data about the current run of the motion planner
/// \param[out] _data Data about the current run of the motion planner
void getPlannerData(::ompl::base::PlannerData& _data) const override;

/// Function that can solve the motion planning problem. This function can be
Expand All @@ -37,19 +37,19 @@ class CRRTConnect : public CRRT
/// addition of starting or goal states (but not changing previously added
/// start/goal states). The function terminates if the call to ptc returns
/// true.
/// \param ptc Conditions for terminating planning before a solution is found
/// \param _ptc Conditions for terminating planning before a solution is found
::ompl::base::PlannerStatus solve(
const ::ompl::base::PlannerTerminationCondition& p_tc) override;
const ::ompl::base::PlannerTerminationCondition& _ptc) override;

/// Solve the motion planning problem in the given time
/// \param solveTime The maximum allowable time to solve the planning problem
/// \param _solveTime The maximum allowable time to solve the planning problem
::ompl::base::PlannerStatus solve(double _solveTime);

/// Clear all internal datastructures. Planner settings are not affected.
/// Subsequent calls to solve() will ignore all previous work.
void clear() override;

/// \param radius The maximum distance between two trees for them to be
/// \param _radius The maximum distance between two trees for them to be
/// considered connected
void setConnectionRadius(double _radius);

Expand Down
7 changes: 4 additions & 3 deletions include/aikido/planner/ompl/GeometricStateSpace.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,10 +48,11 @@ class GeometricStateSpace : public ::ompl::base::StateSpace
/// \param _interpolator An aikido interpolator used by the interpolate method
/// \param _dmetric The distance metric to use to compute distance between two
/// states in the StateSpace
/// \param sampler A state sampler used to sample new states in the StateSpace
/// \param boundsConstraint A Testable used to determine whether
/// \param _sampler A state sampler used to sample new states in the
/// StateSpace
/// \param _boundsConstraint A Testable used to determine whether
/// states fall with in bounds defined on the space.
/// \param boundsProjection A Projectable that can be used to project a state
/// \param _boundsProjection A Projectable that can be used to project a state
/// back within the valid boundary defined on the space.
GeometricStateSpace(
statespace::StateSpacePtr _sspace,
Expand Down
20 changes: 8 additions & 12 deletions include/aikido/planner/ompl/Planner.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ namespace ompl {
/// start to the goal point. Returns nullptr on planning failure.
/// \param _start The start state
/// \param _goal The goal state
/// \param _statespace The StateSpace that the planner must plan within
/// \param _stateSpace The StateSpace that the planner must plan within
/// \param _interpolator An Interpolator defined on the StateSpace. This is used
/// to interpolate between two points within the space.
/// \param _dmetric A valid distance metric defined on the StateSpace
Expand Down Expand Up @@ -71,7 +71,7 @@ trajectory::InterpolatedPtr planOMPL(
/// state is a goal state
/// \param _goalSampler A Sampleable capable of sampling states that satisfy
/// _goalTestable
/// \param _statespace The StateSpace that the planner must plan within
/// \param _stateSpace The StateSpace that the planner must plan within
/// \param _interpolator An Interpolator defined on the StateSpace. This is used
/// to interpolate between two points within the space.
/// \param _dmetric A valid distance metric defined on the StateSpace
Expand Down Expand Up @@ -114,7 +114,7 @@ trajectory::InterpolatedPtr planOMPL(
/// \param _goalSampler A Sampleable capable of sampling states that satisfy
/// _goalTestable
/// \param _trajConstraint The constraint to satisfy along the trajectory
/// \param _statespace The StateSpace that the planner must plan within
/// \param _stateSpace The StateSpace that the planner must plan within
/// \param _interpolator An Interpolator defined on the StateSpace. This is used
/// to interpolate between two points within the space.
/// \param _dmetric A valid distance metric defined on the StateSpace
Expand Down Expand Up @@ -164,7 +164,7 @@ trajectory::InterpolatedPtr planCRRT(
/// \param _goalSampler A Sampleable capable of sampling states that satisfy
/// _goalTestable
/// \param _trajConstraint The constraint to satisfy along the trajectory
/// \param _statespace The StateSpace that the planner must plan within
/// \param _stateSpace The StateSpace that the planner must plan within
/// \param _interpolator An Interpolator defined on the StateSpace. This is used
/// to interpolate between two points within the space.
/// \param _dmetric A valid distance metric defined on the StateSpace
Expand Down Expand Up @@ -210,7 +210,7 @@ trajectory::InterpolatedPtr planCRRTConnect(
double _minTreeConnectionDistance);

/// Generate an OMPL SpaceInformation from aikido components
/// \param _statespace The StateSpace that the SpaceInformation operates on
/// \param _stateSpace The StateSpace that the SpaceInformation operates on
/// \param _interpolator An Interpolator defined on the StateSpace. This is used
/// to interpolate between two points within the space.
/// \param _dmetric A valid distance metric defined on the StateSpace
Expand Down Expand Up @@ -253,7 +253,7 @@ ompl_shared_ptr<::ompl::base::GoalRegion> getGoalRegion(
/// Use the template OMPL Planner type to plan in a custom OMPL Space
/// Information and problem definition and return an aikido Trajector
/// Returns nullptr on planning failure.
/// \param _si The SpaceInformation used by the planner
/// \param _planner Points to some OMPL planner.
/// \param _pdef The ProblemDefintion. This contains start and goal conditions
/// for the planner.
/// \param _sspace The aikido StateSpace to plan against. Used for constructing
Expand All @@ -270,7 +270,7 @@ trajectory::InterpolatedPtr planOMPL(
double _maxPlanTime);

/// Take in an aikido trajectory and simplify it using OMPL methods
/// \param _statespace The StateSpace that the planner must plan within
/// \param _stateSpace The StateSpace that the planner must plan within
/// \param _interpolator An Interpolator defined on the StateSpace. This is used
/// to interpolate between two points within the space.
/// \param _dmetric A valid distance metric defined on the StateSpace
Expand All @@ -293,10 +293,6 @@ trajectory::InterpolatedPtr planOMPL(
/// \param _maxEmptySteps Maximum number of consecutive failed attempts at
/// shortening before simplification terminates. Default 0, equal to number
/// of states in the path
/// \param _rangeRatio Maximum distance between states a connection is
/// attempted, as a fraction relative to the total length of the path
/// \param _snapToVertex Threshold distance for snapping a state on shortened
/// path to a state on original path
/// \param _originalTraj The untimed trajectory obtained from the planner,
/// needs simplifying.
std::pair<std::unique_ptr<trajectory::Interpolated>, bool> simplifyOMPL(
Expand All @@ -314,7 +310,7 @@ std::pair<std::unique_ptr<trajectory::Interpolated>, bool> simplifyOMPL(

/// Take an interpolated trajectory and convert it into OMPL geometric path
/// \param _interpolatedTraj the interpolated trajectory to be converted
/// \param _sspace The space information pointer.
/// \param _si Information about the planning space
/// returns the corresponding OMPL geometric path
::ompl::geometric::PathGeometric toOMPLTrajectory(
const trajectory::InterpolatedPtr& _interpolatedTraj,
Expand Down
Loading