Fix duplicate newlines at the end of files

This commit is contained in:
Matthias Grob
2024-05-22 14:21:56 +02:00
parent 7f14110bb1
commit f2bca92221
274 changed files with 248 additions and 560 deletions

View File

@@ -54,4 +54,3 @@ jobs:
AWS_REGION: 'us-west-1'
SOURCE_DIR: 'build/${{ matrix.target }}/_metadata/'
DEST_DIR: 'Firmware/${{ env.version }}/${{ matrix.target }}/'

View File

@@ -29,4 +29,3 @@ param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104

View File

@@ -30,4 +30,3 @@ param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default EKF2_RNG_A_HMAX 10

View File

@@ -94,4 +94,3 @@ param set-default CA_METHOD 0
# disable attitude failure detection
param set-default FD_FAIL_P 0
param set-default FD_FAIL_R 0

View File

@@ -12,4 +12,3 @@ param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104

View File

@@ -30,4 +30,3 @@ param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default LPE_FUSION 242

View File

@@ -18,4 +18,3 @@ param set-default LPE_FUSION 132
# AEQ: External heading set to use vision input
param set-default ATT_EXT_HDG_M 1

View File

@@ -41,4 +41,3 @@ param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104

View File

@@ -61,4 +61,3 @@ param set-default PWM_MAIN_FUNC5 105
param set-default PWM_MAIN_FUNC6 106
param set-default PWM_MAIN_FUNC7 107
param set-default PWM_MAIN_FUNC8 108

View File

@@ -68,5 +68,3 @@ param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256

View File

@@ -71,4 +71,3 @@ param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256

View File

@@ -55,4 +55,3 @@ param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256

View File

@@ -54,4 +54,3 @@ param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256

View File

@@ -55,4 +55,3 @@ param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256

View File

@@ -62,4 +62,3 @@ param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256

View File

@@ -78,4 +78,3 @@ param set-default VT_FWD_THRUST_EN 4
param set-default VT_FWD_THRUST_SC 1
param set-default VT_F_TRANS_THR 0.75
param set-default VT_TYPE 2

View File

@@ -75,4 +75,3 @@ param set-default VT_F_TRANS_DUR 1.5
param set-default VT_TYPE 0
param set-default WV_EN 0

View File

@@ -88,4 +88,3 @@ param set-default PWM_MAIN_FUNC11 422
param set-default RC_MAP_AUX1 8
param set-default RC_MAP_AUX2 9
param set-default RC_MAP_AUX3 10

View File

@@ -31,4 +31,3 @@ param set-default PWM_MAIN_FUNC1 201
param set-default PWM_MAIN_FUNC2 201
param set-default PWM_MAIN_FUNC6 101
param set-default PWM_MAIN_FUNC7 101

View File

@@ -38,4 +38,3 @@ param set-default PWM_MAIN_FUNC1 201
param set-default PWM_MAIN_FUNC2 201
param set-default PWM_MAIN_FUNC6 101
param set-default PWM_MAIN_FUNC7 101

View File

@@ -41,4 +41,3 @@ param set-default CA_R_REV 3
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102

View File

@@ -64,4 +64,3 @@ param set-default PWM_MAIN_FUNC4 203
param set-default PWM_MAIN_FUNC5 407
param set-default PWM_MAIN_FUNC6 408
param set-default PWM_MAIN_FUNC7 409

View File

@@ -69,4 +69,3 @@ param set-default PWM_MAIN_FUNC4 203
param set-default PWM_MAIN_FUNC5 407
param set-default PWM_MAIN_FUNC6 408
param set-default PWM_MAIN_FUNC7 409

View File

@@ -36,4 +36,3 @@ param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 201
param set-default PWM_MAIN_FUNC4 103

View File

@@ -63,4 +63,3 @@ param set-default PWM_MAIN_FUNC9 422
# Landing gear
param set-default PWM_MAIN_FUNC10 400
param set-default PWM_MAIN_FUNC11 400

View File

@@ -119,4 +119,3 @@ param set-default CA_METHOD 0
# disable attitude failure detection
param set-default FD_FAIL_P 0
param set-default FD_FAIL_R 0

View File

@@ -44,4 +44,3 @@ param set-default CA_ROTOR4_KM -0.05
param set-default CA_ROTOR5_PX 0.25
param set-default CA_ROTOR5_PY -0.433
param set-default CA_ROTOR5_PZ 0.05

View File

