diff --git a/mg_odometry/src/mg_odom_publisher.cpp b/mg_odometry/src/mg_odom_publisher.cpp index bceac11..3c5d0ff 100644 --- a/mg_odometry/src/mg_odom_publisher.cpp +++ b/mg_odometry/src/mg_odom_publisher.cpp @@ -6,6 +6,7 @@ #include #include #include +#include #include "mg_msgs/srv/set_width.hpp" #include "std_srvs/srv/empty.hpp" @@ -56,9 +57,9 @@ class MgOdomPublisher : public rclcpp::Node { void set_width(const std::shared_ptr request) { RCLCPP_INFO(get_logger(), "Setting width to: %lf", request->width); - if (!enc_serial_port_.IsOpen()) { + if (enc_serial_port_.IsOpen()) { union { - std::array bytes; + std::array bytes; double data; } value{}; value.data = request->width; @@ -71,7 +72,7 @@ class MgOdomPublisher : public rclcpp::Node { void zero(const std::shared_ptr /*request*/) { RCLCPP_INFO(get_logger(), "Zeroing odometry"); - if (!enc_serial_port_.IsOpen()) { + if (enc_serial_port_.IsOpen()) { enc_serial_port_ << "z;"; } }