diff --git a/GraspPlanning/ApproachMovementSurfaceNormal.h b/GraspPlanning/ApproachMovementSurfaceNormal.h index bc976fdf72a87ea07fb5071661b0f127d28af924..17dc6279f57cdf3b53ce9317310a54fbe5542305 100644 --- a/GraspPlanning/ApproachMovementSurfaceNormal.h +++ b/GraspPlanning/ApproachMovementSurfaceNormal.h @@ -55,10 +55,10 @@ namespace GraspStudio * \param object The object. * \param eef The end effector. * \param graspPreshape An optional preshape that can be used in order to "open" the eef. - * \param maxRandDist + * \param maxRetreatDist * If >0, the resulting apporach pose is randomly moved in the approach direction * (away from the object) in order to create different distances to the object. - * \param usefaceAreaDistribution + * \param useFaceAreaDistribution * If true, the probability of a face being selected is proportional to its area. * If false, all faces are selected with equal probability. */ diff --git a/GraspPlanning/GraspPlanner/GenericGraspPlanner.h b/GraspPlanning/GraspPlanner/GenericGraspPlanner.h index 0903780fe0eb6ec0aec7f7b27465b9dcda7ce41d..7be6aa603fef73249530d095d827d87eecaa1c5f 100644 --- a/GraspPlanning/GraspPlanner/GenericGraspPlanner.h +++ b/GraspPlanning/GraspPlanner/GenericGraspPlanner.h @@ -62,7 +62,8 @@ namespace GraspStudio /*! Creates new grasps. \param nrGrasps The number of grasps to be planned. - \param timeOutMS The time out in milliseconds. Planning is stopped when this time is exceeded. Disabled when zero. + \param timeOutDuration The time out in milliseconds. Planning is stopped when this time is exceeded. Disabled when zero. + \param obstacles \return Number of generated grasps. */ int plan(int nrGrasps, int timeOutDuration = 0, VirtualRobot::SceneObjectSetPtr obstacles = {}) override; diff --git a/GraspPlanning/GraspPlanner/GraspPlanner.h b/GraspPlanning/GraspPlanner/GraspPlanner.h index b38cc46520ac099f282c4d56a46f6db0e7d2bb46..5b7feb70257860c75d04fa6149407631f7d59b82 100644 --- a/GraspPlanning/GraspPlanner/GraspPlanner.h +++ b/GraspPlanning/GraspPlanner/GraspPlanner.h @@ -56,6 +56,7 @@ namespace GraspStudio Creates new grasps. \param nrGrasps The number of grasps to be planned. \param timeOutMS The time out in milliseconds. Planning is stopped when this time is exceeded. Disabled when zero. + \param obstacles \return Number of planned grasps. */ virtual int plan(int nrGrasps, int timeOutMS = 0, VirtualRobot::SceneObjectSetPtr obstacles = {}) = 0; diff --git a/MotionPlanning/Planner/BiRrt.h b/MotionPlanning/Planner/BiRrt.h index bbaaea6829e505db01c263edb24d9b976d185ce4..5d846881915a86c3c374403df29cd26d2c56c4af 100644 --- a/MotionPlanning/Planner/BiRrt.h +++ b/MotionPlanning/Planner/BiRrt.h @@ -46,6 +46,7 @@ namespace Saba \param cspace An initialized cspace object. \param modeA Specify the RRT method that should be used to build the first tree \param modeB Specify the RRT method that should be used to build the second tree + \param samplingSize */ BiRrt(CSpacePtr cspace, RrtMethod modeA = eConnect, RrtMethod modeB = eConnect, float samplingSize = -1); ~BiRrt() override; diff --git a/MotionPlanning/Planner/Rrt.h b/MotionPlanning/Planner/Rrt.h index 953e1e340d27ddbf74453b9c9d5e649a8158c3ea..94aae148b75cee2adef2a6d3988cf737d0d4b4f8 100644 --- a/MotionPlanning/Planner/Rrt.h +++ b/MotionPlanning/Planner/Rrt.h @@ -68,6 +68,7 @@ namespace Saba \param cspace A cspace, defining the used joints (the dimension/DoF) and the collision detection setup. \param mode Specify the RRT method that should be used \param probabilityExtendToGoal Specify how often the goal node should be used instead of a random config (value must be between 0 and 1) + \param samplingSize */ Rrt(CSpacePtr cspace, RrtMethod mode = eConnect, float probabilityExtendToGoal = 0.1f, float samplingSize = -1); ~Rrt() override; diff --git a/VirtualRobot/MathTools.h b/VirtualRobot/MathTools.h index 74624441024d722bb024a4edeff6746fe3932db0..4297106c392480f0daba82bd741ca2a2bab2e73a 100644 --- a/VirtualRobot/MathTools.h +++ b/VirtualRobot/MathTools.h @@ -650,8 +650,8 @@ namespace VirtualRobot double VIRTUAL_ROBOT_IMPORT_EXPORT getDamping(const Eigen::MatrixXf &matrix); /*! @brief Calculates the damped least square inverse by J^T * (JJ^T + k^2 I)^{-1} - * @jacobian Jacobian J - * @squaredDampingFactor Damping factor k^2 + * @param jacobian Jacobian J + * @param squaredDampingFactor Damping factor k^2 */ template <typename T> Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> VIRTUAL_ROBOT_IMPORT_EXPORT getDampedLeastSquareInverse(const Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> &jacobian, double squaredDampingFactor = 0.01f) { diff --git a/VirtualRobot/Workspace/NaturalPosture.h b/VirtualRobot/Workspace/NaturalPosture.h index ca1e335cfea2b593b52850625743428b1c5a8036..69af00341969f453df7969babf228ec95b2b9ae3 100644 --- a/VirtualRobot/Workspace/NaturalPosture.h +++ b/VirtualRobot/Workspace/NaturalPosture.h @@ -31,7 +31,8 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT NaturalPosture : public WorkspaceRepresentation, public std::enable_shared_from_this<NaturalPosture> + class VIRTUAL_ROBOT_IMPORT_EXPORT NaturalPosture : + public WorkspaceRepresentation, public std::enable_shared_from_this<NaturalPosture> { public: friend class CoinVisualizationFactory; diff --git a/VirtualRobot/Workspace/WorkspaceGrid.h b/VirtualRobot/Workspace/WorkspaceGrid.h index 0b55c26619d7090d95f8de6fef77d7726abeb1be..1d22d9aae3b5d8889db496b9991f1353b97d7a79 100644 --- a/VirtualRobot/Workspace/WorkspaceGrid.h +++ b/VirtualRobot/Workspace/WorkspaceGrid.h @@ -34,7 +34,7 @@ namespace VirtualRobot * A 2D grid which represents a quality distribution (e.g. the reachability) at 2D positions w.r.t. one or multiple grasp(s). * Internally the inverse workspace data (@see WorkspaceRepresentation), which encodes the * transformation between robot's base and grasping position, is used. - * This data is useful to quickly sample positions from where the probability that a grasp is reachable is high (see \func getRandomPos). + * This data is useful to quickly sample positions from where the probability that a grasp is reachable is high (see getRandomPos()). */ class VIRTUAL_ROBOT_IMPORT_EXPORT WorkspaceGrid { diff --git a/VirtualRobot/Workspace/WorkspaceRepresentation.h b/VirtualRobot/Workspace/WorkspaceRepresentation.h index 666aee275ce0294046cdcc52a0c8ef166839a725..de58e980884f79ad5db9197779db1ecae60e0243 100644 --- a/VirtualRobot/Workspace/WorkspaceRepresentation.h +++ b/VirtualRobot/Workspace/WorkspaceRepresentation.h @@ -273,7 +273,7 @@ namespace VirtualRobot /*! Estimate a parameter setup for the given RNS by randomly set configurations and check for achieved workspace extends. The results are slightly scaled. - \param ndoeSet + \param nodeSet \param steps How many loops should be performed to estimate the result. Chose a value >= 1000. \param storeMinBounds Workspace extend from min \param storeMaxBounds Workspace extend to max @@ -321,6 +321,7 @@ namespace VirtualRobot * \brief createCut Create a cut at a specific height (assuming z is upwards). * \param heightPercent Value in [0,1] * \param cellSize The discretization step size of the result + * \param sumAngles¸ * \return */ WorkspaceCut2DPtr createCut(float heightPercent, float cellSize, bool sumAngles) const;