Spelling errors (#19935)

This commit is contained in:
Hamish Willee 2022-07-27 14:33:16 +10:00 committed by GitHub
parent 97f632a408
commit e6eed43648
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
97 changed files with 170 additions and 158 deletions

View File

@ -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.

View File

@ -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.

View File

@ -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)
'''

View File

@ -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
```

View File

@ -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

View File

@ -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)) {

View File

@ -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)) {

View File

@ -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.

View File

@ -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.
*/

View File

@ -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) {

View File

@ -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()

View File

@ -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()

View File

@ -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()

View File

@ -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

View File

@ -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 + (Year1980)×512
uint16 manufacture_date # manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year1980)×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.

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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)

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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:

View File

@ -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)

View File

@ -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. |

View File

@ -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.

View File

@ -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.

View File

@ -33,7 +33,7 @@
/**
* @file log.h
* Platform dependant logging/debug implementation
* Platform dependent logging/debug implementation
*/
#pragma once

View File

@ -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);
}
}

View File

@ -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.");

View File

@ -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 <kabir@uasys.io>
* @author Kelly Steich <kelly.steich@wingtra.com>

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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();

View File

@ -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

View File

@ -44,7 +44,7 @@
#include <board_config.h>
// 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

View File

@ -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

View File

@ -96,7 +96,7 @@ VOXLPM::init()
ret = init_ina231();
} else {
PX4_ERR("Unkown device address");
PX4_ERR("Unknown device address");
ret = PX4_ERROR;
}

View File

@ -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 <device> <baud>
```
$ roboclaw start <device> <baud>
```
`<device>` is the name of the UART port. On the Pixhawk 4, this is `/dev/ttyS3`.
`<baud>` is te baud rate.
- `<device>` is the name of the UART port. On the Pixhawk 4, this is `/dev/ttyS3`.
- `<baud>` is the baud rate.
All available commands are:
- `$ roboclaw start <device> <baud>`
- `$ roboclaw status`
- `$ roboclaw stop`
- `$ roboclaw start <device> <baud>`
- `$ roboclaw status`
- `$ roboclaw stop`
)DESCR_STR");
}

View File

@ -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

View File

@ -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");

View File

@ -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)
*/

View File

@ -115,7 +115,7 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure<uavcan::
_battery_status[instance].remaining = msg.state_of_charge_pct / 100.0f; // between 0 and 1
// _battery_status[instance].scale = msg.; // Power scaling factor, >= 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::ReceivedDataStructure<uavcan::equi
/* Override data that is expected to arrive from UAVCAN msg*/
_battery_status[instance] = _battery[instance]->getBatteryStatus();
_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

View File

@ -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.

View File

@ -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

View File

@ -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

View File

@ -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:

View File

@ -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));

View File

@ -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,

View File

@ -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

View File

@ -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();

View File

@ -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
{

View File

@ -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);

View File

@ -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.

View File

@ -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
*

View File

@ -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 */)

View File

@ -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.
*/

View File

@ -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

View File

@ -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

View File

@ -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;

View File

@ -358,7 +358,7 @@ private:
(ParamExtFloat<px4::params::EKF2_EV_DELAY>)
_param_ekf2_ev_delay, ///< off-board vision measurement delay relative to the IMU (mSec)
(ParamExtFloat<px4::params::EKF2_AVEL_DELAY>)
_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<px4::params::EKF2_GYR_NOISE>)
_param_ekf2_gyr_noise, ///< IMU angular rate noise used for covariance prediction (rad/sec)

View File

@ -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

View File

@ -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

View File

@ -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;
}
}

View File

@ -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. */

View File

@ -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
*/

View File

@ -85,7 +85,7 @@ protected:
(ParamFloat<px4::params::MPC_MAN_Y_TAU>) _param_mpc_man_y_tau,
(ParamFloat<px4::params::MPC_MAN_TILT_MAX>) _param_mpc_man_tilt_max, /**< maximum tilt allowed for manual flight */
(ParamFloat<px4::params::MPC_LAND_ALT1>) _param_mpc_land_alt1, /**< altitude at which to start downwards slowdown */
(ParamFloat<px4::params::MPC_LAND_ALT2>) _param_mpc_land_alt2, /**< altitude below wich to land with land speed */
(ParamFloat<px4::params::MPC_LAND_ALT2>) _param_mpc_land_alt2, /**< altitude below which to land with land speed */
(ParamFloat<px4::params::MPC_LAND_SPEED>)
_param_mpc_land_speed, /**< desired downwards speed when approaching the ground */
(ParamFloat<px4::params::MPC_TKO_SPEED>)

View File

@ -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);

View File

@ -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.

View File

@ -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.
*

View File

@ -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;

View File

@ -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) {

View File

@ -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) {

View File

@ -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.

View File

@ -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:

View File

@ -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

View File

@ -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.

View File

@ -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
*/

View File

@ -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).

View File

@ -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

View File

@ -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,

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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);

View File

@ -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;

View File

@ -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
*

View File

@ -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.

View File

@ -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

View File

@ -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");
}

View File

@ -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