@@ -119,5 +119,3 @@ param set-default PWM_MAIN_TIM0 50
param set-default PWM_MAIN_DIS1 1500
param set-default PWM_MAIN_DIS2 1500
param set-default PWM_MAIN_DIS4 1500

View File

@@ -32,4 +32,3 @@ param set-default CA_SV_TL0_MAXA 45
param set-default CA_SV_TL0_MINA -45
param set-default CA_SV_TL0_TD 90
param set-default CA_SV_TL_COUNT 1

View File

@@ -24,5 +24,3 @@ param set-default MC_PITCHRATE_D 0
param set-default MC_PITCHRATE_FF 0.1
param set-default CA_AIRFRAME 10

View File

@@ -23,4 +23,3 @@ param set-default MAV_0_MODE 1
param set-default MAV_0_CONFIG 102
param set-default GPS_UBX_DYNMODEL 8
param set-default SER_TEL2_BAUD 9600

View File

@@ -72,5 +72,3 @@ param set-default PWM_MAIN_DIS5 1000
param set-default PWM_MAIN_DIS6 1500
param set-default PWM_MAIN_DIS7 1500
param set-default PWM_MAIN_DIS8 1500

View File

@@ -66,4 +66,3 @@ param set-default CA_ROTOR11_PX -0.344
param set-default CA_ROTOR11_PY -0.25
param set-default CA_ROTOR11_PZ -0.05
param set-default CA_ROTOR11_KM -0.05

View File

@@ -38,4 +38,3 @@ param set-default CA_SV_CS_COUNT 1
param set-default CA_SV_CS0_TRQ_P 1
param set-default CA_R_REV 7

View File

@@ -48,5 +48,3 @@ param set-default PWM_MAIN_FUNC1 201
param set-default PWM_MAIN_FUNC2 201
param set-default PWM_MAIN_FUNC6 101
param set-default PWM_MAIN_FUNC7 101

View File

@@ -42,4 +42,3 @@ param set-default CA_ROTOR3_KM 0
param set-default CA_ROTOR3_PX 0
param set-default CA_ROTOR3_PY -0.3
param set-default CA_ROTOR3_PZ 0.3

View File

@@ -31,5 +31,3 @@ param set-default CA_ROTOR4_PY 0.25
param set-default CA_ROTOR5_PX -0.43
param set-default CA_ROTOR5_PY -0.25
param set-default CA_ROTOR5_KM -0.05

View File

@@ -123,4 +123,3 @@ param set-default PWM_MAIN_FUNC6 106
param set-default PWM_MAIN_TIM0 -1
param set-default PWM_MAIN_TIM1 -1
param set-default PWM_MAIN_TIM2 -1

View File

@@ -31,5 +31,3 @@ param set-default CA_ROTOR4_PY -0.43
param set-default CA_ROTOR5_PX -0.25
param set-default CA_ROTOR5_PY 0.43
param set-default CA_ROTOR5_KM -0.05

View File

@@ -36,5 +36,3 @@ param set-default CA_ROTOR6_PY -0.46
param set-default CA_ROTOR7_KM -0.05
param set-default CA_ROTOR7_PX -0.19
param set-default CA_ROTOR7_PY 0.46

View File

@@ -36,4 +36,3 @@ param set-default CA_ROTOR6_PY -0.5
param set-default CA_ROTOR7_KM -0.05
param set-default CA_ROTOR7_PX 0
param set-default CA_ROTOR7_PY 0.5

View File

