From ae927e17751bcdae0cced26d66c966ab2b347aa8 Mon Sep 17 00:00:00 2001 From: murata Date: Wed, 23 Nov 2016 00:34:53 +0900 Subject: [PATCH] DataFlash: Adjust the return value to the type of the method. DataFlash: Adjust the return value to the type of the method. --- libraries/DataFlash/LogFile.cpp | 32 ++++++++++++++++---------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index f44b64a2b5..7eb57d474c 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -119,9 +119,9 @@ uint16_t DataFlash_Block::start_new_log(void) uint16_t last_page = find_last_page(); StartRead(last_page); - //Serial.print("last page: "); Serial.println(last_page); - //Serial.print("file #: "); Serial.println(GetFileNumber()); - //Serial.print("file page: "); Serial.println(GetFilePage()); + //Serial.print("last page: "); Serial.println(last_page); + //Serial.print("file #: "); Serial.println(GetFileNumber()); + //Serial.print("file page: "); Serial.println(GetFilePage()); if(find_last_log() == 0 || GetFileNumber() == 0xFFFF) { SetFileNumber(1); @@ -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; } /* @@ -845,13 +845,13 @@ void DataFlash_Class::Log_Write_Baro(AP_Baro &baro, uint64_t time_us) LOG_PACKET_HEADER_INIT(LOG_BAR2_MSG), time_us : time_us, 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), climbrate : climbrate, sample_time_ms: baro.get_last_update(1), drift_offset : drift_offset, }; - WriteBlock(&pkt2, sizeof(pkt2)); + WriteBlock(&pkt2, sizeof(pkt2)); } if (baro.num_instances() > 2 && baro.healthy(2)) { @@ -859,13 +859,13 @@ void DataFlash_Class::Log_Write_Baro(AP_Baro &baro, uint64_t time_us) LOG_PACKET_HEADER_INIT(LOG_BAR3_MSG), time_us : time_us, 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), climbrate : climbrate, sample_time_ms: baro.get_last_update(2), drift_offset : drift_offset, }; - WriteBlock(&pkt3, sizeof(pkt3)); + WriteBlock(&pkt3, sizeof(pkt3)); } } @@ -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) { uint64_t time_us = AP_HAL::micros64(); - // Write first EKF packet + // Write first EKF packet Vector3f euler; Vector2f posNE; float posD; @@ -1565,7 +1565,7 @@ bool DataFlash_Backend::Log_Write_MavCmd(uint16_t cmd_total, const mavlink_missi return WriteBlock(&pkt, sizeof(pkt)); } -void DataFlash_Class::Log_Write_Radio(const mavlink_radio_t &packet) +void DataFlash_Class::Log_Write_Radio(const mavlink_radio_t &packet) { struct log_Radio pkt = { LOG_PACKET_HEADER_INIT(LOG_RADIO_MSG), @@ -1578,7 +1578,7 @@ void DataFlash_Class::Log_Write_Radio(const mavlink_radio_t &packet) rxerrors : packet.rxerrors, fixed : packet.fixed }; - WriteBlock(&pkt, sizeof(pkt)); + WriteBlock(&pkt, sizeof(pkt)); } // Write a Camera packet @@ -1679,7 +1679,7 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass, uint64_t time_us } const Vector3f &mag_field = compass.get_field(0); const Vector3f &mag_offsets = compass.get_offsets(0); - const Vector3f &mag_motor_offsets = compass.get_motor_offsets(0); + const Vector3f &mag_motor_offsets = compass.get_motor_offsets(0); struct log_Compass pkt = { LOG_PACKET_HEADER_INIT(LOG_COMPASS_MSG), time_us : time_us, @@ -1700,7 +1700,7 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass, uint64_t time_us if (compass.get_count() > 1) { const Vector3f &mag_field2 = compass.get_field(1); const Vector3f &mag_offsets2 = compass.get_offsets(1); - const Vector3f &mag_motor_offsets2 = compass.get_motor_offsets(1); + const Vector3f &mag_motor_offsets2 = compass.get_motor_offsets(1); struct log_Compass pkt2 = { LOG_PACKET_HEADER_INIT(LOG_COMPASS2_MSG), time_us : time_us, @@ -1722,7 +1722,7 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass, uint64_t time_us if (compass.get_count() > 2) { const Vector3f &mag_field3 = compass.get_field(2); const Vector3f &mag_offsets3 = compass.get_offsets(2); - const Vector3f &mag_motor_offsets3 = compass.get_motor_offsets(2); + const Vector3f &mag_motor_offsets3 = compass.get_motor_offsets(2); struct log_Compass pkt3 = { LOG_PACKET_HEADER_INIT(LOG_COMPASS3_MSG), time_us : time_us, @@ -1764,8 +1764,8 @@ void DataFlash_Class::Log_Write_ESC(void) if (_esc_status_sub == -1) { // subscribe to ORB topic on first call - _esc_status_sub = orb_subscribe(ORB_ID(esc_status)); - } + _esc_status_sub = orb_subscribe(ORB_ID(esc_status)); + } // check for new ESC status data bool esc_updated = false;