AP_OpticalFlow: change Serial.print to Serial.print_P to save 27 bytes

This commit is contained in:
rmackay9 2012-10-22 16:37:24 +09:00
parent bff3417d29
commit 57439b662c
2 changed files with 6 additions and 6 deletions

View File

@ -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

View File

@ -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