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 d6656f92..1f116c79 100644 --- a/motion/thruster_allocator/src/allocator_ros.cpp +++ b/motion/thruster_allocator/src/allocator_ros.cpp @@ -17,7 +17,8 @@ ThrusterAllocator::ThrusterAllocator() 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();