diff --git a/diff_drive_controller/src/diff_drive_controller.cpp b/diff_drive_controller/src/diff_drive_controller.cpp index 7356d80219..c4ba9a71cd 100644 --- a/diff_drive_controller/src/diff_drive_controller.cpp +++ b/diff_drive_controller/src/diff_drive_controller.cpp @@ -618,7 +618,9 @@ bool DiffDriveController::reset() void DiffDriveController::reset_buffers() { - reference_interfaces_ = std::vector(2, std::numeric_limits::quiet_NaN()); + std::fill( + reference_interfaces_.begin(), reference_interfaces_.end(), + std::numeric_limits::quiet_NaN()); // Empty out the old queue. Fill with zeros (not NaN) to catch early accelerations. std::queue> empty; std::swap(previous_two_commands_, empty);