DataFlash: Adjust the return value to the type of the method.

DataFlash: Adjust the return value to the type of the method.
This commit is contained in:
murata 2016-11-23 00:34:53 +09:00 committed by Tom Pittenger
parent f9b0f9164a
commit ae927e1775
1 changed files with 16 additions and 16 deletions

View File

@ -326,7 +326,7 @@ uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number)
StartRead(bottom);
if (GetFileNumber() == log_number) return bottom;
return -1;
return 0xFFFF;
}
/*