AP_Logger : correct spelling on comment

This commit is contained in:
RuffaloLavoisier 2022-07-10 20:11:25 +09:00 committed by Randy Mackay
parent 2172095e3f
commit 0e0c23a8e3
5 changed files with 9 additions and 9 deletions

View File

@ -351,7 +351,7 @@ public:
// number of blocks that have been dropped
uint32_t num_dropped(void) const;
// accesss to public parameters
// access to public parameters
void set_force_log_disarmed(bool force_logging) { _force_log_disarmed = force_logging; }
void set_long_log_persist(bool b) { _force_long_log_persist = b; }
bool log_while_disarmed(void) const;
@ -487,7 +487,7 @@ private:
bool _armed;
// state to help us not log unneccesary RCIN values:
// state to help us not log unnecessary RCIN values:
bool should_log_rcin2;
void Write_Compass_instance(uint64_t time_us, uint8_t mag_instance);

View File

@ -446,7 +446,7 @@ bool AP_Logger_Backend::ShouldLog(bool is_critical)
_front._last_mavlink_log_transfer_message_handled_ms != 0) {
if (AP_HAL::millis() - _front._last_mavlink_log_transfer_message_handled_ms < 10000) {
if (!_front.vehicle_is_armed()) {
// user is transfering files via mavlink
// user is transferring files via mavlink
return false;
}
} else {

View File

@ -831,7 +831,7 @@ bool AP_Logger_Block::io_thread_alive() const
/*
IO timer running on IO thread
The IO timer runs every 1ms or at 1Khz. The standard flash chip can write rougly 130Kb/s
The IO timer runs every 1ms or at 1Khz. The standard flash chip can write roughly 130Kb/s
so there is little point in trying to write more than 130 bytes - or 1 page (256 bytes).
The W25Q128FV datasheet gives tpp as typically 0.7ms yielding an absolute maximum rate of
365Kb/s or just over a page per cycle.

View File

@ -708,7 +708,7 @@ struct PACKED log_VER {
#define PID_MULTS "F----------"
// @LoggerMessage: ADSB
// @Description: Automatic Dependant Serveillance - Broadcast detected vehicle information
// @Description: Automatic Dependent Serveillance - Broadcast detected vehicle information
// @Field: TimeUS: Time since system startup
// @Field: ICAO_address: Transponder address
// @Field: Lat: Vehicle latitude
@ -1190,16 +1190,16 @@ struct PACKED log_VER {
// @Field: TimeUS: Time since system startup
// @Field: Name: script name
// @Field: Runtime: run time
// @Field: Total_mem: total memory useage
// @Field: Total_mem: total memory usage
// @Field: Run_mem: run memory usage
// @LoggerMessage: MOTB
// @Description: Motor mixer information
// @Field: TimeUS: Time since system startup
// @Field: LiftMax: Maximum motor compensation gain
// @Field: BatVolt: Ratio betwen detected battery voltage and maximum battery voltage
// @Field: BatVolt: Ratio between detected battery voltage and maximum battery voltage
// @Field: ThLimit: Throttle limit set due to battery current limitations
// @Field: ThrAvMx: Maximum average throttle that can be used to maintain attitude controll, derived from throttle mix params
// @Field: ThrAvMx: Maximum average throttle that can be used to maintain attitude control, derived from throttle mix params
// @Field: FailFlags: bit 0 motor failed, bit 1 motors balanced, should be 2 in normal flight
// messages for all boards

View File

@ -67,7 +67,7 @@ void AP_LoggerTest::setup(void)
// Test
hal.scheduler->delay(20);
// We start to write some info (sequentialy) starting from page 1
// We start to write some info (sequentially) starting from page 1
// This is similar to what we will do...
log_num = logger.find_last_log();
hal.console->printf("Using log number %u\n", log_num);