From 38592087bbbf6e85f12b2a1de6d56b739cbcdc5c Mon Sep 17 00:00:00 2001 From: Clang Robot Date: Sun, 5 Nov 2023 14:46:43 +0000 Subject: [PATCH] Committing clang-format changes --- .../thruster_allocator/allocator_utils.hpp | 16 +++++----- .../pseudoinverse_allocator.hpp | 10 +++++-- .../thruster_allocator/src/allocator_ros.cpp | 30 ++++++++++++------- 3 files changed, 35 insertions(+), 21 deletions(-) diff --git a/motion/thruster_allocator/include/thruster_allocator/allocator_utils.hpp b/motion/thruster_allocator/include/thruster_allocator/allocator_utils.hpp index 9d9c477a..935d37dc 100644 --- a/motion/thruster_allocator/include/thruster_allocator/allocator_utils.hpp +++ b/motion/thruster_allocator/include/thruster_allocator/allocator_utils.hpp @@ -100,17 +100,19 @@ inline void arrayEigenToMsg(const Eigen::VectorXd &u, msg.thrust = u_vec; } -inline Eigen::MatrixXd doubleArrayToEigenMatrix(const std::vector &matrix, int rows, int cols) { +inline Eigen::MatrixXd +doubleArrayToEigenMatrix(const std::vector &matrix, int rows, + int cols) { - Eigen::MatrixXd result(rows, cols); + Eigen::MatrixXd result(rows, cols); - for (int i = 0; i < rows; ++i) { - for (int j = 0; j < cols; ++j) { - result(i, j) = matrix[i * cols + j]; - } + for (int i = 0; i < rows; ++i) { + for (int j = 0; j < cols; ++j) { + result(i, j) = matrix[i * cols + j]; } + } - return result; + return result; } #endif // VORTEX_ALLOCATOR_ALLOCATOR_UTILS_HPP diff --git a/motion/thruster_allocator/include/thruster_allocator/pseudoinverse_allocator.hpp b/motion/thruster_allocator/include/thruster_allocator/pseudoinverse_allocator.hpp index e5f256f8..0d94596e 100644 --- a/motion/thruster_allocator/include/thruster_allocator/pseudoinverse_allocator.hpp +++ b/motion/thruster_allocator/include/thruster_allocator/pseudoinverse_allocator.hpp @@ -1,6 +1,8 @@ /** * @file pseudoinverse_allocator.hpp - * @brief Contains the PseudoinverseAllocator class, which implements the unweighted pseudoinverse-based allocator described in e.g. Fossen 2011 Handbook of Marine Craft Hydrodynamics and Motion Control (chapter 12.3.2). + * @brief Contains the PseudoinverseAllocator class, which implements the + * unweighted pseudoinverse-based allocator described in e.g. Fossen 2011 + * Handbook of Marine Craft Hydrodynamics and Motion Control (chapter 12.3.2). */ #ifndef VORTEX_ALLOCATOR_PSEUDOINVERSE_ALLOCATOR_HPP @@ -9,7 +11,8 @@ #include /** - * @brief The PseudoinverseAllocator class calculates the allocated thrust given the input torques using the pseudoinverse allocator. + * @brief The PseudoinverseAllocator class calculates the allocated thrust given + * the input torques using the pseudoinverse allocator. */ class PseudoinverseAllocator { public: @@ -21,7 +24,8 @@ class PseudoinverseAllocator { explicit PseudoinverseAllocator(const Eigen::MatrixXd &T_pinv); /** - * @brief Calculates the allocated thrust given the input torques using the pseudoinverse allocator. + * @brief Calculates the allocated thrust given the input torques using the + * pseudoinverse allocator. * * @param tau The input torques as a vector. * @return The allocated thrust as a vector. diff --git a/motion/thruster_allocator/src/allocator_ros.cpp b/motion/thruster_allocator/src/allocator_ros.cpp index 71da83a5..2de729c6 100644 --- a/motion/thruster_allocator/src/allocator_ros.cpp +++ b/motion/thruster_allocator/src/allocator_ros.cpp @@ -10,27 +10,35 @@ using namespace std::chrono_literals; ThrusterAllocator::ThrusterAllocator() : Node("thruster_allocator_node"), - pseudoinverse_allocator_(Eigen::MatrixXd::Zero(3, 4)) -{ - //TEST - // std::vector test = {0.70711, 0.70711, 0.70711, 0.70711, -0.70711, 0.70711, -0.70711, 0.70711, 0.27738, 0.27738, -0.27738, -0.27738}; + pseudoinverse_allocator_(Eigen::MatrixXd::Zero(3, 4)) { + // TEST + // std::vector test = {0.70711, 0.70711, 0.70711, 0.70711, -0.70711, + // 0.70711, -0.70711, 0.70711, 0.27738, 0.27738, -0.27738, -0.27738}; declare_parameter("propulsion.dofs.num", 3); declare_parameter("propulsion.thrusters.num", 4); declare_parameter("propulsion.thrusters.min", -100); declare_parameter("propulsion.thrusters.max", 100); declare_parameter("propulsion.thrusters.direction", std::vector{0}); - declare_parameter("propulsion.thrusters.configuration_matrix", std::vector{0}); + declare_parameter("propulsion.thrusters.configuration_matrix", + std::vector{0}); num_dof_ = get_parameter("propulsion.dofs.num").as_int(); num_thrusters_ = get_parameter("propulsion.thrusters.num").as_int(); min_thrust_ = get_parameter("propulsion.thrusters.min").as_int(); - max_thrust_= get_parameter("propulsion.thrusters.max").as_int(); - direction_ = get_parameter("propulsion.thrusters.direction").as_integer_array(); - thrust_configuration = doubleArrayToEigenMatrix(get_parameter("propulsion.thrusters.configuration_matrix").as_double_array(), num_dof_, num_thrusters_); - - RCLCPP_INFO(get_logger(), printMatrix("Test thrust_configuration test from ", thrust_configuration).str().c_str()); - + max_thrust_ = get_parameter("propulsion.thrusters.max").as_int(); + direction_ = + get_parameter("propulsion.thrusters.direction").as_integer_array(); + thrust_configuration = doubleArrayToEigenMatrix( + get_parameter("propulsion.thrusters.configuration_matrix") + .as_double_array(), + num_dof_, num_thrusters_); + + RCLCPP_INFO(get_logger(), printMatrix("Test thrust_configuration test from ", + thrust_configuration) + .str() + .c_str()); + subscription_ = this->create_subscription( "thrust/wrench_input", 1, std::bind(&ThrusterAllocator::wrench_callback, this,