From c207db9e68a263e51a85f8f7f9ddb42590f02642 Mon Sep 17 00:00:00 2001 From: AndyZe Date: Tue, 30 Mar 2021 05:39:10 -0500 Subject: [PATCH] Update doxygen comments for distance() and interpolate() (#401) --- .../include/moveit/robot_model/robot_model.h | 10 +++++ .../include/moveit/robot_state/robot_state.h | 38 ++++++++++++++----- 2 files changed, 39 insertions(+), 9 deletions(-) diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 3560c67da7..6a1e6f2fb2 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -336,7 +336,17 @@ class RobotModel } double getMaximumExtent(const JointBoundsVector& active_joint_bounds) const; + /** \brief Return the sum of joint distances between two states. An L1 norm. Only considers active joints. */ double distance(const double* state1, const double* state2) const; + + /** + * Interpolate between "from" state, to "to" state. Mimic joints are correctly updated. + * + * @param from interpolate from this state + * @param to to this state + * @param t a fraction in the range [0 1]. If 1, the result matches "to" state exactly. + * @param state holds the result + */ void interpolate(const double* from, const double* to, double t, double* state) const; /** \name Access to joint groups diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index 904ffacb72..84d2a070e7 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -1402,32 +1402,52 @@ class RobotState * @{ */ + /** \brief Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints. */ double distance(const RobotState& other) const { return robot_model_->distance(position_, other.getVariablePositions()); } + /** \brief Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints. */ double distance(const RobotState& other, const JointModelGroup* joint_group) const; + /** \brief Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints. */ double distance(const RobotState& other, const JointModel* joint) const { const int idx = joint->getFirstVariableIndex(); return joint->distance(position_ + idx, other.position_ + idx); } - /** \brief Interpolate from this state towards state \e to, at time \e t in [0,1]. - The result is stored in \e state, mimic joints are correctly updated and flags are set - so that FK is recomputed when needed. */ + /** + * Interpolate towards "to" state. Mimic joints are correctly updated and flags are set so that FK is recomputed + * when needed. + * + * @param to interpolate to this state + * @param t a fraction in the range [0 1]. If 1, the result matches "to" state exactly. + * @param state holds the result + */ void interpolate(const RobotState& to, double t, RobotState& state) const; - /** \brief Interpolate from this state towards \e to, at time \e t in [0,1], but only for the joints in the - specified group. If mimic joints need to be updated, they are updated accordingly. Flags are set so that FK - computation is triggered when needed. */ + /** + * Interpolate towards "to" state, but only for the joints in the specified group. Mimic joints are correctly updated + * and flags are set so that FK is recomputed when needed. + * + * @param to interpolate to this state + * @param t a fraction in the range [0 1]. If 1, the result matches "to" state exactly. + * @param state holds the result + * @param joint_group interpolate only for the joints in this group + */ void interpolate(const RobotState& to, double t, RobotState& state, const JointModelGroup* joint_group) const; - /** \brief Update \e state by interpolating form this state towards \e to, at time \e t in [0,1] but only for - the joint \e joint. If there are joints that mimic this joint, they are updated. Flags are set so that - FK computation is triggered as needed. */ + /** + * Interpolate towards "to" state, but only for a single joint. Mimic joints are correctly updated + * and flags are set so that FK is recomputed when needed. + * + * @param to interpolate to this state + * @param t a fraction in the range [0 1]. If 1, the result matches "to" state exactly. + * @param state holds the result + * @param joint interpolate only for this joint + */ void interpolate(const RobotState& to, double t, RobotState& state, const JointModel* joint) const { const int idx = joint->getFirstVariableIndex();