From cc2e156888b8c37efae69d14b460f7a1f924bac4 Mon Sep 17 00:00:00 2001 From: Mykhailo Kuznietsov Date: Wed, 11 Oct 2023 18:41:53 +1100 Subject: [PATCH] AP_HAL: Fix some typos Fixed some typos found in the code. --- libraries/AP_HAL/AP_HAL_Boards.h | 2 +- libraries/AP_HAL/AP_HAL_Namespace.h | 2 +- libraries/AP_HAL/CANIface.h | 6 +++--- libraries/AP_HAL/Device.cpp | 2 +- libraries/AP_HAL/GPIO.h | 2 +- libraries/AP_HAL/RCOutput.h | 2 +- libraries/AP_HAL/WSPIDevice.h | 2 +- libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp | 2 +- libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp | 6 +++--- libraries/AP_HAL/examples/Storage/Storage.cpp | 4 ++-- libraries/AP_HAL/utility/ftoa_engine.cpp | 2 +- libraries/AP_HAL/utility/srxl.cpp | 4 ++-- libraries/AP_HAL/utility/st24.cpp | 2 +- libraries/AP_HAL/utility/sumd.h | 2 +- 14 files changed, 20 insertions(+), 20 deletions(-) diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index bec7d2ea94..027b8f4a07 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -1,5 +1,5 @@ /** - * C preprocesor enumeration of the boards supported by the AP_HAL. + * C preprocessor enumeration of the boards supported by the AP_HAL. * This list exists so HAL_BOARD == HAL_BOARD_xxx preprocessor blocks * can be used to exclude HAL boards from the build when appropriate. * It's not an elegant solution but we can improve it in future. diff --git a/libraries/AP_HAL/AP_HAL_Namespace.h b/libraries/AP_HAL/AP_HAL_Namespace.h index 35a8124d61..b3e84314ed 100644 --- a/libraries/AP_HAL/AP_HAL_Namespace.h +++ b/libraries/AP_HAL/AP_HAL_Namespace.h @@ -51,7 +51,7 @@ namespace AP_HAL { /* Typdefs for function pointers (Procedure, Member Procedure) For member functions we use the FastDelegate delegates class - which allows us to encapculate a member function as a type + which allows us to encapsulate a member function as a type */ typedef void(*Proc)(void); FUNCTOR_TYPEDEF(MemberProc, void); diff --git a/libraries/AP_HAL/CANIface.h b/libraries/AP_HAL/CANIface.h index ad8a0ead35..06b4f7dffb 100644 --- a/libraries/AP_HAL/CANIface.h +++ b/libraries/AP_HAL/CANIface.h @@ -179,7 +179,7 @@ public: // fill read select with true if a frame is available in Rx buffer // fill write select with true if space is available in Tx buffer // Also waits for Rx or Tx event depending on read_select and write_select values - // passed to the method until timeout. Returns true if the Rx/Tx even occured + // passed to the method until timeout. Returns true if the Rx/Tx even occurred // while waiting, false if timedout virtual bool select(bool &read_select, bool &write_select, const CANFrame* const pending_tx, uint64_t timeout) @@ -192,11 +192,11 @@ public: return true; } - // Put frame in queue to be sent, return negative if error occured, 0 if no space, and 1 if successful + // Put frame in queue to be sent, return negative if error occurred, 0 if no space, and 1 if successful // must be called on child class virtual int16_t send(const CANFrame& frame, uint64_t tx_deadline, CanIOFlags flags); - // Non blocking receive frame that pops the frames received inside the buffer, return negative if error occured, + // Non blocking receive frame that pops the frames received inside the buffer, return negative if error occurred, // 0 if no frame available, 1 if successful // must be called on child class virtual int16_t receive(CANFrame& out_frame, uint64_t& out_ts_monotonic, CanIOFlags& out_flags); diff --git a/libraries/AP_HAL/Device.cpp b/libraries/AP_HAL/Device.cpp index beedb24221..8f80bf4bff 100644 --- a/libraries/AP_HAL/Device.cpp +++ b/libraries/AP_HAL/Device.cpp @@ -30,7 +30,7 @@ Periodically (say at 50Hz) you should then call check_next_register(). If that returns false then the sensor has had a corrupted register value. Marking the sensor as unhealthy is - approriate. The bad value will be corrected + appropiate. The bad value will be corrected */ /* diff --git a/libraries/AP_HAL/GPIO.h b/libraries/AP_HAL/GPIO.h index 5dbd753014..f32a1eb250 100644 --- a/libraries/AP_HAL/GPIO.h +++ b/libraries/AP_HAL/GPIO.h @@ -82,7 +82,7 @@ public: // ret indicates the functor must return void // pin is the pin which has triggered the interrupt // state is the new state of the pin - // timestamp is the time in microseconds the interrupt occured + // timestamp is the time in microseconds the interrupt occurred FUNCTOR_TYPEDEF(irq_handler_fn_t, void, uint8_t, bool, uint32_t); virtual bool attach_interrupt(uint8_t pin, irq_handler_fn_t fn, diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h index f4ffd25f5a..366b13963a 100644 --- a/libraries/AP_HAL/RCOutput.h +++ b/libraries/AP_HAL/RCOutput.h @@ -332,7 +332,7 @@ public: const static uint32_t ALL_CHANNELS = 255; /* - Send a dshot command, if command timout is 0 then 10 commands are sent + Send a dshot command, if command timeout is 0 then 10 commands are sent chan is the servo channel to send the command to */ virtual void send_dshot_command(uint8_t command, uint8_t chan = ALL_CHANNELS, uint32_t command_timeout_ms = 0, uint16_t repeat_count = 10, bool priority = false) {} diff --git a/libraries/AP_HAL/WSPIDevice.h b/libraries/AP_HAL/WSPIDevice.h index 08c93f4bfe..1b4c3a294c 100644 --- a/libraries/AP_HAL/WSPIDevice.h +++ b/libraries/AP_HAL/WSPIDevice.h @@ -143,7 +143,7 @@ public: virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override = 0; - // Set command header for upcomming transfer call(s) + // Set command header for upcoming transfer call(s) virtual void set_cmd_header(const CommandHeader& cmd_hdr) override = 0; virtual bool is_busy() = 0; diff --git a/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp b/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp index 33689a8fdd..1a177b13bb 100644 --- a/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp +++ b/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp @@ -22,7 +22,7 @@ void loop(); //declaration of the loop() function const AP_HAL::HAL& hal = AP_HAL::get_HAL(); //create a reference to AP_HAL::HAL object to get access to hardware specific functions. For more info see -AP_HAL::AnalogSource* chan; //delare a pointer to AnalogSource object. AnalogSource class can be found in : AP_HAL->AnalogIn.h +AP_HAL::AnalogSource* chan; //declare a pointer to AnalogSource object. AnalogSource class can be found in : AP_HAL->AnalogIn.h // the setup function runs once when the board powers up void setup(void) { diff --git a/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp b/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp index ff6e57cb65..ca8dd7b0b0 100644 --- a/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp +++ b/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp @@ -28,12 +28,12 @@ void drive(uint16_t hz_speed); class Menu_Commands { public: /* Menu commands to drive a SERVO type with - * repective PWM output freq defined by SERVO_HZ + * respective PWM output freq defined by SERVO_HZ */ int8_t menu_servo(uint8_t argc, const Menu::arg *argv); /* Menu commands to drive a ESC type with - * repective PWM output freq defined by ESC_HZ + * respective PWM output freq defined by ESC_HZ */ int8_t menu_esc(uint8_t argc, const Menu::arg *argv); }; @@ -45,7 +45,7 @@ Menu_Commands commands; static uint16_t pwm = 1500; static int8_t delta = 1; -/* Function to drive a RC output TYPE especified */ +/* Function to drive a RC output TYPE specified */ void drive(uint16_t hz_speed) { hal.rcout->set_freq(0xFF, hz_speed); diff --git a/libraries/AP_HAL/examples/Storage/Storage.cpp b/libraries/AP_HAL/examples/Storage/Storage.cpp index 171c423de5..e39fd83b1a 100644 --- a/libraries/AP_HAL/examples/Storage/Storage.cpp +++ b/libraries/AP_HAL/examples/Storage/Storage.cpp @@ -20,7 +20,7 @@ void setup(void) st->init(); /* - Calculate XOR of the full conent of memory + Calculate XOR of the full content of memory Do it by block of 8 bytes */ unsigned char buff[8], XOR_res = 0; @@ -35,7 +35,7 @@ void setup(void) /* print XORed result */ - hal.console->printf("XORed ememory: %u\r\n", (unsigned) XOR_res); + hal.console->printf("XORed memory: %u\r\n", (unsigned) XOR_res); } // In main loop do nothing diff --git a/libraries/AP_HAL/utility/ftoa_engine.cpp b/libraries/AP_HAL/utility/ftoa_engine.cpp index 384f32c2af..e280052908 100644 --- a/libraries/AP_HAL/utility/ftoa_engine.cpp +++ b/libraries/AP_HAL/utility/ftoa_engine.cpp @@ -131,7 +131,7 @@ int16_t ftoa_engine(float val, char *buf, uint8_t precision, uint8_t maxDecimals int64_t prod = (int64_t)frac * (int64_t)factorTable[idx]; // The expConvFactorTable are factor are correct iff the lower 3 exponent - // bits are 1 (=7). Else we need to compensate by divding frac. + // bits are 1 (=7). Else we need to compensate by dividing frac. // If the lower 3 bits are 7 we are right. // If the lower 3 bits are 6 we right-shift once // .. diff --git a/libraries/AP_HAL/utility/srxl.cpp b/libraries/AP_HAL/utility/srxl.cpp index 1023daa427..14b4e21197 100644 --- a/libraries/AP_HAL/utility/srxl.cpp +++ b/libraries/AP_HAL/utility/srxl.cpp @@ -17,7 +17,7 @@ Andrew Tridgell, September 2016 Co author: Roman Kirchner, September 2016 - - 2016.10.23: SRXL variant V1 sucessfully (Testbench and Pixhawk/MissionPlanner) tested with RX-9-DR M-LINK (SW v1.26) + - 2016.10.23: SRXL variant V1 successfully (Testbench and Pixhawk/MissionPlanner) tested with RX-9-DR M-LINK (SW v1.26) */ #include "srxl.h" @@ -49,7 +49,7 @@ #define SRXL_HEADER_V1 0xA1U /* Headerbyte for: Mpx SRXLv1 or XBUS Mode B */ #define SRXL_HEADER_V2 0xA2U /* Headerbyte for: Mpx SRXLv2 */ #define SRXL_HEADER_V5 0xA5U /* Headerbyte for: Spk AR7700 etc. */ -#define SRXL_HEADER_NOT_IMPL 0xFFU /* Headerbyte for non impemented srxl header*/ +#define SRXL_HEADER_NOT_IMPL 0xFFU /* Headerbyte for non implemented srxl header*/ diff --git a/libraries/AP_HAL/utility/st24.cpp b/libraries/AP_HAL/utility/st24.cpp index 80c8643d72..04cad55102 100644 --- a/libraries/AP_HAL/utility/st24.cpp +++ b/libraries/AP_HAL/utility/st24.cpp @@ -125,7 +125,7 @@ typedef struct { */ typedef struct { uint16_t t; ///< packet counter or clock - int32_t lat; ///< lattitude (degrees) +/- 90 deg + int32_t lat; ///< latitude (degrees) +/- 90 deg int32_t lon; ///< longitude (degrees) +/- 180 deg int32_t alt; ///< 0.01m resolution, altitude (meters) int16_t vx, vy, vz; ///< velocity 0.01m res, +/-320.00 North-East- Down diff --git a/libraries/AP_HAL/utility/sumd.h b/libraries/AP_HAL/utility/sumd.h index 22052a20ba..2c27a310a0 100644 --- a/libraries/AP_HAL/utility/sumd.h +++ b/libraries/AP_HAL/utility/sumd.h @@ -50,7 +50,7 @@ * * @param byte current char to read * @param rssi pointer to a byte where the RSSI value is written back to - * @param rx_count pointer to a byte where the receive count of packets signce last wireless frame is written back to + * @param rx_count pointer to a byte where the receive count of packets since last wireless frame is written back to * @param channels pointer to a datastructure of size max_chan_count where channel values (12 bit) are written back to * @param max_chan_count maximum channels to decode - if more channels are decoded, the last n are skipped and success (0) is returned * @return 0 for success (a decoded packet), 1 for no packet yet (accumulating), 2 for unknown packet, 3 for out of sync, 4 for checksum error