From 62b9213a93716149d304fc280df7dd9d6ae7b2cb Mon Sep 17 00:00:00 2001
From: rmackay9 <rmackay9@yahoo.com>
Date: Mon, 22 Oct 2012 16:37:24 +0900
Subject: [PATCH] AP_OpticalFlow: change Serial.print to Serial.print_P to save
 27 bytes

---
 libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp | 10 +++++-----
 libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.h   |  2 +-
 2 files changed, 6 insertions(+), 6 deletions(-)

diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp
index 0fc29d658..9ba3c142b 100644
--- a/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp
+++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp
@@ -528,7 +528,7 @@ AP_OpticalFlow_ADNS3080::clear_motion()
 
 // get_pixel_data - captures an image from the sensor and stores it to the pixe_data array
 void
-AP_OpticalFlow_ADNS3080::print_pixel_data(Stream *serPort)
+AP_OpticalFlow_ADNS3080::print_pixel_data()
 {
     int16_t i,j;
     bool isFirstPixel = true;
@@ -546,16 +546,16 @@ AP_OpticalFlow_ADNS3080::print_pixel_data(Stream *serPort)
         for( j=0; j<ADNS3080_PIXELS_X; j++ ) {
             regValue = read_register(ADNS3080_FRAME_CAPTURE);
             if( isFirstPixel && (regValue & 0x40) == 0 ) {
-                serPort->println("failed to find first pixel");
+                Serial.print_P(PSTR("failed to find first pixel"));
             }
             isFirstPixel = false;
             pixelValue = ( regValue << 2);
-            serPort->print(pixelValue,DEC);
+            Serial.print(pixelValue,DEC);
             if( j!= ADNS3080_PIXELS_X-1 )
-                serPort->print(",");
+                Serial.print_P(PSTR(","));
             delayMicroseconds(50);
         }
-        serPort->println();
+        Serial.println();
     }
 
     // hardware reset to restore sensor to normal operation
diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.h
index 3a82c9f98..e0f9b00ee 100644
--- a/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.h
+++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.h
@@ -122,7 +122,7 @@ public:
 
     void                clear_motion(); // will cause the x,y, dx, dy, and the sensor's motion registers to be cleared
 
-    void                print_pixel_data(Stream *serPort); // dumps a 30x30 image to the Serial port
+    void                print_pixel_data(); // dumps a 30x30 image to the Serial port
 
 private:
     // bytes to store SPI settings
-- 
GitLab