Skip to content

Commit

Permalink
Fix doxy comments
Browse files Browse the repository at this point in the history
  • Loading branch information
abhaybd committed Apr 12, 2024
1 parent 12224ef commit ff6cbce
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
4 changes: 2 additions & 2 deletions src/kinematics/ForwardArmKinematics.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ class ForwardArmKinematics {
* @brief Given a joint position, calculate the current EE position.
*
* @param jointPos Current joint position.
* @return Eigen::Vectord<D> The EE position.
* @return navtypes::Vectord<D> The EE position.
*/
virtual navtypes::Vectord<D>
jointPosToEEPos(const navtypes::Vectord<N>& jointPos) const = 0;
Expand All @@ -74,7 +74,7 @@ class ForwardArmKinematics {
*
* @param jointPos Current joint position.
* @param jointVel Current velocity of each joint angle.
* @return Eigen::Vectord<D> The EE velocity.
* @return navtypes::Vectord<D> The EE velocity.
*/
navtypes::Vectord<D> jointVelToEEVel(const navtypes::Vectord<N>& jointPos,
const navtypes::Vectord<N>& jointVel) const {
Expand Down
4 changes: 2 additions & 2 deletions src/kinematics/InverseArmKinematics.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class InverseArmKinematics {
* solver.
* @param[out] success Output parameter that signals if the IK solver succeeded. Failure
* may occur if the target is unreachable or the IK solver exceeds the iteration limit.
* @return navtypes::Arrayd<N> The target joint angles that achieve the desired EE
* @return navtypes::Vectord<N> The target joint angles that achieve the desired EE
* position.
*/
virtual navtypes::Vectord<N> eePosToJointPos(const navtypes::Vectord<D>& eePos,
Expand Down Expand Up @@ -83,7 +83,7 @@ class InverseArmKinematics {
* solver.
* @param[out] success Output parameter that signals if the IK solver succeeded. Failure
* may occur if the target is unreachable or the IK solver exceeds the iteration limit.
* @return navtypes::Arrayd<N> The target joint angles that achieve the desired EE
* @return navtypes::Vectord<N> The target joint angles that achieve the desired EE
* position.
*/
virtual navtypes::Vectord<N> solve(const navtypes::Vectord<D>& eePos,
Expand Down

0 comments on commit ff6cbce

Please sign in to comment.