Skip to content

Commit

Permalink
refactor: change thrust output type to Float64MutliArray
Browse files Browse the repository at this point in the history
  • Loading branch information
Andeshog committed Jan 5, 2025
1 parent 6d60ce3 commit 8809896
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
#include <rclcpp/rclcpp.hpp>

#include <geometry_msgs/msg/wrench.hpp>
#include <std_msgs/msg/float32_multi_array.hpp>
#include <std_msgs/msg/float64_multi_array.hpp>

using namespace std::chrono_literals;

Expand All @@ -39,7 +39,7 @@ class ThrusterAllocator : public rclcpp::Node {
* @param msg The received geometry_msgs::msg::Wrench message.
*/
void wrench_callback(const geometry_msgs::msg::Wrench &msg);
rclcpp::Publisher<std_msgs::msg::Float32MultiArray>::SharedPtr
rclcpp::Publisher<std_msgs::msg::Float64MultiArray>::SharedPtr
thruster_forces_publisher_;
rclcpp::Subscription<geometry_msgs::msg::Wrench>::SharedPtr
wrench_subscriber_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,7 @@
#include <rclcpp/rclcpp.hpp>
#include <string>
#include <vector>

#include <std_msgs/msg/float32_multi_array.hpp>
#include <std_msgs/msg/float64_multi_array.hpp>

/**
* @brief Check if the matrix has any NaN or INF elements.
Expand Down Expand Up @@ -89,10 +88,9 @@ inline bool saturate_vector_values(Eigen::VectorXd &vec, double min,
* @param msg The std_msgs::msg::Float32MultiArray message to store the
* converted values.
*/
#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::Float64MultiArray &msg) {
msg.data.assign(u.data(), u.data() + u.size());
}

Expand Down
6 changes: 3 additions & 3 deletions motion/thruster_allocator/src/allocator_ros.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include "thruster_allocator/allocator_ros.hpp"
#include "thruster_allocator/allocator_utils.hpp"
#include "thruster_allocator/pseudoinverse_allocator.hpp"
#include <std_msgs/msg/float32_multi_array.hpp>
#include <std_msgs/msg/float64_multi_array.hpp>

#include <chrono>
#include <functional>
Expand Down Expand Up @@ -34,7 +34,7 @@ ThrusterAllocator::ThrusterAllocator()
std::placeholders::_1));

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

calculate_thrust_timer_ = this->create_wall_timer(
Expand All @@ -59,7 +59,7 @@ void ThrusterAllocator::calculate_thrust_timer_cb() {
RCLCPP_WARN(get_logger(), "Thruster forces vector required saturation.");
}

std_msgs::msg::Float32MultiArray msg_out;
std_msgs::msg::Float64MultiArray msg_out;
array_eigen_to_msg(thruster_forces, msg_out);
thruster_forces_publisher_->publish(msg_out);
}
Expand Down

0 comments on commit 8809896

Please sign in to comment.