mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_OpticalFlow: change Serial.print to Serial.print_P to save 27 bytes
This commit is contained in:
parent
eaf75d3be4
commit
00279c6d3a
@ -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
|
// get_pixel_data - captures an image from the sensor and stores it to the pixe_data array
|
||||||
void
|
void
|
||||||
AP_OpticalFlow_ADNS3080::print_pixel_data(Stream *serPort)
|
AP_OpticalFlow_ADNS3080::print_pixel_data()
|
||||||
{
|
{
|
||||||
int16_t i,j;
|
int16_t i,j;
|
||||||
bool isFirstPixel = true;
|
bool isFirstPixel = true;
|
||||||
@ -546,16 +546,16 @@ AP_OpticalFlow_ADNS3080::print_pixel_data(Stream *serPort)
|
|||||||
for( j=0; j<ADNS3080_PIXELS_X; j++ ) {
|
for( j=0; j<ADNS3080_PIXELS_X; j++ ) {
|
||||||
regValue = read_register(ADNS3080_FRAME_CAPTURE);
|
regValue = read_register(ADNS3080_FRAME_CAPTURE);
|
||||||
if( isFirstPixel && (regValue & 0x40) == 0 ) {
|
if( isFirstPixel && (regValue & 0x40) == 0 ) {
|
||||||
serPort->println("failed to find first pixel");
|
Serial.print_P(PSTR("failed to find first pixel"));
|
||||||
}
|
}
|
||||||
isFirstPixel = false;
|
isFirstPixel = false;
|
||||||
pixelValue = ( regValue << 2);
|
pixelValue = ( regValue << 2);
|
||||||
serPort->print(pixelValue,DEC);
|
Serial.print(pixelValue,DEC);
|
||||||
if( j!= ADNS3080_PIXELS_X-1 )
|
if( j!= ADNS3080_PIXELS_X-1 )
|
||||||
serPort->print(",");
|
Serial.print_P(PSTR(","));
|
||||||
delayMicroseconds(50);
|
delayMicroseconds(50);
|
||||||
}
|
}
|
||||||
serPort->println();
|
Serial.println();
|
||||||
}
|
}
|
||||||
|
|
||||||
// hardware reset to restore sensor to normal operation
|
// hardware reset to restore sensor to normal operation
|
||||||
|
@ -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 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:
|
private:
|
||||||
// bytes to store SPI settings
|
// bytes to store SPI settings
|
||||||
|
Loading…
Reference in New Issue
Block a user