@@ -45,7 +45,7 @@ function [ center, radii, evecs, v ] = ellipsoid_fit( X, flag, equals )
% * center - ellispoid center coordinates [xc; yc; zc]
% * ax - ellipsoid radii [a; b; c]
% * evecs - ellipsoid radii directions as columns of the 3x3 matrix
% * v - the 9 parameters describing the ellipsoid algebraically:
% * v - the 9 parameters describing the ellipsoid algebraically:
% Ax^2 + By^2 + Cz^2 + 2Dxy + 2Exz + 2Fyz + 2Gx + 2Hy + 2Iz = 1
%
% Author:
@@ -59,7 +59,7 @@ end
if flag == 2 && nargin == 2
equals = 'xy';
end
if size( X, 2 ) ~= 3
error( 'Input data must have three columns!' );
else
@@ -69,7 +69,7 @@ else
end
% need nine or more data points
if length( x ) < 9 && flag == 0
if length( x ) < 9 && flag == 0
error( 'Must have at least 9 points to fit a unique ellipsoid' );
end
if length( x ) < 6 && flag == 1
@@ -91,7 +91,7 @@ if flag == 0
2 * x .* z, ...
2 * y .* z, ...
2 * x, ...
2 * y, ...
2 * y, ...
2 * z ]; % ndatapoints x 9 ellipsoid parameters
elseif flag == 1
% fit ellipsoid in the form Ax^2 + By^2 + Cz^2 + 2Gx + 2Hy + 2Iz = 1
@@ -99,7 +99,7 @@ elseif flag == 1
y .* y, ...
z .* z, ...
2 * x, ...
2 * y, ...
2 * y, ...
2 * z ]; % ndatapoints x 6 ellipsoid parameters
elseif flag == 2
% fit ellipsoid in the form Ax^2 + By^2 + Cz^2 + 2Gx + 2Hy + 2Iz = 1,
@@ -127,7 +127,7 @@ else
% fit sphere in the form A(x^2 + y^2 + z^2) + 2Gx + 2Hy + 2Iz = 1
D = [ x .* x + y .* y + z .* z, ...
2 * x, ...
2 * y, ...
2 * y, ...
2 * z ]; % ndatapoints x 4 sphere parameters
end
@@ -170,5 +170,3 @@ else
radii = ( sqrt( gam ./ v( 1:3 ) ) )';
evecs = eye( 3 );
end

View File

@@ -170,4 +170,3 @@ if(__name__ == "__main__"):
fs.write(f.read())
except:
pass

View File

@@ -139,7 +139,3 @@ def find_checks_that_apply(
innov_fail_checks.append('ofy')
return sensor_checks, innov_fail_checks

View File

@@ -243,4 +243,3 @@ def main():
if __name__ == '__main__':
main()

View File

@@ -282,4 +282,3 @@ def main():
if __name__ == '__main__':
main()

View File

@@ -330,4 +330,3 @@ if serial_params_output_file is not None:
fid.write(template.render(serial_devices=serial_devices,
ethernet_configuration=ethernet_configuration,
commands=commands, serial_ports=serial_ports))

View File

@@ -30,4 +30,3 @@ unset PRT
unset PRT_F
unset BAUD_PARAM
unset MAV_ARGS

View File

@@ -70,4 +70,3 @@ PARAM_DEFINE_INT32({{ command.port_param_name }}, {{ command.default_port }});
{% endfor -%}
{% endif %}

View File

@@ -125,4 +125,3 @@ def main():
if __name__ == '__main__':
main()

View File

@@ -50,4 +50,3 @@ for json_file in json_files:
except:
print("JSON validation for {:} failed (schema: {:})".format(json_file, schema_file))
raise

View File

@@ -65,4 +65,3 @@ for yaml_file in yaml_files:
print(validator.errors)
print("")
raise Exception("Validation of {:} failed".format(yaml_file))

View File

@@ -37,4 +37,3 @@ constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusInternal(1),
initI2CBusExternal(2),
};

View File

@@ -105,4 +105,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}

View File

@@ -8,4 +8,3 @@ echo "uploading: $PX4_BINARY_FILE"
PX4_BINARY_FILE_SIZE=$(stat -c%s "$PX4_BINARY_FILE")
curl -v -F "image=@$PX4_BINARY_FILE" -H "Expect:" -H "File-Size:$PX4_BINARY_FILE_SIZE" http://192.168.42.1/cgi-bin/upload

View File

@@ -374,4 +374,3 @@
* SDMMC1_D2 PC10
* SDMMC1_D3 PC11
*/

View File

@@ -81,4 +81,3 @@ int BBBlueRcPWMOut::send_output_pwm(const uint16_t *pwm, int num_outputs)
return ret;
}

View File

@@ -105,4 +105,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}

View File

@@ -105,4 +105,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}

View File

@@ -12,4 +12,3 @@ icm20948 -s -b 4 -R 10 -M start
# SPI1
ms5611 -s -b 1 start
icm20649 -s -b 1 start

View File

@@ -37,4 +37,3 @@ else
fi
ms5611 -s -b 1 start

View File

@@ -12,4 +12,3 @@ icm20948 -s -b 4 -R 10 -M start
# SPI1
ms5611 -s -b 1 start
icm20649 -s -b 1 start

View File

@@ -5,4 +5,3 @@
param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303

View File

@@ -153,4 +153,3 @@ int NavioSysfsPWMOut::pwm_write_sysfs(char *path, int value)
return 0;
}

View File

@@ -7,5 +7,3 @@ if ! param compare OSD_ATXXXX_CFG 0
then
atxxxx start -s
fi

View File

@@ -264,4 +264,3 @@
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PC12 */
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_1 /* PB3 */

