mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
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:
parent
f9b0f9164a
commit
ae927e1775
@ -119,9 +119,9 @@ uint16_t DataFlash_Block::start_new_log(void)
|
|||||||
uint16_t last_page = find_last_page();
|
uint16_t last_page = find_last_page();
|
||||||
|
|
||||||
StartRead(last_page);
|
StartRead(last_page);
|
||||||
//Serial.print("last page: "); Serial.println(last_page);
|
//Serial.print("last page: "); Serial.println(last_page);
|
||||||
//Serial.print("file #: "); Serial.println(GetFileNumber());
|
//Serial.print("file #: "); Serial.println(GetFileNumber());
|
||||||
//Serial.print("file page: "); Serial.println(GetFilePage());
|
//Serial.print("file page: "); Serial.println(GetFilePage());
|
||||||
|
|
||||||
if(find_last_log() == 0 || GetFileNumber() == 0xFFFF) {
|
if(find_last_log() == 0 || GetFileNumber() == 0xFFFF) {
|
||||||
SetFileNumber(1);
|
SetFileNumber(1);
|
||||||
@ -326,7 +326,7 @@ uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number)
|
|||||||
StartRead(bottom);
|
StartRead(bottom);
|
||||||
if (GetFileNumber() == log_number) return bottom;
|
if (GetFileNumber() == log_number) return bottom;
|
||||||
|
|
||||||
return -1;
|
return 0xFFFF;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -845,7 +845,7 @@ void DataFlash_Class::Log_Write_Baro(AP_Baro &baro, uint64_t time_us)
|
|||||||
LOG_PACKET_HEADER_INIT(LOG_BAR2_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_BAR2_MSG),
|
||||||
time_us : time_us,
|
time_us : time_us,
|
||||||
altitude : baro.get_altitude(1),
|
altitude : baro.get_altitude(1),
|
||||||
pressure : baro.get_pressure(1),
|
pressure : baro.get_pressure(1),
|
||||||
temperature : (int16_t)(baro.get_temperature(1) * 100 + 0.5f),
|
temperature : (int16_t)(baro.get_temperature(1) * 100 + 0.5f),
|
||||||
climbrate : climbrate,
|
climbrate : climbrate,
|
||||||
sample_time_ms: baro.get_last_update(1),
|
sample_time_ms: baro.get_last_update(1),
|
||||||
@ -859,7 +859,7 @@ void DataFlash_Class::Log_Write_Baro(AP_Baro &baro, uint64_t time_us)
|
|||||||
LOG_PACKET_HEADER_INIT(LOG_BAR3_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_BAR3_MSG),
|
||||||
time_us : time_us,
|
time_us : time_us,
|
||||||
altitude : baro.get_altitude(2),
|
altitude : baro.get_altitude(2),
|
||||||
pressure : baro.get_pressure(2),
|
pressure : baro.get_pressure(2),
|
||||||
temperature : (int16_t)(baro.get_temperature(2) * 100 + 0.5f),
|
temperature : (int16_t)(baro.get_temperature(2) * 100 + 0.5f),
|
||||||
climbrate : climbrate,
|
climbrate : climbrate,
|
||||||
sample_time_ms: baro.get_last_update(2),
|
sample_time_ms: baro.get_last_update(2),
|
||||||
@ -1284,7 +1284,7 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled)
|
|||||||
void DataFlash_Class::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled)
|
void DataFlash_Class::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled)
|
||||||
{
|
{
|
||||||
uint64_t time_us = AP_HAL::micros64();
|
uint64_t time_us = AP_HAL::micros64();
|
||||||
// Write first EKF packet
|
// Write first EKF packet
|
||||||
Vector3f euler;
|
Vector3f euler;
|
||||||
Vector2f posNE;
|
Vector2f posNE;
|
||||||
float posD;
|
float posD;
|
||||||
|
Loading…
Reference in New Issue
Block a user