From e6eed4364860345de1dcab81ecfa2530e87aa00a Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 27 Jul 2022 14:33:16 +1000 Subject: [PATCH] Spelling errors (#19935) --- .../mixers/vtol_tailsitter_duo.main.mix | 2 +- .../mixers/vtol_tailsitter_duo_sat.main.mix | 2 +- Tools/mavlink_px4.py | 8 ++++---- Tools/px4moduledoc/markdownout.py | 11 +++++++---- Tools/setup/ubuntu.sh | 2 +- boards/nxp/fmuk66-e/src/spi.cpp | 2 +- boards/nxp/fmuk66-v3/src/spi.cpp | 2 +- .../nuttx-config/scripts/ocram-script.ld | 4 ++-- .../nuttx-config/scripts/script.ld | 2 +- boards/nxp/ucans32k146/src/spi.cpp | 2 +- .../mavros/mavros_offboard_attctl_test.py | 2 +- .../mavros/mavros_offboard_posctl_test.py | 2 +- .../mavros/mavros_offboard_yawrate_test.py | 2 +- msg/airspeed.msg | 2 +- msg/battery_status.msg | 2 +- msg/cellular_status.msg | 2 +- msg/differential_pressure.msg | 2 +- msg/estimator_event_flags.msg | 2 +- msg/estimator_innovations.msg | 4 ++-- msg/estimator_status_flags.msg | 2 +- msg/gps_dump.msg | 2 +- msg/input_rc.msg | 4 ++-- msg/iridiumsbd_status.msg | 2 +- msg/led_control.msg | 2 +- msg/rpm.msg | 2 +- msg/sensor_hygrometer.msg | 2 +- msg/takeoff_status.msg | 4 ++-- msg/tools/px_generate_uorb_topic_files.py | 2 +- msg/uwb_distance.msg | 4 ++-- msg/vehicle_command.msg | 2 +- msg/vehicle_odometry.msg | 2 +- .../include/px4_platform_common/board_common.h | 8 ++++---- .../common/include/px4_platform_common/log.h | 2 +- platforms/posix/src/px4/common/main.cpp | 2 +- src/drivers/batt_smbus/batt_smbus.cpp | 2 +- src/drivers/camera_trigger/camera_trigger.cpp | 2 +- src/drivers/cyphal/parameters.c | 2 +- .../afbrs50/Inc/platform/argus_print.h | 2 +- src/drivers/distance_sensor/pga460/pga460.cpp | 4 +++- src/drivers/distance_sensor/pga460/pga460.h | 4 ++-- .../ulanding_radar/AerotennaULanding.hpp | 2 +- src/drivers/drv_led.h | 2 +- src/drivers/imu/fxas21002c/FXAS21002C.cpp | 2 +- src/drivers/power_monitor/voxlpm/voxlpm.cpp | 2 +- src/drivers/roboclaw/roboclaw_main.cpp | 18 ++++++++++-------- src/drivers/rpm/pcf8583/parameters.c | 6 +++--- src/drivers/tap_esc/TAP_ESC.cpp | 11 ++++++++--- src/drivers/tap_esc/drv_tap_esc.h | 4 ++-- src/drivers/uavcan/sensors/battery.cpp | 4 ++-- .../uavcan/uavcan_drivers/kinetis/README.md | 6 +++--- src/drivers/uavcan/uavcan_params.c | 2 +- src/drivers/uwb/uwb_sr150/module.yaml | 2 +- src/drivers/uwb/uwb_sr150/uwb_sr150.cpp | 4 ++-- src/lib/airspeed/airspeed.cpp | 6 +++--- src/lib/airspeed/airspeed.h | 8 ++++---- src/lib/battery/module.yaml | 2 +- src/lib/drivers/smbus_sbs/SBS.hpp | 4 ++-- src/lib/led/led.h | 2 +- src/lib/parameters/flashparams/flashfs.c | 2 +- src/lib/parameters/px_process_params.py | 2 +- src/lib/systemlib/system_params.c | 4 ++-- src/lib/tunes/tune_definition.desc | 4 ++-- src/lib/tunes/tunes.h | 2 +- src/modules/commander/commander_params.c | 2 +- src/modules/ekf2/EKF/common.h | 4 ++-- src/modules/ekf2/EKF2.cpp | 2 +- src/modules/ekf2/EKF2.hpp | 2 +- src/modules/ekf2/ekf2_params.c | 10 +++++----- .../flight_mode_manager/FlightModeManager.cpp | 2 +- .../Templates/FlightTasks_generated.cpp.em | 2 +- .../tasks/Auto/FlightTaskAuto.hpp | 2 +- .../AutoFollowTarget/follow_target_params.c | 2 +- .../FlightTaskManualAltitude.hpp | 2 +- .../tasks/Orbit/FlightTaskOrbit.cpp | 2 +- .../fw_autotune_attitude_control_params.c | 2 +- .../fw_pos_control_l1_params.c | 4 ++-- .../CMSIS_5/CMSIS/DSP/Include/arm_math.h | 2 +- .../local_position_estimator/sensors/gps.cpp | 2 +- .../local_position_estimator/sensors/land.cpp | 2 +- src/modules/mavlink/mavlink_stream.h | 2 +- src/modules/mavlink/module.yaml | 2 +- .../mc_att_control/mc_att_control_params.c | 2 +- .../mc_autotune_attitude_control_params.c | 2 +- .../PositionControl/ControlMath.hpp | 2 +- .../mc_pos_control/mc_pos_control_params.c | 2 +- .../mc_rate_control/mc_rate_control_params.c | 4 ++-- src/modules/rc_update/params.c | 2 +- src/modules/sensors/sensor_params_flow.c | 2 +- src/modules/sensors/sensor_params_mag.c | 2 +- src/modules/sensors/vehicle_air_data/params.c | 2 +- src/modules/sih/sih.cpp | 2 +- src/modules/sih/sih.hpp | 6 +++--- src/modules/sih/sih_params.c | 18 +++++++++--------- .../temperature_calibration/polyfit.hpp | 4 ++-- src/modules/vtol_att_control/standard_params.c | 4 ++-- src/systemcmds/hardfault_log/hardfault_log.c | 8 ++++---- validation/module_schema.yaml | 2 +- 97 files changed, 170 insertions(+), 158 deletions(-) diff --git a/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo.main.mix b/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo.main.mix index 0a5c6efd37..ba3a277224 100644 --- a/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo.main.mix +++ b/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo.main.mix @@ -5,7 +5,7 @@ Tailsitter duo mixer This file defines a mixer for a generic duo tailsitter VTOL (eg TBS Caipirinha tailsitter edition). This vehicle has two motors in total, one attached to each wing. It also has two elevons which are located in the slipstream of the propellers. This mixer generates 4 PWM outputs -on the main PWM ouput port, two at 400Hz for the motors, and two at 50Hz for the +on the main PWM output port, two at 400Hz for the motors, and two at 50Hz for the elevon servos. Channels 1-4 are configured to run at 400Hz, while channels 5-8 run at the default rate of 50Hz. Note that channels 3 and 4 are assigned but not used. diff --git a/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo_sat.main.mix b/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo_sat.main.mix index 2a9e3197c1..76b116e534 100644 --- a/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo_sat.main.mix +++ b/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo_sat.main.mix @@ -4,7 +4,7 @@ Tailsitter duo mixer This file defines a mixer for a generic duo tailsitter VTOL (eg TBS Caipirinha tailsitter edition). This vehicle has two motors in total, one attached to each wing. It also has two elevons which are located in the slipstream of the propellers. This mixer generates 4 PWM outputs -on the main PWM ouput port, two at 400Hz for the motors, and two at 50Hz for the +on the main PWM output port, two at 400Hz for the motors, and two at 50Hz for the elevon servos. Channels 1-4 are configured to run at 400Hz, while channels 5-8 run at the default rate of 50Hz. Note that channels 3 and 4 are assigned but not used. diff --git a/Tools/mavlink_px4.py b/Tools/mavlink_px4.py index b9f17cb5e7..96cc4c80a4 100644 --- a/Tools/mavlink_px4.py +++ b/Tools/mavlink_px4.py @@ -3019,7 +3019,7 @@ class MAVLink(object): time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) press_abs : Absolute pressure (hectopascal) (float) press_diff : Differential pressure 1 (hectopascal) (float) - temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + temperature : Temperature measurement (0.01 degrees Celsius) (int16_t) ''' msg = MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) @@ -3035,7 +3035,7 @@ class MAVLink(object): time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) press_abs : Absolute pressure (hectopascal) (float) press_diff : Differential pressure 1 (hectopascal) (float) - temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + temperature : Temperature measurement (0.01 degrees Celsius) (int16_t) ''' return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) @@ -4879,7 +4879,7 @@ class MAVLink(object): abs_pressure : Absolute pressure in millibar (float) diff_pressure : Differential pressure in millibar (float) pressure_alt : Altitude calculated from pressure (float) - temperature : Temperature in degrees celsius (float) + temperature : Temperature in degrees Celsius (float) fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) ''' @@ -4904,7 +4904,7 @@ class MAVLink(object): abs_pressure : Absolute pressure in millibar (float) diff_pressure : Differential pressure in millibar (float) pressure_alt : Altitude calculated from pressure (float) - temperature : Temperature in degrees celsius (float) + temperature : Temperature in degrees Celsius (float) fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) ''' diff --git a/Tools/px4moduledoc/markdownout.py b/Tools/px4moduledoc/markdownout.py index 9896c091b4..131993410c 100644 --- a/Tools/px4moduledoc/markdownout.py +++ b/Tools/px4moduledoc/markdownout.py @@ -14,12 +14,14 @@ class MarkdownOutput(): result = """ # Modules & Commands Reference -The following pages document the PX4 modules, drivers and commands. They -describe the provided functionality, high-level implementation overview and how + +The following pages document the PX4 modules, drivers and commands. +They describe the provided functionality, high-level implementation overview and how to use the command-line interface. -> **Note** **This is auto-generated from the source code** and contains the -> most recent modules documentation. +:::note +**This is auto-generated from the source code** and contains the most recent modules documentation. +::: It is not a complete list and NuttX provides some additional commands as well (such as `free`). Use `help` on the console to get a list of all @@ -29,6 +31,7 @@ Since this is generated from source, errors must be reported/fixed in the [PX4-Autopilot](https://github.com/PX4/PX4-Autopilot) repository. The documentation pages can be generated by running the following command from the root of the PX4-Autopilot directory: + ``` make module_documentation ``` diff --git a/Tools/setup/ubuntu.sh b/Tools/setup/ubuntu.sh index 25c12cb170..8077444b3a 100755 --- a/Tools/setup/ubuntu.sh +++ b/Tools/setup/ubuntu.sh @@ -104,7 +104,7 @@ sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends i echo echo "Installing PX4 Python3 dependencies" if [ -n "$VIRTUAL_ENV" ]; then - # virtual envrionments don't allow --user option + # virtual environments don't allow --user option python -m pip install -r ${DIR}/requirements.txt else # older versions of Ubuntu require --user option diff --git a/boards/nxp/fmuk66-e/src/spi.cpp b/boards/nxp/fmuk66-e/src/spi.cpp index ba6669f8b9..efdd6c484d 100644 --- a/boards/nxp/fmuk66-e/src/spi.cpp +++ b/boards/nxp/fmuk66-e/src/spi.cpp @@ -110,7 +110,7 @@ __EXPORT void board_spi_reset(int ms, int bus_mask) VDD_3V3_SENSORS_EN(true); up_mdelay(2); - /* Restore all the CS to ouputs inactive */ + /* Restore all the CS to outputs inactive */ for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) { if (px4_spi_buses[bus].bus == PX4_BUS_NUMBER_TO_PX4(1)) { diff --git a/boards/nxp/fmuk66-v3/src/spi.cpp b/boards/nxp/fmuk66-v3/src/spi.cpp index 65a562f32b..ccf25dfd04 100644 --- a/boards/nxp/fmuk66-v3/src/spi.cpp +++ b/boards/nxp/fmuk66-v3/src/spi.cpp @@ -124,7 +124,7 @@ __EXPORT void board_spi_reset(int ms, int bus_mask) VDD_3V3_SENSORS_EN(true); up_mdelay(2); - /* Restore all the CS to ouputs inactive */ + /* Restore all the CS to outputs inactive */ for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) { if (px4_spi_buses[bus].bus == PX4_BUS_NUMBER_TO_PX4(1)) { diff --git a/boards/nxp/fmurt1062-v1/nuttx-config/scripts/ocram-script.ld b/boards/nxp/fmurt1062-v1/nuttx-config/scripts/ocram-script.ld index 845fc66526..274071f4aa 100644 --- a/boards/nxp/fmurt1062-v1/nuttx-config/scripts/ocram-script.ld +++ b/boards/nxp/fmurt1062-v1/nuttx-config/scripts/ocram-script.ld @@ -35,7 +35,7 @@ ****************************************************************************/ /* The FMURT1062 has 8MiB of QSPI FLASH beginning at address, - * 0x0060:0000, Upto 512Kb of DTCM RAM beginning at 0x2000:0000, and 1MiB OCRAM + * 0x0060:0000, Up to 512Kb of DTCM RAM beginning at 0x2000:0000, and 1MiB OCRAM * beginning at 0x2020:0000. Neither DTCM or SDRAM are used in this * configuration. * @@ -43,7 +43,7 @@ * 256Kib to OCRRAM, 128Kib ITCM and 128Kib DTCM. * This can be changed by using a dcd by minipulating * IOMUX GPR16 and GPR17. - * The configuartion we will use is 384Kib to OCRRAM, 0Kib ITCM and + * The configuration we will use is 384Kib to OCRRAM, 0Kib ITCM and * 128Kib DTCM. * * This is the OCRAM inker script. diff --git a/boards/nxp/fmurt1062-v1/nuttx-config/scripts/script.ld b/boards/nxp/fmurt1062-v1/nuttx-config/scripts/script.ld index 685dd3ed82..eac08ed305 100644 --- a/boards/nxp/fmurt1062-v1/nuttx-config/scripts/script.ld +++ b/boards/nxp/fmurt1062-v1/nuttx-config/scripts/script.ld @@ -35,7 +35,7 @@ ****************************************************************************/ /* The FMURT1062 has 8MiB of QSPI FLASH beginning at address, - * 0x0060:0000, Upto 512Kb of DTCM RAM beginning at 0x2000:0000, and 1MiB OCRAM + * 0x0060:0000, Up to 512Kb of DTCM RAM beginning at 0x2000:0000, and 1MiB OCRAM * beginning at 0x2020:0000. Neither DTCM or SDRAM are used in this * configuratin. */ diff --git a/boards/nxp/ucans32k146/src/spi.cpp b/boards/nxp/ucans32k146/src/spi.cpp index 1e5708d259..7ed6b8194f 100644 --- a/boards/nxp/ucans32k146/src/spi.cpp +++ b/boards/nxp/ucans32k146/src/spi.cpp @@ -93,7 +93,7 @@ __EXPORT void board_spi_reset(int ms, int bus_mask) } } - /* Restore all the CS to ouputs inactive */ + /* Restore all the CS to outputs inactive */ for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) { if (px4_spi_buses[bus].bus == PX4_BUS_NUMBER_TO_PX4(1)) { for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) { diff --git a/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py b/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py index 4fa626aaa5..5e791be7b5 100755 --- a/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py +++ b/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py @@ -68,7 +68,7 @@ class MavrosOffboardAttctlTest(MavrosTestCommon): self.att_setpoint_pub = rospy.Publisher( 'mavros/setpoint_raw/attitude', AttitudeTarget, queue_size=1) - # send setpoints in seperate thread to better prevent failsafe + # send setpoints in separate thread to better prevent failsafe self.att_thread = Thread(target=self.send_att, args=()) self.att_thread.daemon = True self.att_thread.start() diff --git a/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py b/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py index 836b0da3b6..81c6835a2b 100755 --- a/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py +++ b/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py @@ -73,7 +73,7 @@ class MavrosOffboardPosctlTest(MavrosTestCommon): self.pos_setpoint_pub = rospy.Publisher( 'mavros/setpoint_position/local', PoseStamped, queue_size=1) - # send setpoints in seperate thread to better prevent failsafe + # send setpoints in separate thread to better prevent failsafe self.pos_thread = Thread(target=self.send_pos, args=()) self.pos_thread.daemon = True self.pos_thread.start() diff --git a/integrationtests/python_src/px4_it/mavros/mavros_offboard_yawrate_test.py b/integrationtests/python_src/px4_it/mavros/mavros_offboard_yawrate_test.py index 315d7b373b..f40c45b17f 100755 --- a/integrationtests/python_src/px4_it/mavros/mavros_offboard_yawrate_test.py +++ b/integrationtests/python_src/px4_it/mavros/mavros_offboard_yawrate_test.py @@ -66,7 +66,7 @@ class MavrosOffboardYawrateTest(MavrosTestCommon): self.att_setpoint_pub = rospy.Publisher( 'mavros/setpoint_raw/attitude', AttitudeTarget, queue_size=1) - # send setpoints in seperate thread to better prevent failsafe + # send setpoints in separate thread to better prevent failsafe self.att_thread = Thread(target=self.send_att, args=()) self.att_thread.daemon = True self.att_thread.start() diff --git a/msg/airspeed.msg b/msg/airspeed.msg index 9dd5f18ae8..aaed7b72ca 100644 --- a/msg/airspeed.msg +++ b/msg/airspeed.msg @@ -5,6 +5,6 @@ float32 indicated_airspeed_m_s # indicated airspeed in m/s float32 true_airspeed_m_s # true filtered airspeed in m/s -float32 air_temperature_celsius # air temperature in degrees celsius, -1000 if unknown +float32 air_temperature_celsius # air temperature in degrees Celsius, -1000 if unknown float32 confidence # confidence value from 0 to 1 for this sensor diff --git a/msg/battery_status.msg b/msg/battery_status.msg index 376506d423..65845b57ae 100644 --- a/msg/battery_status.msg +++ b/msg/battery_status.msg @@ -21,7 +21,7 @@ uint16 capacity # actual capacity of the battery uint16 cycle_count # number of discharge cycles the battery has experienced uint16 average_time_to_empty # predicted remaining battery capacity based on the average rate of discharge in min uint16 serial_number # serial number of the battery pack -uint16 manufacture_date # manufacture date, part of serial number of the battery pack. formated as: Day + Month×32 + (Year–1980)×512 +uint16 manufacture_date # manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 uint16 state_of_health # state of health. FullChargeCapacity/DesignCapacity, 0-100%. uint16 max_error # max error, expected margin of error in % in the state-of-charge calculation with a range of 1 to 100% uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed. diff --git a/msg/cellular_status.msg b/msg/cellular_status.msg index 42186c0ff0..5a1c8bac7a 100644 --- a/msg/cellular_status.msg +++ b/msg/cellular_status.msg @@ -17,7 +17,7 @@ uint8 CELLULAR_STATUS_FLAG_CONNECTED=12 # One or more packet data bearers is ac uint8 CELLULAR_NETWORK_FAILED_REASON_NONE=0 # No error uint8 CELLULAR_NETWORK_FAILED_REASON_UNKNOWN=1 # Error state is unknown uint8 CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING=2 # SIM is required for the modem but missing -uint8 CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR=3 # SIM is available, but not usuable for connection +uint8 CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR=3 # SIM is available, but not usable for connection uint16 status # Status bitmap 1: Roaming is active uint8 failure_reason #Failure reason when status in in CELLUAR_STATUS_FAILED diff --git a/msg/differential_pressure.msg b/msg/differential_pressure.msg index b561b2271b..0cdf1e4cce 100644 --- a/msg/differential_pressure.msg +++ b/msg/differential_pressure.msg @@ -5,6 +5,6 @@ uint32 device_id # unique device ID for the sensor that does float32 differential_pressure_pa # differential pressure reading in Pascals (may be negative) -float32 temperature # Temperature provided by sensor in celcius, NAN if unknown +float32 temperature # Temperature provided by sensor in degrees Celsius, NAN if unknown uint32 error_count # Number of errors detected by driver diff --git a/msg/estimator_event_flags.msg b/msg/estimator_event_flags.msg index 62efa0a0da..3baea13361 100644 --- a/msg/estimator_event_flags.msg +++ b/msg/estimator_event_flags.msg @@ -30,7 +30,7 @@ bool gps_data_stopped_using_alternate # 3 - true when the gps data has stoppe bool height_sensor_timeout # 4 - true when the height sensor has not been used to correct the state estimates for a significant time period bool stopping_navigation # 5 - true when the filter has insufficient data to estimate velocity and position and is falling back to an attitude, height and height rate mode of operation bool invalid_accel_bias_cov_reset # 6 - true when the filter has detected bad acceerometer bias state esitmstes and has reset the corresponding covariance matrix elements -bool bad_yaw_using_gps_course # 7 - true when the fiter has detected an invalid yaw esitmate and has reset the yaw angle to the GPS ground course +bool bad_yaw_using_gps_course # 7 - true when the filter has detected an invalid yaw estimate and has reset the yaw angle to the GPS ground course bool stopping_mag_use # 8 - true when the filter has detected bad magnetometer data and is stopping further use of the magnetomer data bool vision_data_stopped # 9 - true when the vision system data has stopped for a significant time period bool emergency_yaw_reset_mag_stopped # 10 - true when the filter has detected bad magnetometer data, has reset the yaw to anothter source of data and has stopped further use of the magnetomer data diff --git a/msg/estimator_innovations.msg b/msg/estimator_innovations.msg index 56a741b37d..75327b3ab0 100644 --- a/msg/estimator_innovations.msg +++ b/msg/estimator_innovations.msg @@ -18,8 +18,8 @@ float32 rng_vpos # range sensor height innovation (m) and innovation variance (m float32 baro_vpos # barometer height innovation (m) and innovation variance (m**2) # Auxiliary velocity -float32[2] aux_hvel # horizontal auxiliar velocity innovation from landing target measurement (m/sec) and innovation variance ((m/sec)**2) -float32 aux_vvel # vertical auxiliar velocity innovation from landing target measurement (m/sec) and innovation variance ((m/sec)**2) +float32[2] aux_hvel # horizontal auxiliary velocity innovation from landing target measurement (m/sec) and innovation variance ((m/sec)**2) +float32 aux_vvel # vertical auxiliary velocity innovation from landing target measurement (m/sec) and innovation variance ((m/sec)**2) # Optical flow float32[2] flow # flow innvoation (rad/sec) and innovation variance ((rad/sec)**2) diff --git a/msg/estimator_status_flags.msg b/msg/estimator_status_flags.msg index 5176db9af5..f86f85c1a7 100644 --- a/msg/estimator_status_flags.msg +++ b/msg/estimator_status_flags.msg @@ -9,7 +9,7 @@ bool cs_yaw_align # 1 - true if the filter yaw alignment is complet bool cs_gps # 2 - true if GPS measurement fusion is intended bool cs_opt_flow # 3 - true if optical flow measurements fusion is intended bool cs_mag_hdg # 4 - true if a simple magnetic yaw heading fusion is intended -bool cs_mag_3d # 5 - true if 3-axis magnetometer measurement fusion is inteded +bool cs_mag_3d # 5 - true if 3-axis magnetometer measurement fusion is intended bool cs_mag_dec # 6 - true if synthetic magnetic declination measurements fusion is intended bool cs_in_air # 7 - true when the vehicle is airborne bool cs_wind # 8 - true when wind velocity is being estimated diff --git a/msg/gps_dump.msg b/msg/gps_dump.msg index d9fbb8ab80..3aa1313aa6 100644 --- a/msg/gps_dump.msg +++ b/msg/gps_dump.msg @@ -3,7 +3,7 @@ uint64 timestamp # time since system start (microseconds) -uint8 instance # Instance of GNSS reciever +uint8 instance # Instance of GNSS receiver uint8 len # length of data, MSB bit set = message to the gps device, # clear = message from the device diff --git a/msg/input_rc.msg b/msg/input_rc.msg index d26c31ea0f..68addbfdf1 100644 --- a/msg/input_rc.msg +++ b/msg/input_rc.msg @@ -29,8 +29,8 @@ int32 rssi # receive signal strength indicator (RSSI): < 0: Undefined, 0: no bool rc_failsafe # explicit failsafe flag: true on TX failure or TX out of range , false otherwise. Only the true state is reliable, as there are some (PPM) receivers on the market going into failsafe without telling us explicitly. bool rc_lost # RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise. True usually means that the receiver has been disconnected, but can also indicate a radio link loss on "stupid" systems. Will remain false, if a RX with failsafe option continues to transmit frames after a link loss. -uint16 rc_lost_frame_count # Number of lost RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike funtionality. -uint16 rc_total_frame_count # Number of total RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike funtionality. +uint16 rc_lost_frame_count # Number of lost RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike functionality. +uint16 rc_total_frame_count # Number of total RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike functionality. uint16 rc_ppm_frame_length # Length of a single PPM frame. Zero for non-PPM systems uint8 input_source # Input source diff --git a/msg/iridiumsbd_status.msg b/msg/iridiumsbd_status.msg index 75b167ffa4..39e3de780a 100644 --- a/msg/iridiumsbd_status.msg +++ b/msg/iridiumsbd_status.msg @@ -4,7 +4,7 @@ uint16 tx_buf_write_index # current size of the tx buffer uint16 rx_buf_read_index # the rx buffer is parsed up to that index uint16 rx_buf_end_index # current size of the rx buffer uint16 failed_sbd_sessions # number of failed sbd sessions -uint16 successful_sbd_sessions # number of successfull sbd sessions +uint16 successful_sbd_sessions # number of successful sbd sessions uint16 num_tx_buf_reset # number of times the tx buffer was reset uint8 signal_quality # current signal quality, 0 is no signal, 5 the best uint8 state # current state of the driver, see the satcom_state of IridiumSBD.h for the definition diff --git a/msg/led_control.msg b/msg/led_control.msg index 5bf968219d..4be5cc1ceb 100644 --- a/msg/led_control.msg +++ b/msg/led_control.msg @@ -24,7 +24,7 @@ uint8 MODE_BLINK_FAST = 5 uint8 MODE_BREATHE = 6 # continuously increase & decrease brightness (solid color if driver does not support it) uint8 MODE_FLASH = 7 # two fast blinks (on/off) with timing as in MODE_BLINK_FAST and then off for a while -uint8 MAX_PRIORITY = 2 # maxium priority (minimum is 0) +uint8 MAX_PRIORITY = 2 # maximum priority (minimum is 0) uint8 led_mask # bitmask which LED(s) to control, set to 0xff for all diff --git a/msg/rpm.msg b/msg/rpm.msg index 9ddb7d92f2..baab7c6a67 100644 --- a/msg/rpm.msg +++ b/msg/rpm.msg @@ -1,4 +1,4 @@ uint64 timestamp # time since system start (microseconds) float32 indicated_frequency_rpm # indicated rotor Frequency in Revolution per minute -float32 estimated_accurancy_rpm # estimated accurancy in Revolution per minute +float32 estimated_accurancy_rpm # estimated accuracy in Revolution per minute diff --git a/msg/sensor_hygrometer.msg b/msg/sensor_hygrometer.msg index 400f560bd6..490a7402a2 100755 --- a/msg/sensor_hygrometer.msg +++ b/msg/sensor_hygrometer.msg @@ -3,6 +3,6 @@ uint64 timestamp_sample uint32 device_id # unique device ID for the sensor that does not change between power cycles -float32 temperature # Temperature provided by sensor (Celcius) +float32 temperature # Temperature provided by sensor (Celsius) float32 humidity # Humidity provided by sensor diff --git a/msg/takeoff_status.msg b/msg/takeoff_status.msg index ed2f906d77..4cc49d5094 100644 --- a/msg/takeoff_status.msg +++ b/msg/takeoff_status.msg @@ -1,4 +1,4 @@ -# Status of the takeoff state machine currently just availble for multicopters +# Status of the takeoff state machine currently just available for multicopters uint64 timestamp # time since system start (microseconds) @@ -11,4 +11,4 @@ uint8 TAKEOFF_STATE_FLIGHT = 5 uint8 takeoff_state -float32 tilt_limit # limited tilt feasability during takeoff, contains maximum tilt otherwise +float32 tilt_limit # limited tilt feasibility during takeoff, contains maximum tilt otherwise diff --git a/msg/tools/px_generate_uorb_topic_files.py b/msg/tools/px_generate_uorb_topic_files.py index e7894bd92b..2a038f381c 100755 --- a/msg/tools/px_generate_uorb_topic_files.py +++ b/msg/tools/px_generate_uorb_topic_files.py @@ -413,7 +413,7 @@ def convert_dir(format_idx, inputdir, outputdir, package, templatedir): def copy_changed(inputdir, outputdir, prefix='', quiet=False): """ Copies files from inputdir to outputdir if they don't exist in - ouputdir or if their content changed + outputdir or if their content changed """ # Make sure output directory exists: diff --git a/msg/uwb_distance.msg b/msg/uwb_distance.msg index 8f1f7105b5..e496a72396 100644 --- a/msg/uwb_distance.msg +++ b/msg/uwb_distance.msg @@ -8,8 +8,8 @@ uint32 sessionid # UWB SessionID uint32 time_offset # Time between Ranging Rounds in ms uint16 status # status feedback # -uint16[12] anchor_distance # distance in cm to each UWB Anchor (UWB Device wich takes part in Ranging) +uint16[12] anchor_distance # distance in cm to each UWB Anchor (UWB Device which takes part in Ranging) bool[12] nlos # Visual line of sight yes/no -float32[12] aoafirst # Angle of arrival of first incomming RX msg +float32[12] aoafirst # Angle of arrival of first incoming RX msg float32[3] position # Position of the Landing point in relation to the Drone (x,y,z in Meters NED) diff --git a/msg/vehicle_command.msg b/msg/vehicle_command.msg index 954b4a0644..9d47ebaf7d 100644 --- a/msg/vehicle_command.msg +++ b/msg/vehicle_command.msg @@ -99,7 +99,7 @@ uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibrati # PX4 vehicle commands (beyond 16 bit mavlink commands) uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX) -uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS co-ordinates of the vehicle local origin (0,0,0) position. |Empty|Empty|Empty|Empty|Latitude|Longitude|Altitude| +uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Empty|Empty|Empty|Empty|Latitude|Longitude|Altitude| uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization | uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | diff --git a/msg/vehicle_odometry.msg b/msg/vehicle_odometry.msg index 5f597f4d96..27cfe93c4d 100644 --- a/msg/vehicle_odometry.msg +++ b/msg/vehicle_odometry.msg @@ -32,7 +32,7 @@ float32 y # East position float32 z # Down position # Orientation quaternion. First value NaN if invalid/unknown -float32[4] q # Quaternion rotation from FRD body frame to refernce frame +float32[4] q # Quaternion rotation from FRD body frame to reference frame float32[4] q_offset # Quaternion rotation from odometry reference frame to navigation frame # Row-major representation of 6x6 pose cross-covariance matrix URT. diff --git a/platforms/common/include/px4_platform_common/board_common.h b/platforms/common/include/px4_platform_common/board_common.h index a246d73dcb..f819842df3 100644 --- a/platforms/common/include/px4_platform_common/board_common.h +++ b/platforms/common/include/px4_platform_common/board_common.h @@ -854,7 +854,7 @@ __EXPORT void board_get_uuid32(uuid_uint32_t uuid_words); // DEPRICATED use boar * * Input Parameters: * format_buffer - A pointer to a bufferer of at least PX4_CPU_UUID_WORD32_FORMAT_SIZE - * that will contain a 0 terminated string formated as described + * that will contain a 0 terminated string formatted as described * the format string and optional separator. * size - The size of the buffer (should be atleaset PX4_CPU_UUID_WORD32_FORMAT_SIZE) * format - The fort mat specifier for the hex digit see CPU_UUID_FORMAT @@ -870,7 +870,7 @@ __EXPORT void board_get_uuid32(uuid_uint32_t uuid_words); // DEPRICATED use boar * 3238333641203833355110 * * Returned Value: - * The format buffer is populated with a 0 terminated string formated as described. + * The format buffer is populated with a 0 terminated string formatted as described. * Zero (OK) is returned on success; * ************************************************************************************/ @@ -907,7 +907,7 @@ int board_get_mfguid(mfguid_t mfgid); * * Input Parameters: * format_buffer - A pointer to a bufferer of at least PX4_CPU_MFGUID_FORMAT_SIZE - * that will contain a 0 terminated string formated as 0 prefixed + * that will contain a 0 terminated string formatted as 0 prefixed * lowercase hex. 2 charaters per digit of the mfguid_t. * * Returned Value: @@ -964,7 +964,7 @@ int board_get_px4_guid(px4_guid_t guid); * manufactures Unique ID or define BOARD_OVERRIDE_PX4_GUID * * Input Parameters: - * format_buffer - A buffer to receive the 0 terminated formated px4 + * format_buffer - A buffer to receive the 0 terminated formatted px4 * guid string. * size - Size of the buffer provided. Normally this would * be PX4_GUID_FORMAT_SIZE. diff --git a/platforms/common/include/px4_platform_common/log.h b/platforms/common/include/px4_platform_common/log.h index 7b36fcd50f..3a781ca411 100644 --- a/platforms/common/include/px4_platform_common/log.h +++ b/platforms/common/include/px4_platform_common/log.h @@ -33,7 +33,7 @@ /** * @file log.h - * Platform dependant logging/debug implementation + * Platform dependent logging/debug implementation */ #pragma once diff --git a/platforms/posix/src/px4/common/main.cpp b/platforms/posix/src/px4/common/main.cpp index 901ffdd722..1ea83b5d16 100644 --- a/platforms/posix/src/px4/common/main.cpp +++ b/platforms/posix/src/px4/common/main.cpp @@ -541,7 +541,7 @@ int run_startup_script(const std::string &commands_file, const std::string &abso void wait_to_exit() { while (!_exit_requested) { - // needs to be a regular sleep not dependant on lockstep (not px4_usleep) + // needs to be a regular sleep not dependent on lockstep (not px4_usleep) usleep(100000); } } diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp index 1dfac055b4..8c5b1c7364 100644 --- a/src/drivers/batt_smbus/batt_smbus.cpp +++ b/src/drivers/batt_smbus/batt_smbus.cpp @@ -523,7 +523,7 @@ $ batt_smbus -X write_flash 19069 2 27 0 PRINT_MODULE_USAGE_COMMAND_DESCR("man_info", "Prints manufacturer info."); PRINT_MODULE_USAGE_COMMAND_DESCR("unseal", "Unseals the devices flash memory to enable write_flash commands."); - PRINT_MODULE_USAGE_COMMAND_DESCR("seal", "Seals the devices flash memory to disbale write_flash commands."); + PRINT_MODULE_USAGE_COMMAND_DESCR("seal", "Seals the devices flash memory to disable write_flash commands."); PRINT_MODULE_USAGE_COMMAND_DESCR("suspend", "Suspends the driver from rescheduling the cycle."); PRINT_MODULE_USAGE_COMMAND_DESCR("resume", "Resumes the driver from suspension."); diff --git a/src/drivers/camera_trigger/camera_trigger.cpp b/src/drivers/camera_trigger/camera_trigger.cpp index 86b48cfacd..c03e63aca4 100644 --- a/src/drivers/camera_trigger/camera_trigger.cpp +++ b/src/drivers/camera_trigger/camera_trigger.cpp @@ -35,7 +35,7 @@ * @file camera_trigger.cpp * * External camera-IMU synchronisation and triggering, and support for - * camera manipulation using PWM signals over FMU auxillary pins. + * camera manipulation using PWM signals over FMU auxiliary pins. * * @author Mohammed Kabir * @author Kelly Steich diff --git a/src/drivers/cyphal/parameters.c b/src/drivers/cyphal/parameters.c index d9f8ea9b38..becd33fc42 100644 --- a/src/drivers/cyphal/parameters.c +++ b/src/drivers/cyphal/parameters.c @@ -123,7 +123,7 @@ PARAM_DEFINE_INT32(UCAN1_BMS_BS_SUB, -1); PARAM_DEFINE_INT32(UCAN1_BMS_BP_SUB, -1); /** - * Cyphal leagcy battery port ID. + * Cyphal legacy battery port ID. * * @min -1 * @max 6143 diff --git a/src/drivers/distance_sensor/broadcom/afbrs50/Inc/platform/argus_print.h b/src/drivers/distance_sensor/broadcom/afbrs50/Inc/platform/argus_print.h index d53b2df35a..0ca49f858c 100644 --- a/src/drivers/distance_sensor/broadcom/afbrs50/Inc/platform/argus_print.h +++ b/src/drivers/distance_sensor/broadcom/afbrs50/Inc/platform/argus_print.h @@ -54,7 +54,7 @@ #include "api/argus_def.h" /*!*************************************************************************** - * @brief A printf-like function to print formated data to an debugging interface. + * @brief A printf-like function to print formatted data to an debugging interface. * * @details Writes the C string pointed by fmt_t to an output. If format * includes format specifiers (subsequences beginning with %), the diff --git a/src/drivers/distance_sensor/pga460/pga460.cpp b/src/drivers/distance_sensor/pga460/pga460.cpp index 1765cde777..a94f7c5b57 100644 --- a/src/drivers/distance_sensor/pga460/pga460.cpp +++ b/src/drivers/distance_sensor/pga460/pga460.cpp @@ -482,10 +482,12 @@ int PGA460::print_usage(const char *reason) PRINT_MODULE_DESCRIPTION( R"DESCR_STR( ### Description + Ultrasonic range finder driver that handles the communication with the device and publishes the distance via uORB. ### Implementation -This driver is implented as a NuttX task. This Implementation was chosen due to the need for polling on a message + +This driver is implemented as a NuttX task. This Implementation was chosen due to the need for polling on a message via UART, which is not supported in the work_queue. This driver continuously takes range measurements while it is running. A simple algorithm to detect false readings is implemented at the driver levelin an attemptto improve the quality of data that is being published. The driver will not publish data at all if it deems the sensor data diff --git a/src/drivers/distance_sensor/pga460/pga460.h b/src/drivers/distance_sensor/pga460/pga460.h index c7fa0f23c8..8783dcc947 100644 --- a/src/drivers/distance_sensor/pga460/pga460.h +++ b/src/drivers/distance_sensor/pga460/pga460.h @@ -286,7 +286,7 @@ public: int read_eeprom(); /** - * @brief Writes the user defined paramaters to device EEPROM. + * @brief Writes the user defined parameters to device EEPROM. * @return Returns true if the EEPROM was successfully written to. */ int write_eeprom(); @@ -341,7 +341,7 @@ private: int initialize_device_settings(); /** - * @brief Writes the user defined paramaters to device register map. + * @brief Writes the user defined parameters to device register map. * @return Returns true if the thresholds were successfully written. */ int initialize_thresholds(); diff --git a/src/drivers/distance_sensor/ulanding_radar/AerotennaULanding.hpp b/src/drivers/distance_sensor/ulanding_radar/AerotennaULanding.hpp index 719121e548..dc133254bf 100644 --- a/src/drivers/distance_sensor/ulanding_radar/AerotennaULanding.hpp +++ b/src/drivers/distance_sensor/ulanding_radar/AerotennaULanding.hpp @@ -71,7 +71,7 @@ using namespace time_literals; /** * Assume standard deviation to be equal to sensor resolution. - * Static bench tests have shown that the sensor ouput does + * Static bench tests have shown that the sensor output does * not vary if the unit is not moved. */ #define SENS_VARIANCE 0.045f * 0.045f diff --git a/src/drivers/drv_led.h b/src/drivers/drv_led.h index d00d102f01..0aaf59e0ec 100644 --- a/src/drivers/drv_led.h +++ b/src/drivers/drv_led.h @@ -44,7 +44,7 @@ #include -// allow the board to override the number (or maxiumum number) of LED's it has +// allow the board to override the number (or maximum number) of LED's it has #ifndef BOARD_MAX_LEDS #define BOARD_MAX_LEDS 4 #endif diff --git a/src/drivers/imu/fxas21002c/FXAS21002C.cpp b/src/drivers/imu/fxas21002c/FXAS21002C.cpp index 9f755f4d8d..9bc41e903b 100644 --- a/src/drivers/imu/fxas21002c/FXAS21002C.cpp +++ b/src/drivers/imu/fxas21002c/FXAS21002C.cpp @@ -39,7 +39,7 @@ #define FXAS21002C_MAX_RATE 800 #define FXAS21002C_DEFAULT_RATE FXAS21002C_MAX_RATE #define FXAS21002C_DEFAULT_RANGE_DPS 2000 -#define FXAS21002C_DEFAULT_ONCHIP_FILTER_FREQ 64 // ODR dependant +#define FXAS21002C_DEFAULT_ONCHIP_FILTER_FREQ 64 // ODR dependent /* we set the timer interrupt to run a bit faster than the desired diff --git a/src/drivers/power_monitor/voxlpm/voxlpm.cpp b/src/drivers/power_monitor/voxlpm/voxlpm.cpp index 91270538b3..2627dcebbb 100644 --- a/src/drivers/power_monitor/voxlpm/voxlpm.cpp +++ b/src/drivers/power_monitor/voxlpm/voxlpm.cpp @@ -96,7 +96,7 @@ VOXLPM::init() ret = init_ina231(); } else { - PX4_ERR("Unkown device address"); + PX4_ERR("Unknown device address"); ret = PX4_ERROR; } diff --git a/src/drivers/roboclaw/roboclaw_main.cpp b/src/drivers/roboclaw/roboclaw_main.cpp index 44c9ca8d6b..66f5d03101 100644 --- a/src/drivers/roboclaw/roboclaw_main.cpp +++ b/src/drivers/roboclaw/roboclaw_main.cpp @@ -85,8 +85,8 @@ static void usage() This driver communicates over UART with the [Roboclaw motor driver](http://downloads.basicmicro.com/docs/roboclaw_user_manual.pdf). It performs two tasks: - - Control the motors based on the `actuator_controls_0` UOrb topic. - - Read the wheel encoders and publish the raw data in the `wheel_encoders` UOrb topic +- Control the motors based on the `actuator_controls_0` UOrb topic. +- Read the wheel encoders and publish the raw data in the `wheel_encoders` UOrb topic In order to use this driver, the Roboclaw should be put into Packet Serial mode (see the linked documentation), and your flight controller's UART port should be connected to the Roboclaw as shown in the documentation. For Pixhawk 4, @@ -109,16 +109,18 @@ the driver terminates immediately. The command to start this driver is: - $ roboclaw start +``` +$ roboclaw start +``` -`` is the name of the UART port. On the Pixhawk 4, this is `/dev/ttyS3`. -`` is te baud rate. +- `` is the name of the UART port. On the Pixhawk 4, this is `/dev/ttyS3`. +- `` is the baud rate. All available commands are: - - `$ roboclaw start ` - - `$ roboclaw status` - - `$ roboclaw stop` +- `$ roboclaw start ` +- `$ roboclaw status` +- `$ roboclaw stop` )DESCR_STR"); } diff --git a/src/drivers/rpm/pcf8583/parameters.c b/src/drivers/rpm/pcf8583/parameters.c index bf2d41b6fd..f34ea4ae6d 100644 --- a/src/drivers/rpm/pcf8583/parameters.c +++ b/src/drivers/rpm/pcf8583/parameters.c @@ -60,9 +60,9 @@ PARAM_DEFINE_INT32(PCF8583_POOL, 1000000); /** * PCF8583 rotorfreq (i2c) pulse reset value * - * Internal device counter is reset to 0 when overun this value, - * counter is able to store upto 6 digits - * reset of counter takes some time - measurement with reset has worse accurancy. + * Internal device counter is reset to 0 when overrun this value, + * counter is able to store up to 6 digits + * reset of counter takes some time - measurement with reset has worse accuracy. * 0 means reset counter after every measurement. * * @reboot_required true diff --git a/src/drivers/tap_esc/TAP_ESC.cpp b/src/drivers/tap_esc/TAP_ESC.cpp index 80fd32806f..829f57b230 100644 --- a/src/drivers/tap_esc/TAP_ESC.cpp +++ b/src/drivers/tap_esc/TAP_ESC.cpp @@ -511,17 +511,22 @@ int TAP_ESC::print_usage(const char *reason) PRINT_MODULE_DESCRIPTION( R"DESCR_STR( ### Description + This module controls the TAP_ESC hardware via UART. It listens on the actuator_controls topics, does the mixing and writes the PWM outputs. ### Implementation -Currently the module is implementd as a threaded version only, meaning that it + +Currently the module is implemented as a threaded version only, meaning that it runs in its own thread instead of on the work queue. ### Example -The module is typically started with: -tap_esc start -d /dev/ttyS2 -n <1-8> +The module is typically started with: + +``` +tap_esc start -d /dev/ttyS2 -n <1-8> +``` )DESCR_STR"); PRINT_MODULE_USAGE_NAME("tap_esc", "driver"); diff --git a/src/drivers/tap_esc/drv_tap_esc.h b/src/drivers/tap_esc/drv_tap_esc.h index 041bff1854..f34cf01453 100644 --- a/src/drivers/tap_esc/drv_tap_esc.h +++ b/src/drivers/tap_esc/drv_tap_esc.h @@ -107,7 +107,7 @@ typedef struct { uint16_t current; // 0.0 - 200.0 A #endif #if defined(ESC_HAVE_TEMPERATURE_SENSOR) - uint8_t temperature; // 0 - 256 degree celsius + uint8_t temperature; // 0 - 256 degrees Celsius #endif } RunInfoRepsonse; /****** Run ***********/ @@ -232,7 +232,7 @@ typedef struct { * * speed: -32767 - 32767 rpm * - * temperature: 0 - 256 celsius degree (if available) + * temperature: 0 - 256 degrees Celsius (if available) * voltage: 0.00 - 100.00 V (if available) * current: 0.0 - 200.0 A (if available) */ diff --git a/src/drivers/uavcan/sensors/battery.cpp b/src/drivers/uavcan/sensors/battery.cpp index 9a2b22746c..b8d6f098ea 100644 --- a/src/drivers/uavcan/sensors/battery.cpp +++ b/src/drivers/uavcan/sensors/battery.cpp @@ -115,7 +115,7 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure= 1, or -1 if unknown - _battery_status[instance].temperature = msg.temperature + CONSTANTS_ABSOLUTE_NULL_CELSIUS; // Kelvin to Celcius + _battery_status[instance].temperature = msg.temperature + CONSTANTS_ABSOLUTE_NULL_CELSIUS; // Kelvin to Celsius // _battery_status[instance].cell_count = msg.; _battery_status[instance].connected = true; _battery_status[instance].source = msg.status_flags & uavcan::equipment::power::BatteryInfo::STATUS_FLAG_IN_USE; @@ -238,7 +238,7 @@ UavcanBatteryBridge::filterData(const uavcan::ReceivedDataStructuregetBatteryStatus(); - _battery_status[instance].temperature = msg.temperature + CONSTANTS_ABSOLUTE_NULL_CELSIUS; // Kelvin to Celcius + _battery_status[instance].temperature = msg.temperature + CONSTANTS_ABSOLUTE_NULL_CELSIUS; // Kelvin to Celsius _battery_status[instance].serial_number = msg.model_instance_id; _battery_status[instance].id = msg.getSrcNodeID().get(); // overwrite zeroed index from _battery diff --git a/src/drivers/uavcan/uavcan_drivers/kinetis/README.md b/src/drivers/uavcan/uavcan_drivers/kinetis/README.md index 45ee8828f4..5d04cdd2b0 100644 --- a/src/drivers/uavcan/uavcan_drivers/kinetis/README.md +++ b/src/drivers/uavcan/uavcan_drivers/kinetis/README.md @@ -18,9 +18,9 @@ and the following commandline defines: |UAVCAN_KINETIS_TIMER_NUMBER | - {0..3} Sets the Periodic Interrupt Timer (PITn) channel | Things that could be improved: -1. Build time command line configuartion of Mailbox/FIFO and filters -2. Build time command line configuartion clock source - - Curently the driver use `const uavcan::uint8_t CLOCKSEL = 0;` To Select OSCERCLK +1. Build time command line configuration of Mailbox/FIFO and filters +2. Build time command line configuration clock source + - Currently the driver use `const uavcan::uint8_t CLOCKSEL = 0;` To Select OSCERCLK 3. Dynamic filter disable. There are no filter enable bits on the FlexCAN, just the number of Filters can be set. But this changes the memory map. So the configuration show below has been chosen. diff --git a/src/drivers/uavcan/uavcan_params.c b/src/drivers/uavcan/uavcan_params.c index 0766f52ed1..2ece897d99 100644 --- a/src/drivers/uavcan/uavcan_params.c +++ b/src/drivers/uavcan/uavcan_params.c @@ -318,7 +318,7 @@ PARAM_DEFINE_INT32(UAVCAN_SUB_HYGRO, 0); /** * subscription ICE * - * Enable UAVCAN internal combusion engine (ICE) subscription. + * Enable UAVCAN internal combustion engine (ICE) subscription. * uavcan::equipment::ice::reciprocating::Status * * @boolean diff --git a/src/drivers/uwb/uwb_sr150/module.yaml b/src/drivers/uwb/uwb_sr150/module.yaml index 3442e138be..68085187bf 100644 --- a/src/drivers/uwb/uwb_sr150/module.yaml +++ b/src/drivers/uwb/uwb_sr150/module.yaml @@ -13,7 +13,7 @@ parameters: UWB_INIT_OFF_X: description: short: UWB sensor X offset in body frame - long: UWB sensor positioning in relation to Drone in NED. X offset. A Positiv offset results in a Position o + long: UWB sensor positioning in relation to Drone in NED. X offset. A Positive offset results in a Position o type: float unit: m decimal: 2 diff --git a/src/drivers/uwb/uwb_sr150/uwb_sr150.cpp b/src/drivers/uwb/uwb_sr150/uwb_sr150.cpp index 128cf415bc..6fcce6ea92 100644 --- a/src/drivers/uwb/uwb_sr150/uwb_sr150.cpp +++ b/src/drivers/uwb/uwb_sr150/uwb_sr150.cpp @@ -394,7 +394,7 @@ int UWB_SR150::distance() break; case UWB_LIN_DEP_FOR_THREE: - PX4_INFO("UWB localization: linear dependant with 3 Anchors"); + PX4_INFO("UWB localization: linear dependent with 3 Anchors"); break; case UWB_ANC_ON_ONE_LEVEL: @@ -402,7 +402,7 @@ int UWB_SR150::distance() break; case UWB_LIN_DEP_FOR_FOUR: - PX4_INFO("UWB localization: linear dependant with four or more Anchors"); + PX4_INFO("UWB localization: linear dependent with four or more Anchors"); break; case UWB_RANK_ZERO: diff --git a/src/lib/airspeed/airspeed.cpp b/src/lib/airspeed/airspeed.cpp index f3ed3506b6..bd47f0930f 100644 --- a/src/lib/airspeed/airspeed.cpp +++ b/src/lib/airspeed/airspeed.cpp @@ -49,7 +49,7 @@ float calc_IAS_corrected(enum AIRSPEED_COMPENSATION_MODEL pmodel, enum AIRSPEED_ float tube_len, float tube_dia_mm, float differential_pressure, float pressure_ambient, float temperature_celsius) { if (!PX4_ISFINITE(temperature_celsius)) { - temperature_celsius = 15.f; // ICAO Standard Atmosphere 15 degrees celcius + temperature_celsius = 15.f; // ICAO Standard Atmosphere 15 degrees Celsius } // air density in kg/m3 @@ -189,7 +189,7 @@ float calc_IAS(float differential_pressure) float calc_TAS_from_CAS(float speed_calibrated, float pressure_ambient, float temperature_celsius) { if (!PX4_ISFINITE(temperature_celsius)) { - temperature_celsius = 15.f; // ICAO Standard Atmosphere 15 degrees celcius + temperature_celsius = 15.f; // ICAO Standard Atmosphere 15 degrees Celsius } return speed_calibrated * sqrtf(CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C / get_air_density(pressure_ambient, @@ -222,7 +222,7 @@ float calc_TAS(float total_pressure, float static_pressure, float temperature_ce float get_air_density(float static_pressure, float temperature_celsius) { if (!PX4_ISFINITE(temperature_celsius)) { - temperature_celsius = 15.f; // ICAO Standard Atmosphere 15 degrees celcius + temperature_celsius = 15.f; // ICAO Standard Atmosphere 15 degrees Celsius } return static_pressure / (CONSTANTS_AIR_GAS_CONST * (temperature_celsius - CONSTANTS_ABSOLUTE_NULL_CELSIUS)); diff --git a/src/lib/airspeed/airspeed.h b/src/lib/airspeed/airspeed.h index 6b53a8710c..74d273054e 100644 --- a/src/lib/airspeed/airspeed.h +++ b/src/lib/airspeed/airspeed.h @@ -92,7 +92,7 @@ __EXPORT float calc_IAS(float differential_pressure); * * @param speed_equivalent current calibrated airspeed * @param pressure_ambient pressure at the side of the tube/airplane - * @param temperature_celsius air temperature in degrees celcius + * @param temperature_celsius air temperature in degrees Celsius * @return TAS in m/s */ __EXPORT float calc_TAS_from_CAS(float speed_indicated, float pressure_ambient, @@ -116,7 +116,7 @@ __EXPORT float calc_CAS_from_IAS(float speed_indicated, float scale); * * @param total_pressure pressure inside the pitot/prandtl tube * @param static_pressure pressure at the side of the tube/airplane - * @param temperature_celsius air temperature in degrees celcius + * @param temperature_celsius air temperature in degrees Celsius * @return true airspeed in m/s */ __EXPORT float calc_TAS(float total_pressure, float static_pressure, float temperature_celsius); @@ -125,7 +125,7 @@ __EXPORT float calc_TAS(float total_pressure, float static_pressure, float tempe * Calculates air density. * * @param static_pressure ambient pressure in millibar -* @param temperature_celcius air / ambient temperature in celcius +* @param temperature_celcius air / ambient temperature in Celsius */ __EXPORT float get_air_density(float static_pressure, float temperature_celsius); @@ -135,7 +135,7 @@ __EXPORT float get_air_density(float static_pressure, float temperature_celsius) * * @param speed_true current true airspeed * @param pressure_ambient pressure at the side of the tube/airplane - * @param temperature_celsius air temperature in degrees celcius + * @param temperature_celsius air temperature in degrees Celsius * @return CAS in m/s */ __EXPORT float calc_CAS_from_TAS(float speed_true, float pressure_ambient, diff --git a/src/lib/battery/module.yaml b/src/lib/battery/module.yaml index 1478cb56af..4cbf1da675 100644 --- a/src/lib/battery/module.yaml +++ b/src/lib/battery/module.yaml @@ -43,7 +43,7 @@ parameters: description: short: Voltage drop per cell on full throttle long: | - This implicitely defines the internal resistance + This implicitly defines the internal resistance to maximum current ratio for battery 1 and assumes linearity. A good value to use is the difference between the 5C and 20-25C load. Not used if BAT${i}_R_INTERNAL is diff --git a/src/lib/drivers/smbus_sbs/SBS.hpp b/src/lib/drivers/smbus_sbs/SBS.hpp index de636d4cf5..176928923a 100644 --- a/src/lib/drivers/smbus_sbs/SBS.hpp +++ b/src/lib/drivers/smbus_sbs/SBS.hpp @@ -69,7 +69,7 @@ public: int populate_smbus_data(battery_status_s &msg); - virtual void RunImpl(); // Can be overriden by derived implimentation + virtual void RunImpl(); // Can be overridden by derived implimentation virtual void custom_method(const BusCLIArguments &cli) = 0; //Has be overriden by derived implimentation @@ -81,7 +81,7 @@ public: /** * @brief Read info from battery on startup. - * @return Returns PX4_OK on success, PX4_ERROR on failure. Can be overriden by derived implimentation + * @return Returns PX4_OK on success, PX4_ERROR on failure. Can be overridden by derived implimentation */ virtual int get_startup_info(); diff --git a/src/lib/led/led.h b/src/lib/led/led.h index 48a0cb17dc..23550b495d 100644 --- a/src/lib/led/led.h +++ b/src/lib/led/led.h @@ -76,7 +76,7 @@ public: } /** - * get maxium time between two consecutive calls to update() in us. + * get maximum time between two consecutive calls to update() in us. */ int maximum_update_interval() const { diff --git a/src/lib/parameters/flashparams/flashfs.c b/src/lib/parameters/flashparams/flashfs.c index da11614a9e..ed1f318b28 100644 --- a/src/lib/parameters/flashparams/flashfs.c +++ b/src/lib/parameters/flashparams/flashfs.c @@ -1048,7 +1048,7 @@ int parameter_flashfs_init(sector_descriptor_t *fconfig, uint8_t *buffer, uint16 flash_entry_header_t *pf = find_entry(parameters_token); - /* No paramaters */ + /* No parameters */ if (pf == NULL) { size_t total_size = size + sizeof(flash_entry_header_t); diff --git a/src/lib/parameters/px_process_params.py b/src/lib/parameters/px_process_params.py index 0c777bb1d4..59f041c680 100755 --- a/src/lib/parameters/px_process_params.py +++ b/src/lib/parameters/px_process_params.py @@ -33,7 +33,7 @@ ############################################################################ # -# PX4 paramaters processor (main executable file) +# PX4 parameters processor (main executable file) # # This tool scans the PX4 source code for declarations of tunable parameters # and outputs the list in various formats. diff --git a/src/lib/systemlib/system_params.c b/src/lib/systemlib/system_params.c index 1ae3cf9ef0..95305d20e1 100644 --- a/src/lib/systemlib/system_params.c +++ b/src/lib/systemlib/system_params.c @@ -146,7 +146,7 @@ PARAM_DEFINE_INT32(SYS_CAL_BARO, 0); * Required temperature rise during thermal calibration * * A temperature increase greater than this value is required during calibration. - * Calibration will complete for each sensor when the temperature increase above the starting temeprature exceeds the value set by SYS_CAL_TDEL. + * Calibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL. * If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit. * * @unit celcius @@ -223,7 +223,7 @@ PARAM_DEFINE_INT32(SYS_HAS_BARO, 1); * * If set to the number of distance sensors, the preflight check will check * for their presence and valid data publication. Disable with 0 if no distance - * sensor present or to disbale the preflight check. + * sensor present or to disable the preflight check. * * @reboot_required true * diff --git a/src/lib/tunes/tune_definition.desc b/src/lib/tunes/tune_definition.desc index 7c09be81fc..c615a16c09 100644 --- a/src/lib/tunes/tune_definition.desc +++ b/src/lib/tunes/tune_definition.desc @@ -83,8 +83,8 @@ */ -// ordinal name tune interruptable* hint -// * Repeated tunes should always be defined as interruptable, if not an explict 'tone_control stop' is needed +// ordinal name tune interruptible* hint +// * Repeated tunes should always be defined as interruptible, if not an explicit 'tone_control stop' is needed PX4_DEFINE_TUNE(0, CUSTOM, "", true /* empty to align with the index */) PX4_DEFINE_TUNE(1, STARTUP, "MFT240L8 O4aO5dc O4aO5dc O4aO5dc L16dcdcdcdc", true /* startup tune */) PX4_DEFINE_TUNE(2, ERROR_TUNE, "MBT200a8a8a8PaaaP", true /* ERROR tone */) diff --git a/src/lib/tunes/tunes.h b/src/lib/tunes/tunes.h index 7ab240fde5..5134407354 100644 --- a/src/lib/tunes/tunes.h +++ b/src/lib/tunes/tunes.h @@ -92,7 +92,7 @@ public: * or the tune being already played is a repeated tune. * @param tune_control struct containig the uORB message * @return return ControlResult::InvalidTune if the default tune does not exist, - * ControlResult::WouldInterrupt if tune was already playing and not interruptable, + * ControlResult::WouldInterrupt if tune was already playing and not interruptible, * ControlResult::AlreadyPlaying if same tune was already playing, * ControlResult::Success if new tune was set. */ diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 3daa5ddc69..c8b379adb8 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -1063,7 +1063,7 @@ PARAM_DEFINE_FLOAT(COM_WIND_WARN, -1.f); * the time since takeoff is above this value. It is not possible to resume the * mission or switch to any mode other than RTL or Land. * - * Set a nagative value to disable. + * Set a negative value to disable. * * * @unit s diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 7ce494560c..4d7f66cf68 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -479,7 +479,7 @@ union filter_control_status_u { uint32_t gps : 1; ///< 2 - true if GPS measurement fusion is intended uint32_t opt_flow : 1; ///< 3 - true if optical flow measurements fusion is intended uint32_t mag_hdg : 1; ///< 4 - true if a simple magnetic yaw heading fusion is intended - uint32_t mag_3D : 1; ///< 5 - true if 3-axis magnetometer measurement fusion is inteded + uint32_t mag_3D : 1; ///< 5 - true if 3-axis magnetometer measurement fusion is intended uint32_t mag_dec : 1; ///< 6 - true if synthetic magnetic declination measurements fusion is intended uint32_t in_air : 1; ///< 7 - true when the vehicle is airborne uint32_t wind : 1; ///< 8 - true when wind velocity is being estimated @@ -571,7 +571,7 @@ union warning_event_status_u { bool height_sensor_timeout : 1; ///< 4 - true when the height sensor has not been used to correct the state estimates for a significant time period bool stopping_navigation : 1; ///< 5 - true when the filter has insufficient data to estimate velocity and position and is falling back to an attitude, height and height rate mode of operation bool invalid_accel_bias_cov_reset : 1; ///< 6 - true when the filter has detected bad acceerometer bias state estimates and has reset the corresponding covariance matrix elements - bool bad_yaw_using_gps_course : 1; ///< 7 - true when the fiter has detected an invalid yaw esitmate and has reset the yaw angle to the GPS ground course + bool bad_yaw_using_gps_course : 1; ///< 7 - true when the filter has detected an invalid yaw estimate and has reset the yaw angle to the GPS ground course bool stopping_mag_use : 1; ///< 8 - true when the filter has detected bad magnetometer data and is stopping further use of the magnetomer data bool vision_data_stopped : 1; ///< 9 - true when the vision system data has stopped for a significant time period bool emergency_yaw_reset_mag_stopped : 1; ///< 10 - true when the filter has detected bad magnetometer data, has reset the yaw to anothter source of data and has stopped further use of the magnetomer data diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 80e82e9bf2..c373db0004 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1539,7 +1539,7 @@ void EKF2::UpdateAirspeedSample(ekf2_timestamps_s &ekf2_timestamps) void EKF2::UpdateAuxVelSample(ekf2_timestamps_s &ekf2_timestamps) { - // EKF auxillary velocity sample + // EKF auxiliary velocity sample // - use the landing target pose estimate as another source of velocity data const unsigned last_generation = _landing_target_pose_sub.get_last_generation(); landing_target_pose_s landing_target_pose; diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index aa730eb1fb..77931a5e02 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -358,7 +358,7 @@ private: (ParamExtFloat) _param_ekf2_ev_delay, ///< off-board vision measurement delay relative to the IMU (mSec) (ParamExtFloat) - _param_ekf2_avel_delay, ///< auxillary velocity measurement delay relative to the IMU (mSec) + _param_ekf2_avel_delay, ///< auxiliary velocity measurement delay relative to the IMU (mSec) (ParamExtFloat) _param_ekf2_gyr_noise, ///< IMU angular rate noise used for covariance prediction (rad/sec) diff --git a/src/modules/ekf2/ekf2_params.c b/src/modules/ekf2/ekf2_params.c index 28b245e304..8a4fddcc8b 100644 --- a/src/modules/ekf2/ekf2_params.c +++ b/src/modules/ekf2/ekf2_params.c @@ -139,7 +139,7 @@ PARAM_DEFINE_FLOAT(EKF2_ASP_DELAY, 100); PARAM_DEFINE_FLOAT(EKF2_EV_DELAY, 0); /** - * Auxillary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements + * Auxiliary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements * * @group EKF2 * @min 0 @@ -676,7 +676,7 @@ PARAM_DEFINE_INT32(EKF2_NOAID_TOUT, 5000000); PARAM_DEFINE_FLOAT(EKF2_RNG_NOISE, 0.1f); /** - * Range finder range dependant noise scaler. + * Range finder range dependent noise scaler. * * Specifies the increase in range finder noise with range. * @@ -702,7 +702,7 @@ PARAM_DEFINE_FLOAT(EKF2_RNG_GATE, 5.0f); /** * Expected range finder reading when on ground. * - * If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is avilable at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground. + * If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground. * * @group EKF2 * @min 0.01 @@ -1374,7 +1374,7 @@ PARAM_DEFINE_INT32(EKF2_MAG_CHECK, 1); * For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated * using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter * will only have an effect if the global position of the drone is known. - * For 3D mag fusion the magnetometer Z measurement will simply be ingored instead of fusing the synthetic value. + * For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value. * * @group EKF2 * @boolean @@ -1384,7 +1384,7 @@ PARAM_DEFINE_INT32(EKF2_SYNT_MAG_Z, 0); /** * Default value of true airspeed used in EKF-GSF AHRS calculation. * - * If no airspeed measurements are avalable, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes. + * If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes. * * @group EKF2 * @min 0.0 diff --git a/src/modules/flight_mode_manager/FlightModeManager.cpp b/src/modules/flight_mode_manager/FlightModeManager.cpp index a63fdd969f..101da19251 100644 --- a/src/modules/flight_mode_manager/FlightModeManager.cpp +++ b/src/modules/flight_mode_manager/FlightModeManager.cpp @@ -385,7 +385,7 @@ void FlightModeManager::handleCommand() // check what command it is FlightTaskIndex desired_task = switchVehicleCommand(command.command); - // ignore all unkown commands + // ignore all unknown commands if (desired_task != FlightTaskIndex::None && _vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) { // switch to the commanded task diff --git a/src/modules/flight_mode_manager/Templates/FlightTasks_generated.cpp.em b/src/modules/flight_mode_manager/Templates/FlightTasks_generated.cpp.em index f7522afdbe..16cedf4056 100644 --- a/src/modules/flight_mode_manager/Templates/FlightTasks_generated.cpp.em +++ b/src/modules/flight_mode_manager/Templates/FlightTasks_generated.cpp.em @@ -91,7 +91,7 @@ upperCase = lambda s: s[:].upper() if s else '' @[end for]@ @[end if]@ - // ignore all unkown commands + // ignore all unknown commands default : return FlightTaskIndex::None; } } diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp index c650eb0e95..f4a0867798 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp @@ -197,7 +197,7 @@ private: _triplet_next_wp; /**< next triplet from navigator which may differ from the intenal one (_next_wp) depending on the vehicle state.*/ matrix::Vector3f _closest_pt; /**< closest point to the vehicle position on the line previous - target */ - hrt_abstime _time_last_cruise_speed_override{0}; ///< timestamp the cruise speed was last time overriden using DO_CHANGE_SPEED + hrt_abstime _time_last_cruise_speed_override{0}; ///< timestamp the cruise speed was last time overridden using DO_CHANGE_SPEED MapProjection _reference_position{}; /**< Class used to project lat/lon setpoint into local frame. */ float _reference_altitude{NAN}; /**< Altitude relative to ground. */ diff --git a/src/modules/flight_mode_manager/tasks/AutoFollowTarget/follow_target_params.c b/src/modules/flight_mode_manager/tasks/AutoFollowTarget/follow_target_params.c index 2336d323e0..f81210f09a 100644 --- a/src/modules/flight_mode_manager/tasks/AutoFollowTarget/follow_target_params.c +++ b/src/modules/flight_mode_manager/tasks/AutoFollowTarget/follow_target_params.c @@ -99,7 +99,7 @@ PARAM_DEFINE_FLOAT(FLW_TGT_FA, 180.0f); * to prevent terrain collisions due to GPS inaccuracies of the target. * * @value 0 2D Tracking: Maintain constant altitude relative to home and track XY position only - * @value 1 2D + Terrain: Mantain constant altitude relative to terrain below and track XY position + * @value 1 2D + Terrain: Maintain constant altitude relative to terrain below and track XY position * @value 2 3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless) * @group Follow target */ diff --git a/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.hpp b/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.hpp index 1a9706f5fb..7f520798b6 100644 --- a/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.hpp +++ b/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.hpp @@ -85,7 +85,7 @@ protected: (ParamFloat) _param_mpc_man_y_tau, (ParamFloat) _param_mpc_man_tilt_max, /**< maximum tilt allowed for manual flight */ (ParamFloat) _param_mpc_land_alt1, /**< altitude at which to start downwards slowdown */ - (ParamFloat) _param_mpc_land_alt2, /**< altitude below wich to land with land speed */ + (ParamFloat) _param_mpc_land_alt2, /**< altitude below which to land with land speed */ (ParamFloat) _param_mpc_land_speed, /**< desired downwards speed when approaching the ground */ (ParamFloat) diff --git a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp index 09457fbabb..249f59708a 100644 --- a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp +++ b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp @@ -52,7 +52,7 @@ FlightTaskOrbit::FlightTaskOrbit() bool FlightTaskOrbit::applyCommandParameters(const vehicle_command_s &command) { bool ret = true; - // save previous velocity and roatation direction + // save previous velocity and rotation direction bool new_is_clockwise = _orbit_velocity > 0; float new_radius = _orbit_radius; float new_absolute_velocity = fabsf(_orbit_velocity); diff --git a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control_params.c b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control_params.c index 3d7b938357..93421a0fcc 100644 --- a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control_params.c +++ b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control_params.c @@ -46,7 +46,7 @@ * and can be dangerous. Only activate if you know what you * are doing, and in a safe environment. * - * Any motion of the remote stick will abord the signal + * Any motion of the remote stick will abort the signal * injection and reset this parameter * Best is to perform the identification in position or * hold mode. diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index 25f39040a3..3daa747c19 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -76,7 +76,7 @@ PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f); /** * L1 controller roll slew rate limit. * - * The maxium change in roll angle setpoint per second. + * The maximum change in roll angle setpoint per second. * * @unit deg/s * @min 0 @@ -826,7 +826,7 @@ PARAM_DEFINE_FLOAT(FW_T_TAS_TC, 5.0f); PARAM_DEFINE_FLOAT(FW_GND_SPD_MIN, 5.0f); /** - * RC stick configuraton fixed-wing. + * RC stick configuration fixed-wing. * * Set RC/joystick configuration for fixed-wing manual position and altitude controlled flight. * diff --git a/src/modules/gyro_fft/CMSIS_5/CMSIS/DSP/Include/arm_math.h b/src/modules/gyro_fft/CMSIS_5/CMSIS/DSP/Include/arm_math.h index 48bee62cd9..316db4a067 100644 --- a/src/modules/gyro_fft/CMSIS_5/CMSIS/DSP/Include/arm_math.h +++ b/src/modules/gyro_fft/CMSIS_5/CMSIS/DSP/Include/arm_math.h @@ -7916,7 +7916,7 @@ typedef struct const float32_t *dualCoefficients; /**< Dual coefficients */ const float32_t *supportVectors; /**< Support vectors */ const int32_t *classes; /**< The two SVM classes */ - float32_t coef0; /**< Independant constant */ + float32_t coef0; /**< Independent constant */ float32_t gamma; /**< Gamma factor */ } arm_svm_sigmoid_instance_f32; diff --git a/src/modules/local_position_estimator/sensors/gps.cpp b/src/modules/local_position_estimator/sensors/gps.cpp index 6995d44b13..acfef88097 100644 --- a/src/modules/local_position_estimator/sensors/gps.cpp +++ b/src/modules/local_position_estimator/sensors/gps.cpp @@ -210,7 +210,7 @@ void BlockLocalPositionEstimator::gpsCorrect() // fault detection float beta = (r.transpose() * (S_I * r))(0, 0); - // artifically increase beta threshhold to prevent fault during landing + // artificially increase beta threshhold to prevent fault during landing float beta_thresh = 1e2f; if (beta / BETA_TABLE[n_y_gps] > beta_thresh) { diff --git a/src/modules/local_position_estimator/sensors/land.cpp b/src/modules/local_position_estimator/sensors/land.cpp index abb2fb3c28..1d945234f7 100644 --- a/src/modules/local_position_estimator/sensors/land.cpp +++ b/src/modules/local_position_estimator/sensors/land.cpp @@ -67,7 +67,7 @@ void BlockLocalPositionEstimator::landCorrect() // fault detection float beta = (r.transpose() * (S_I * r))(0, 0); - // artifically increase beta threshhold to prevent fault during landing + // artificially increase beta threshhold to prevent fault during landing float beta_thresh = 1e2f; if (beta / BETA_TABLE[n_y_land] > beta_thresh) { diff --git a/src/modules/mavlink/mavlink_stream.h b/src/modules/mavlink/mavlink_stream.h index 4bb4c111c3..67034e0c93 100644 --- a/src/modules/mavlink/mavlink_stream.h +++ b/src/modules/mavlink/mavlink_stream.h @@ -129,7 +129,7 @@ protected: virtual bool send() = 0; /** - * Function to collect/update data for the streams at a high rate independant of + * Function to collect/update data for the streams at a high rate independent of * actual stream rate. * * This function is called at every iteration of the mavlink module. diff --git a/src/modules/mavlink/module.yaml b/src/modules/mavlink/module.yaml index 10da1b8883..73a2c828c6 100644 --- a/src/modules/mavlink/module.yaml +++ b/src/modules/mavlink/module.yaml @@ -167,7 +167,7 @@ parameters: short: Enable serial flow control for instance ${i} long: | This is used to force flow control on or off for the the mavlink - instance. By default it is auto detected. Use when auto detction fails. + instance. By default it is auto detected. Use when auto detection fails. type: enum values: diff --git a/src/modules/mc_att_control/mc_att_control_params.c b/src/modules/mc_att_control/mc_att_control_params.c index f45e856942..1d7fe08bc4 100644 --- a/src/modules/mc_att_control/mc_att_control_params.c +++ b/src/modules/mc_att_control/mc_att_control_params.c @@ -86,7 +86,7 @@ PARAM_DEFINE_FLOAT(MC_YAW_P, 2.8f); * in yaw compared to the other axes and it makes sense because yaw is not critical for * stable hovering or 3D navigation. * - * For yaw control tuning use MC_YAW_P. This ratio has no inpact on the yaw gain. + * For yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain. * * @min 0.0 * @max 1.0 diff --git a/src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control_params.c b/src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control_params.c index e530eb75a8..0227743e40 100644 --- a/src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control_params.c +++ b/src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control_params.c @@ -54,7 +54,7 @@ PARAM_DEFINE_INT32(MC_AT_EN, 0); * and can be dangerous. Only activate if you know what you * are doing, and in a safe environment. * - * Any motion of the remote stick will abord the signal + * Any motion of the remote stick will abort the signal * injection and reset this parameter * Best is to perform the identification in position or * hold mode. diff --git a/src/modules/mc_pos_control/PositionControl/ControlMath.hpp b/src/modules/mc_pos_control/PositionControl/ControlMath.hpp index e356d945e6..c2d9b8b7f8 100644 --- a/src/modules/mc_pos_control/PositionControl/ControlMath.hpp +++ b/src/modules/mc_pos_control/PositionControl/ControlMath.hpp @@ -98,7 +98,7 @@ bool cross_sphere_line(const matrix::Vector3f &sphere_c, const float sphere_r, c /** * Adds e.g. feed-forward to the setpoint making sure existing or added NANs have no influence on control. - * This function is udeful to support all the different setpoint combinations of position, velocity, acceleration with NAN representing an uncommited value. + * This function is udeful to support all the different setpoint combinations of position, velocity, acceleration with NAN representing an uncommitted value. * @param setpoint existing possibly NAN setpoint to add to * @param addition value/NAN to add to the setpoint */ diff --git a/src/modules/mc_pos_control/mc_pos_control_params.c b/src/modules/mc_pos_control/mc_pos_control_params.c index 25d094289c..dae279826e 100644 --- a/src/modules/mc_pos_control/mc_pos_control_params.c +++ b/src/modules/mc_pos_control/mc_pos_control_params.c @@ -848,7 +848,7 @@ PARAM_DEFINE_INT32(MPC_YAW_MODE, 0); PARAM_DEFINE_FLOAT(SYS_VEHICLE_RESP, -0.4f); /** - * Overall Horizonal Velocity Limit + * Overall Horizontal Velocity Limit * * If set to a value greater than zero, other parameters are automatically set (such as * MPC_XY_VEL_MAX or MPC_VEL_MANUAL). diff --git a/src/modules/mc_rate_control/mc_rate_control_params.c b/src/modules/mc_rate_control/mc_rate_control_params.c index 4bc092db60..55e92f9be8 100644 --- a/src/modules/mc_rate_control/mc_rate_control_params.c +++ b/src/modules/mc_rate_control/mc_rate_control_params.c @@ -359,7 +359,7 @@ PARAM_DEFINE_FLOAT(MC_ACRO_EXPO_Y, 0.69f); * SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO. * * 0 Pure Expo function - * 0.7 resonable shape enhancement for intuitive stick feel + * 0.7 reasonable shape enhancement for intuitive stick feel * 0.95 very strong bent input curve only near maxima have effect * * @min 0 @@ -375,7 +375,7 @@ PARAM_DEFINE_FLOAT(MC_ACRO_SUPEXPO, 0.7f); * SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. * * 0 Pure Expo function - * 0.7 resonable shape enhancement for intuitive stick feel + * 0.7 reasonable shape enhancement for intuitive stick feel * 0.95 very strong bent input curve only near maxima have effect * * @min 0 diff --git a/src/modules/rc_update/params.c b/src/modules/rc_update/params.c index 2ddb20f6db..72ea4b8ee6 100644 --- a/src/modules/rc_update/params.c +++ b/src/modules/rc_update/params.c @@ -1858,7 +1858,7 @@ PARAM_DEFINE_INT32(RC_MAP_PARAM3, 0); /** * Failsafe channel PWM threshold. * - * Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this theshold. + * Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold. * By default this is the throttle channel. * * Set to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event, diff --git a/src/modules/sensors/sensor_params_flow.c b/src/modules/sensors/sensor_params_flow.c index 7d3de7ff7a..174cf5ba94 100644 --- a/src/modules/sensors/sensor_params_flow.c +++ b/src/modules/sensors/sensor_params_flow.c @@ -100,7 +100,7 @@ PARAM_DEFINE_FLOAT(SENS_FLOW_MAXR, 8.f); * Optical flow max rate. * * Optical flow data maximum publication rate. This is an upper bound, - * actual optical flow data rate is still dependant on the sensor. + * actual optical flow data rate is still dependent on the sensor. * * @min 1 * @max 200 diff --git a/src/modules/sensors/sensor_params_mag.c b/src/modules/sensors/sensor_params_mag.c index 6a904137ac..ff35f49558 100644 --- a/src/modules/sensors/sensor_params_mag.c +++ b/src/modules/sensors/sensor_params_mag.c @@ -82,7 +82,7 @@ PARAM_DEFINE_INT32(CAL_MAG_ROT_AUTO, 1); * Magnetometer max rate. * * Magnetometer data maximum publication rate. This is an upper bound, - * actual magnetometer data rate is still dependant on the sensor. + * actual magnetometer data rate is still dependent on the sensor. * * @min 1 * @max 200 diff --git a/src/modules/sensors/vehicle_air_data/params.c b/src/modules/sensors/vehicle_air_data/params.c index 950529bbf9..fee8ac6263 100644 --- a/src/modules/sensors/vehicle_air_data/params.c +++ b/src/modules/sensors/vehicle_air_data/params.c @@ -45,7 +45,7 @@ PARAM_DEFINE_FLOAT(SENS_BARO_QNH, 1013.25f); * Baro max rate. * * Barometric air data maximum publication rate. This is an upper bound, - * actual barometric data rate is still dependant on the sensor. + * actual barometric data rate is still dependent on the sensor. * * @min 1 * @max 200 diff --git a/src/modules/sih/sih.cpp b/src/modules/sih/sih.cpp index 45137bc722..555253aae5 100644 --- a/src/modules/sih/sih.cpp +++ b/src/modules/sih/sih.cpp @@ -562,7 +562,7 @@ void Sih::reconstruct_sensors_signals() float altitude = (_H0 - _p_I(2)) + _baro_offset_m + generate_wgn() * 0.14f; // altitude with noise _baro_p_mBar = CONSTANTS_STD_PRESSURE_MBAR * // reconstructed pressure in mBar powf((1.0f + altitude * TEMP_GRADIENT / T1_K), -CONSTANTS_ONE_G / (TEMP_GRADIENT * CONSTANTS_AIR_GAS_CONST)); - _baro_temp_c = T1_K + CONSTANTS_ABSOLUTE_NULL_CELSIUS + TEMP_GRADIENT * altitude; // reconstructed temperture in celcius + _baro_temp_c = T1_K + CONSTANTS_ABSOLUTE_NULL_CELSIUS + TEMP_GRADIENT * altitude; // reconstructed temperture in Celsius // GPS _gps_lat_noiseless = _LAT0 + degrees((double)_p_I(0) / CONSTANTS_RADIUS_OF_EARTH); diff --git a/src/modules/sih/sih.hpp b/src/modules/sih/sih.hpp index 05b11a8014..3762d17581 100644 --- a/src/modules/sih/sih.hpp +++ b/src/modules/sih/sih.hpp @@ -159,7 +159,7 @@ private: // hard constants static constexpr uint16_t NB_MOTORS = 6; - static constexpr float T1_C = 15.0f; // ground temperature in celcius + static constexpr float T1_C = 15.0f; // ground temperature in Celsius static constexpr float T1_K = T1_C - CONSTANTS_ABSOLUTE_NULL_CELSIUS; // ground temperature in Kelvin static constexpr float TEMP_GRADIENT = -6.5f / 1000.0f; // temperature gradient in degrees per metre // Aerodynamic coefficients @@ -281,14 +281,14 @@ private: double _gps_lon, _gps_lon_noiseless; float _gps_alt, _gps_alt_noiseless; float _baro_p_mBar; // reconstructed (simulated) pressure in mBar - float _baro_temp_c; // reconstructed (simulated) barometer temperature in celcius + float _baro_temp_c; // reconstructed (simulated) barometer temperature in degrees Celsius // parameters float _MASS, _T_MAX, _Q_MAX, _L_ROLL, _L_PITCH, _KDV, _KDW, _H0, _T_TAU; double _LAT0, _LON0, _COS_LAT0; matrix::Vector3f _W_I; // weight of the vehicle in inertial frame [N] matrix::Matrix3f _I; // vehicle inertia matrix - matrix::Matrix3f _Im1; // inverse of the intertia matrix + matrix::Matrix3f _Im1; // inverse of the inertia matrix matrix::Vector3f _mu_I; // NED magnetic field in inertial frame [G] int _gps_used; diff --git a/src/modules/sih/sih_params.c b/src/modules/sih/sih_params.c index a174d78c34..cc2c5cb76c 100644 --- a/src/modules/sih/sih_params.c +++ b/src/modules/sih/sih_params.c @@ -55,7 +55,7 @@ PARAM_DEFINE_FLOAT(SIH_MASS, 1.0f); /** * Vehicle inertia about X axis * - * The intertia is a 3 by 3 symmetric matrix. + * The inertia is a 3 by 3 symmetric matrix. * It represents the difficulty of the vehicle to modify its angular rate. * * @unit kg m^2 @@ -69,7 +69,7 @@ PARAM_DEFINE_FLOAT(SIH_IXX, 0.025f); /** * Vehicle inertia about Y axis * - * The intertia is a 3 by 3 symmetric matrix. + * The inertia is a 3 by 3 symmetric matrix. * It represents the difficulty of the vehicle to modify its angular rate. * * @unit kg m^2 @@ -83,7 +83,7 @@ PARAM_DEFINE_FLOAT(SIH_IYY, 0.025f); /** * Vehicle inertia about Z axis * - * The intertia is a 3 by 3 symmetric matrix. + * The inertia is a 3 by 3 symmetric matrix. * It represents the difficulty of the vehicle to modify its angular rate. * * @unit kg m^2 @@ -97,7 +97,7 @@ PARAM_DEFINE_FLOAT(SIH_IZZ, 0.030f); /** * Vehicle cross term inertia xy * - * The intertia is a 3 by 3 symmetric matrix. + * The inertia is a 3 by 3 symmetric matrix. * This value can be set to 0 for a quad symmetric about its center of mass. * * @unit kg m^2 @@ -110,7 +110,7 @@ PARAM_DEFINE_FLOAT(SIH_IXY, 0.0f); /** * Vehicle cross term inertia xz * - * The intertia is a 3 by 3 symmetric matrix. + * The inertia is a 3 by 3 symmetric matrix. * This value can be set to 0 for a quad symmetric about its center of mass. * * @unit kg m^2 @@ -123,7 +123,7 @@ PARAM_DEFINE_FLOAT(SIH_IXZ, 0.0f); /** * Vehicle cross term inertia yz * - * The intertia is a 3 by 3 symmetric matrix. + * The inertia is a 3 by 3 symmetric matrix. * This value can be set to 0 for a quad symmetric about its center of mass. * * @unit kg m^2 @@ -393,7 +393,7 @@ PARAM_DEFINE_FLOAT(SIH_MAG_OFFSET_Y, 0.0f); PARAM_DEFINE_FLOAT(SIH_MAG_OFFSET_Z, 0.0f); /** - * distance sensor minimun range + * distance sensor minimum range * * @unit m * @min 0.0 @@ -405,7 +405,7 @@ PARAM_DEFINE_FLOAT(SIH_MAG_OFFSET_Z, 0.0f); PARAM_DEFINE_FLOAT(SIH_DISTSNSR_MIN, 0.0f); /** - * distance sensor maximun range + * distance sensor maximum range * * @unit m * @min 0.0 @@ -417,7 +417,7 @@ PARAM_DEFINE_FLOAT(SIH_DISTSNSR_MIN, 0.0f); PARAM_DEFINE_FLOAT(SIH_DISTSNSR_MAX, 100.0f); /** - * if >= 0 the distance sensor measures will be overrided by this value + * if >= 0 the distance sensor measures will be overridden by this value * * Absolute value superior to 10000 will disable distance sensor * diff --git a/src/modules/temperature_compensation/temperature_calibration/polyfit.hpp b/src/modules/temperature_compensation/temperature_calibration/polyfit.hpp index 70cc28a5a2..cd56dce7c4 100644 --- a/src/modules/temperature_compensation/temperature_calibration/polyfit.hpp +++ b/src/modules/temperature_compensation/temperature_calibration/polyfit.hpp @@ -39,8 +39,8 @@ equation of the following form: yi = a0 + a1.xi + a2.xi^2 + a3.xi^3 + .... + an.xi^n + ei , where: i = [0,m] -xi is the x coordinate (independant variable) of the i'th measurement -yi is the y coordinate (dependant variable) of the i'th measurement +xi is the x coordinate (independent variable) of the i'th measurement +yi is the y coordinate (dependent variable) of the i'th measurement ei is a random fit error being the difference between the i'th y coordinate and the value predicted by the polynomial. diff --git a/src/modules/vtol_att_control/standard_params.c b/src/modules/vtol_att_control/standard_params.c index 3129619cec..924a95488c 100644 --- a/src/modules/vtol_att_control/standard_params.c +++ b/src/modules/vtol_att_control/standard_params.c @@ -89,8 +89,8 @@ PARAM_DEFINE_FLOAT(VT_B_TRANS_RAMP, 3.0f); /** * Output on airbrakes channel during back transition * - * Used for airbrakes or with ESCs that have reverse thrust enabled on a seperate channel - * Airbrakes need to be enables for your selected model/mixer + * Used for airbrakes or with ESCs that have reverse thrust enabled on a separate channel. + * Airbrakes need to be enabled for your selected model/mixer. * * @min 0 * @max 1 diff --git a/src/systemcmds/hardfault_log/hardfault_log.c b/src/systemcmds/hardfault_log/hardfault_log.c index c24245665d..30e3616ddd 100644 --- a/src/systemcmds/hardfault_log/hardfault_log.c +++ b/src/systemcmds/hardfault_log/hardfault_log.c @@ -1214,16 +1214,16 @@ static void print_usage(void) PRINT_MODULE_USAGE_NAME("hardfault_log", "command"); - PRINT_MODULE_USAGE_COMMAND_DESCR("check", "Check if there's an uncommited hardfault"); - PRINT_MODULE_USAGE_COMMAND_DESCR("rearm", "Drop an uncommited hardfault"); + PRINT_MODULE_USAGE_COMMAND_DESCR("check", "Check if there's an uncommitted hardfault"); + PRINT_MODULE_USAGE_COMMAND_DESCR("rearm", "Drop an uncommitted hardfault"); PRINT_MODULE_USAGE_COMMAND_DESCR("fault", "Generate a hardfault (this command crashes the system :)"); PRINT_MODULE_USAGE_ARG("0|1", "Hardfault type: 0=divide by 0, 1=Assertion (default=0)", true); PRINT_MODULE_USAGE_COMMAND_DESCR("commit", - "Write uncommited hardfault to /fs/microsd/fault_%i.txt (and rearm, but don't reset)"); + "Write uncommitted hardfault to /fs/microsd/fault_%i.txt (and rearm, but don't reset)"); PRINT_MODULE_USAGE_COMMAND_DESCR("count", - "Read the reboot counter, counts the number of reboots of an uncommited hardfault (returned as the exit code of the program)"); + "Read the reboot counter, counts the number of reboots of an uncommitted hardfault (returned as the exit code of the program)"); PRINT_MODULE_USAGE_COMMAND_DESCR("reset", "Reset the reboot counter"); } diff --git a/validation/module_schema.yaml b/validation/module_schema.yaml index 64700568fb..df0035ebb2 100644 --- a/validation/module_schema.yaml +++ b/validation/module_schema.yaml @@ -194,7 +194,7 @@ parameters: volatile: # Optional volatile flag. Set to true if the # parameter can be changed by the system - # automatially + # automatically type: boolean reboot_required: # set to true, if changing of the parameter requires