diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.hpp b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.hpp index aa4d78df1d..060a113f56 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.hpp +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.hpp @@ -166,7 +166,7 @@ double jointLimitVelocityScalingFactor(const Eigen::VectorXd& velocities, const moveit::core::JointBoundsVector& joint_bounds, double scaling_override); /** - * \brief Finds the joint variable indices correspond to joints exceeding allowable position limits. + * \brief Finds the joint variable indices corresponding to joints exceeding allowable position limits. * @param positions The joint positions. * @param velocities The current commanded velocities. * @param joint_bounds The allowable limits for the robot joints. diff --git a/moveit_ros/moveit_servo/src/utils/common.cpp b/moveit_ros/moveit_servo/src/utils/common.cpp index ba63cea053..e270dc76e3 100644 --- a/moveit_ros/moveit_servo/src/utils/common.cpp +++ b/moveit_ros/moveit_servo/src/utils/common.cpp @@ -422,7 +422,7 @@ std::vector jointVariablesToHalt(const Eigen::VectorXd& positions, const bool halt_joint = false; for (const auto& variable_bound : *joint_bound) { - // First, loop through all the variables to see if + // First, loop through all the joint variables to see if the entire joint should be halted. if (variable_bound.position_bounded_) { const bool approaching_negative_bound =