View File

@@ -99,4 +99,3 @@
// AVAILABLE // DMA1, Stream 5
// AVAILABLE // DMA1, Stream 6
// DMAMAP_USART1_TX USART1_TX // DMA1, Stream 7, Channel 5

View File

@@ -10,4 +10,3 @@ fi
# DShot telemetry is always on UART7
dshot telemetry /dev/ttyS5

View File

@@ -304,4 +304,3 @@
* OTG_FS_DP PA12
* VBUS PA8
*/

View File

@@ -99,4 +99,3 @@
// DMAMAP_TIM1_UP // DMA2, Stream 5, Channel 6 (DSHOT)
// AVAILABLE // DMA1, Stream 6
// AVAILABLE // DMA1, Stream 7

View File

@@ -105,4 +105,3 @@ __EXPORT void led_toggle(int led)
{
phy_set_led(led, !phy_get_led(led));
}

View File

@@ -31,4 +31,3 @@ param set-default EKF2_IMU_CTRL 7
param set-default CBRK_BUZZER 782090
param set-default IMU_GYRO_RATEMAX 2000

View File

@@ -10,4 +10,3 @@ fi
# DShot telemetry is always on UART7
dshot telemetry /dev/ttyS5

View File

@@ -416,4 +416,3 @@
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)

View File

@@ -37,4 +37,3 @@
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2 */
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2 */

View File

@@ -10,4 +10,3 @@ fi
# DShot telemetry is always on UART7
dshot telemetry /dev/ttyS5

View File

@@ -416,4 +416,3 @@
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)

View File

@@ -37,4 +37,3 @@
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2 */
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2 */

View File

@@ -10,4 +10,3 @@ fi
# DShot telemetry is always on UART7
dshot telemetry /dev/ttyS5

View File

@@ -416,4 +416,3 @@
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)

View File

@@ -37,4 +37,3 @@
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2 */
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2 */

View File

@@ -10,7 +10,5 @@
atxxxx start -s
# DShot telemetry is always on UART7
# dshot telemetry /dev/ttyS5

View File

@@ -13,4 +13,3 @@ atxxxx start -s
# DShot telemetry is always on UART7
# dshot telemetry /dev/ttyS5

View File

@@ -13,4 +13,3 @@ atxxxx start -s
# DShot telemetry is always on UART7
# dshot telemetry /dev/ttyS5

View File

@@ -2,4 +2,3 @@
# Run this from the px4 project top level directory
docker run -it --rm --privileged -v `pwd`:/usr/local/workspace px4io/px4-dev-nuttx-focal:2022-08-12

View File

@@ -108,6 +108,3 @@ ControllerInput getKey(const std::map<ControllerInput, std::string> &map, const
return ControllerInput::DEFAULT;
}

View File

@@ -123,4 +123,3 @@ private:
// (ParamBool<px4::params::RC_GHST_TEL_EN>) _param_rc_ghst_tel_en
// )
};

View File

@@ -8,4 +8,3 @@ serial_config:
#depends_on_port: RC
description_extended: |
Ghost RC (GHST) driver.

View File

@@ -41,4 +41,3 @@ px4_add_module(
DEPENDS
rc
)

View File

@@ -282,4 +282,3 @@
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_3

View File

@@ -8,4 +8,3 @@ param set-default BAT1_A_PER_V 15.391030303
rgbled_pwm start
safety_button start

View File

@@ -7,5 +7,3 @@ if ! param compare OSD_ATXXXX_CFG 0
then
atxxxx start -s
fi

View File

@@ -105,4 +105,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}

View File

@@ -49,4 +49,3 @@ constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
initIOTimerChannelMapping(io_timers, timer_io_channels);

View File

@@ -11,4 +11,3 @@ param set-default CBRK_SUPPLY_CHK 894281
# Disable safety switch by default
param set-default CBRK_IO_SAFETY 22027

View File

@@ -82,4 +82,3 @@ __EXPORT void rp2040_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}

View File

@@ -376,6 +376,3 @@
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */

View File

@@ -42,4 +42,3 @@
#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_0 /* DMA1:81 */
#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_0 /* DMA1:82 */

View File

@@ -31,4 +31,3 @@ lis3mdl -R 2 -X start
# NCP5623 Led driver
rgbled_ncp5623c -X -a 0x38 start

View File

@@ -7,5 +7,3 @@ if ! param compare OSD_ATXXXX_CFG 0
then
atxxxx start -s
fi

Some files were not shown because too many files have changed in this diff Show More