From 4446ef215c274e1a330e232c5374d6c12d96cd99 Mon Sep 17 00:00:00 2001 From: Clang Robot Date: Wed, 3 Apr 2024 15:55:36 +0000 Subject: [PATCH] Committing clang-format changes --- .../include/thruster_allocator/allocator_utils.hpp | 9 +++++---- motion/thruster_allocator/src/allocator_ros.cpp | 5 +++-- 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/motion/thruster_allocator/include/thruster_allocator/allocator_utils.hpp b/motion/thruster_allocator/include/thruster_allocator/allocator_utils.hpp index 7a2ccf33..0e69bcff 100644 --- a/motion/thruster_allocator/include/thruster_allocator/allocator_utils.hpp +++ b/motion/thruster_allocator/include/thruster_allocator/allocator_utils.hpp @@ -36,7 +36,7 @@ inline bool is_invalid_matrix(const Eigen::MatrixBase &M) { * @return std::stringstream The string stream containing the matrix. */ inline std::stringstream print_matrix(std::string name, - const Eigen::MatrixXd &M) { + const Eigen::MatrixXd &M) { std::stringstream ss; ss << std::endl << name << " = " << std::endl << M; return ss; @@ -68,7 +68,8 @@ inline Eigen::MatrixXd calculate_right_pseudoinverse(const Eigen::MatrixXd &T) { * @return True if all vector values are within the given range, false * otherwise. */ -inline bool saturate_vector_values(Eigen::Vector3d &vec, double min, double max) { +inline bool saturate_vector_values(Eigen::Vector3d &vec, double min, + double max) { bool all_values_in_range = std::all_of(vec.begin(), vec.end(), [min, max](double val) { return val >= min && val <= max; }); @@ -91,7 +92,7 @@ inline bool saturate_vector_values(Eigen::Vector3d &vec, double min, double max) #include inline void array_eigen_to_msg(const Eigen::VectorXd &u, - std_msgs::msg::Float32MultiArray &msg) { + std_msgs::msg::Float32MultiArray &msg) { msg.data.assign(u.data(), u.data() + u.size()); } @@ -105,7 +106,7 @@ inline void array_eigen_to_msg(const Eigen::VectorXd &u, */ inline Eigen::MatrixXd double_array_to_eigen_matrix(const std::vector &matrix, int rows, - int cols) { + int cols) { return Eigen::Map>(matrix.data(), rows, cols); diff --git a/motion/thruster_allocator/src/allocator_ros.cpp b/motion/thruster_allocator/src/allocator_ros.cpp index 4ac0aaf8..fb01a966 100644 --- a/motion/thruster_allocator/src/allocator_ros.cpp +++ b/motion/thruster_allocator/src/allocator_ros.cpp @@ -33,8 +33,9 @@ ThrusterAllocator::ThrusterAllocator() std::bind(&ThrusterAllocator::wrench_callback, this, std::placeholders::_1)); - thruster_forces_publisher_ = this->create_publisher( - "thrust/thruster_forces", 1); + thruster_forces_publisher_ = + this->create_publisher( + "thrust/thruster_forces", 1); calculate_thrust_timer_ = this->create_wall_timer( 100ms, std::bind(&ThrusterAllocator::calculate_thrust_timer_cb, this));