Skip to content

Commit

Permalink
Merge remote-tracking branch 'refs/remotes/origin/enhancement/thruste…
Browse files Browse the repository at this point in the history
…r_allocator_cleanup' into enhancement/thruster_allocator_cleanup
  • Loading branch information
Aldokan committed Apr 8, 2024
2 parents df6fd87 + 4446ef2 commit 542514c
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ inline bool is_invalid_matrix(const Eigen::MatrixBase<Derived> &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;
Expand Down Expand Up @@ -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; });
Expand All @@ -91,7 +92,7 @@ inline bool saturate_vector_values(Eigen::Vector3d &vec, double min, double max)
#include <std_msgs/msg/float32_multi_array.hpp>

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());
}

Expand All @@ -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<double> &matrix, int rows,
int cols) {
int cols) {
return Eigen::Map<const Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic,
Eigen::RowMajor>>(matrix.data(), rows,
cols);
Expand Down
5 changes: 3 additions & 2 deletions motion/thruster_allocator/src/allocator_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,9 @@ ThrusterAllocator::ThrusterAllocator()
std::bind(&ThrusterAllocator::wrench_callback, this,
std::placeholders::_1));

thruster_forces_publisher_ = this->create_publisher<std_msgs::msg::Float32MultiArray>(
"thrust/thruster_forces", 1);
thruster_forces_publisher_ =
this->create_publisher<std_msgs::msg::Float32MultiArray>(
"thrust/thruster_forces", 1);

calculate_thrust_timer_ = this->create_wall_timer(
100ms, std::bind(&ThrusterAllocator::calculate_thrust_timer_cb, this));
Expand Down

0 comments on commit 542514c

Please sign in to comment.