diff --git a/motion/thruster_interface/src/thruster_interface.cpp b/motion/thruster_interface/src/thruster_interface.cpp index b766c472..3e1741d0 100644 --- a/motion/thruster_interface/src/thruster_interface.cpp +++ b/motion/thruster_interface/src/thruster_interface.cpp @@ -53,7 +53,7 @@ float ThrusterInterface::interpolate(float force) { pwm1 + ((force - force1) * (pwm2 - pwm1)) / (force2 - force1) + 0.5); int clipped_pwm_signal = - std::min(std::max(pwm_signal, 1300), 1700); // min 1100, max 1900 + std::min(std::max(pwm_signal, 1400), 1600); // min 1100, max 1900 return clipped_pwm_signal; } @@ -65,7 +65,7 @@ ThrusterInterface::pwm_to_bytes(const std::vector &pwm_values) { for (const auto &val : pwm_values) { // Ensure the value is in the correct range and cast to an integer int pwm_int = static_cast( - std::min(std::max(val, 1300), 1700)); // min 1100, max 1900 + std::min(std::max(val, 1400), 1600)); // min 1100, max 1900 // Split the integer into most significant byte (MSB) and least significant // byte (LSB) diff --git a/motion/thruster_interface/src/thruster_interface_node.cpp b/motion/thruster_interface/src/thruster_interface_node.cpp index b868d8aa..ff084ec5 100644 --- a/motion/thruster_interface/src/thruster_interface_node.cpp +++ b/motion/thruster_interface/src/thruster_interface_node.cpp @@ -33,8 +33,8 @@ void ThrusterInterfaceROS::thrust_callback( int pwm_value_correct_direction = center_pwm_value + thruster_direction_map[i] * offset_from_center_value; - int pwm_clamped = std::min(std::max(pwm_value_correct_direction, 1300), - 1700); // min 1100, max 1900 + int pwm_clamped = std::min(std::max(pwm_value_correct_direction, 1400), + 1600); // min 1100, max 1900 pwm_msg.positive_width_us.push_back(pwm_clamped); pwm_msg.pins.push_back(thruster_to_pin_map[i]); }