From 73e01bea22463818adc338182962777ca714eb6d Mon Sep 17 00:00:00 2001 From: DrDab Date: Mon, 2 Oct 2023 18:23:45 -0700 Subject: [PATCH] Make normalizeVector private --- src/control/PlanarArmController.h | 38 +++++++++++++++---------------- 1 file changed, 19 insertions(+), 19 deletions(-) diff --git a/src/control/PlanarArmController.h b/src/control/PlanarArmController.h index 9ec6e6211..660144fdb 100644 --- a/src/control/PlanarArmController.h +++ b/src/control/PlanarArmController.h @@ -51,25 +51,6 @@ template class PlanarArmController { setpoint = normalizeVectorWithinRadius(newSetPoint, radius); } - /** - * @brief Normalize the input vector to have a set radius, - * while maintaining the same direction it did before if it exceeds that set radius. - * - * @param input The input vector to normalize. - * @param radius The radius to normalize the vector to. - */ - Eigen::Vector2d normalizeVectorWithinRadius(Eigen::Vector2d input, double radius) { - if (input.norm() > radius) { - // TODO: will need to eventually shrink velocity vector until it is within radius - // instead of just normalizing it. - - input.normalize(); - input *= radius; - } - - return input; - } - /** * @brief Gets the current end effector setpoint / target position. * @@ -155,5 +136,24 @@ template class PlanarArmController { Eigen::Vector2d velocity; std::optional velTimestamp; const double safetyFactor; + + /** + * @brief Normalize the input vector to have a set radius, + * while maintaining the same direction it did before if it exceeds that set radius. + * + * @param input The input vector to normalize. + * @param radius The radius to normalize the vector to. + */ + Eigen::Vector2d normalizeVectorWithinRadius(Eigen::Vector2d input, double radius) { + if (input.norm() > radius) { + // TODO: will need to eventually shrink velocity vector until it is within radius + // instead of just normalizing it. + + input.normalize(); + input *= radius; + } + + return input; + } }; } // namespace control \ No newline at end of file