From 904ab16558272939f15a4ce90255783a761dc1f9 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Sat, 7 Dec 2019 10:10:51 +0100 Subject: [PATCH] Fix trailing whitespace, EOF newline, indentation --- .vscode/cmake-variants.yaml | 1 - README.md | 2 +- .../init.d/airframes/6002_draco_r | 6 ++-- Tools/sitl_run.sh | 2 +- .../holybro/durandal-v1/nuttx-config/Kconfig | 1 - boards/px4/fmu-v4/nuttx-config/Kconfig | 2 -- .../nuttx/src/px4/stm/stm32h7/CMakeLists.txt | 1 - .../px4/stm/stm32h7/include/px4_arch/adc.h | 1 - .../stm/stm32h7/include/px4_arch/io_timer.h | 2 -- .../stm/stm32h7/include/px4_arch/micro_hal.h | 1 - .../stm32h7/include/px4_arch/px4io_serial.h | 1 - .../stm/stm32h7/px4io_serial/px4io_serial.cpp | 1 - platforms/posix/src/px4/common/adc.cpp | 1 - .../uavcan/uavcan_drivers/kinetis/README.md | 4 +-- .../kinetis/driver/CMakeLists.txt | 1 - .../stm32/driver/CMakeLists.txt | 1 - .../MulticopterRateControl.hpp | 1 - .../mc_rate_control/mc_rate_control_params.c | 1 - src/modules/sensors/sensor_params_gyro0.c | 1 - src/modules/sensors/sensor_params_gyro1.c | 1 - src/modules/sensors/sensor_params_gyro2.c | 1 - src/systemcmds/tests/test_matrix.cpp | 35 +++++++------------ 22 files changed, 20 insertions(+), 48 deletions(-) diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index 4dd3686f7d..9fc391393b 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -71,4 +71,3 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: holybro_durandal-v1_default - \ No newline at end of file diff --git a/README.md b/README.md index 5dade9808e..d8fb44aa6b 100644 --- a/README.md +++ b/README.md @@ -86,7 +86,7 @@ This repository contains code supporting these boards: * [Pixhawk 3 Pro](https://docs.px4.io/master/en/flight_controller/pixhawk3_pro.html) * FMUv5 (ARM Cortex M7) * [Pixhawk 4](https://docs.px4.io/master/en/flight_controller/pixhawk4.html) - * [Pixhawk 4 mini](https://docs.px4.io/master/en/flight_controller/pixhawk4_mini.html) + * [Pixhawk 4 mini](https://docs.px4.io/master/en/flight_controller/pixhawk4_mini.html) * [CUAV V5+](https://docs.px4.io/master/en/flight_controller/cuav_v5_plus.html) * [CUAV V5 nano](https://docs.px4.io/master/en/flight_controller/cuav_v5_nano.html) * [Airmind MindPX V2.8](http://www.mindpx.net/assets/accessories/UserGuide_MindPX.pdf) diff --git a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r index c44c2f286c..3c0a3bed6a 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r +++ b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r @@ -30,7 +30,7 @@ set PWM_OUT 12345678 if [ $AUTOCNF = yes ] then - ############################################### + ############################################### # Attitude & rate gains ############################################### # Roll @@ -53,7 +53,7 @@ then param set MC_YAW_FF 0.00000 param set MC_YAWRATE_MAX 700.00000 - ############################################### + ############################################### # Multirotor Position Gains ############################################### param set MPC_ACC_HOR 8.0000 @@ -138,7 +138,7 @@ then param set MAV_1_FORWARD 1 param set MAV_1_RATE 800000 param set SER_TEL2_BAUD 921600 - + # Disable internal magnetometer sensor param set CAL_MAG0_EN 0 # Enable external magnetometer sensor diff --git a/Tools/sitl_run.sh b/Tools/sitl_run.sh index 5a139aafb6..f83c52cd2e 100755 --- a/Tools/sitl_run.sh +++ b/Tools/sitl_run.sh @@ -51,7 +51,7 @@ fi # be running from last time pkill -x gazebo || true -# Do NOT kill PX4 if debug in ide +# Do NOT kill PX4 if debug in ide if [ "$debugger" != "ide" ]; then pkill -x px4 || true pkill -x px4_$model || true diff --git a/boards/holybro/durandal-v1/nuttx-config/Kconfig b/boards/holybro/durandal-v1/nuttx-config/Kconfig index d21e7f3ea9..bb33d3cfda 100644 --- a/boards/holybro/durandal-v1/nuttx-config/Kconfig +++ b/boards/holybro/durandal-v1/nuttx-config/Kconfig @@ -15,4 +15,3 @@ config BOARD_USE_PROBES ---help--- Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. - diff --git a/boards/px4/fmu-v4/nuttx-config/Kconfig b/boards/px4/fmu-v4/nuttx-config/Kconfig index a3360d93f8..affacc01c7 100644 --- a/boards/px4/fmu-v4/nuttx-config/Kconfig +++ b/boards/px4/fmu-v4/nuttx-config/Kconfig @@ -15,5 +15,3 @@ config BOARD_USE_PROBES ---help--- Select to use GPIO FMU-CH1-6 to provide timing signals from selected drivers. - - diff --git a/platforms/nuttx/src/px4/stm/stm32h7/CMakeLists.txt b/platforms/nuttx/src/px4/stm/stm32h7/CMakeLists.txt index d813819859..f44fe2a34b 100644 --- a/platforms/nuttx/src/px4/stm/stm32h7/CMakeLists.txt +++ b/platforms/nuttx/src/px4/stm/stm32h7/CMakeLists.txt @@ -43,4 +43,3 @@ add_subdirectory(../stm32_common/tone_alarm tone_alarm) add_subdirectory(../stm32_common/version version) add_subdirectory(px4io_serial) - diff --git a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/adc.h b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/adc.h index 3ccc32b0f8..5388bceee4 100644 --- a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/adc.h +++ b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/adc.h @@ -56,4 +56,3 @@ #endif #include - diff --git a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/io_timer.h b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/io_timer.h index 2960835d2e..6b565c3847 100644 --- a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/io_timer.h +++ b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/io_timer.h @@ -32,6 +32,4 @@ ****************************************************************************/ #pragma once - #include "../../../stm32_common/include/px4_arch/io_timer.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/micro_hal.h b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/micro_hal.h index cea5db9583..6beb18012c 100644 --- a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/micro_hal.h +++ b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/micro_hal.h @@ -54,4 +54,3 @@ int stm32h7_flash_writeprotect(size_t block, bool enabled); #define stm32_flash_lock() stm32h7_flash_lock(PX4_FLASH_BASE) __END_DECLS - diff --git a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/px4io_serial.h b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/px4io_serial.h index 0e78048670..85e3c55469 100644 --- a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/px4io_serial.h +++ b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/px4io_serial.h @@ -35,4 +35,3 @@ #define PX4IO_SERIAL_BUF_ALIGN ARMV7M_DCACHE_LINESIZE #include "../../../stm32_common/include/px4_arch/px4io_serial.h" - diff --git a/platforms/nuttx/src/px4/stm/stm32h7/px4io_serial/px4io_serial.cpp b/platforms/nuttx/src/px4/stm/stm32h7/px4io_serial/px4io_serial.cpp index 1908b18913..5e35ab1dda 100644 --- a/platforms/nuttx/src/px4/stm/stm32h7/px4io_serial/px4io_serial.cpp +++ b/platforms/nuttx/src/px4/stm/stm32h7/px4io_serial/px4io_serial.cpp @@ -545,4 +545,3 @@ ArchPX4IOSerial::_abort_dma() rICR = rISR & rISR_ERR_FLAGS_MASK; /* clear the flags */ } - diff --git a/platforms/posix/src/px4/common/adc.cpp b/platforms/posix/src/px4/common/adc.cpp index a4e162e37e..e6bd93ad1e 100644 --- a/platforms/posix/src/px4/common/adc.cpp +++ b/platforms/posix/src/px4/common/adc.cpp @@ -37,4 +37,3 @@ uint32_t px4_arch_adc_dn_fullcount(void) { return 1 << 12; // 12 bit ADC } - diff --git a/src/drivers/uavcan/uavcan_drivers/kinetis/README.md b/src/drivers/uavcan/uavcan_drivers/kinetis/README.md index 052e45cfdd..45ee8828f4 100644 --- a/src/drivers/uavcan/uavcan_drivers/kinetis/README.md +++ b/src/drivers/uavcan/uavcan_drivers/kinetis/README.md @@ -1,7 +1,7 @@ # libuavcan_kinetis Libuavcan platform driver for Kinetis FlexCAN -The Directory contains the Kinetis FlexCAN platform driver for Libuavcan on NuttX. +The Directory contains the Kinetis FlexCAN platform driver for Libuavcan on NuttX. Configuation is set by the NuttX board.h for the following: @@ -22,7 +22,7 @@ Things that could be improved: 2. Build time command line configuartion clock source - Curently 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. + can be set. But this changes the memory map. So the configuration show below has been chosen. ``` /* Layout of Fifo, filters and Message buffers */ diff --git a/src/drivers/uavcan/uavcan_drivers/kinetis/driver/CMakeLists.txt b/src/drivers/uavcan/uavcan_drivers/kinetis/driver/CMakeLists.txt index f4cc48168a..5278517b1b 100644 --- a/src/drivers/uavcan/uavcan_drivers/kinetis/driver/CMakeLists.txt +++ b/src/drivers/uavcan/uavcan_drivers/kinetis/driver/CMakeLists.txt @@ -14,4 +14,3 @@ install(DIRECTORY include/uavcan_kinetis DESTINATION include) install(TARGETS uavcan_kinetis_driver DESTINATION lib) # vim: set et ft=cmake fenc=utf-8 ff=unix sts=4 sw=4 ts=4 :) - diff --git a/src/drivers/uavcan/uavcan_drivers/stm32/driver/CMakeLists.txt b/src/drivers/uavcan/uavcan_drivers/stm32/driver/CMakeLists.txt index ce8ef00234..bdbbbb5b06 100644 --- a/src/drivers/uavcan/uavcan_drivers/stm32/driver/CMakeLists.txt +++ b/src/drivers/uavcan/uavcan_drivers/stm32/driver/CMakeLists.txt @@ -14,4 +14,3 @@ install(DIRECTORY include/uavcan_stm32 DESTINATION include) install(TARGETS uavcan_stm32_driver DESTINATION lib) # vim: set et ft=cmake fenc=utf-8 ff=unix sts=4 sw=4 ts=4 :) - diff --git a/src/modules/mc_rate_control/MulticopterRateControl.hpp b/src/modules/mc_rate_control/MulticopterRateControl.hpp index 849003ab56..09124ea8a4 100644 --- a/src/modules/mc_rate_control/MulticopterRateControl.hpp +++ b/src/modules/mc_rate_control/MulticopterRateControl.hpp @@ -182,4 +182,3 @@ private: matrix::Vector3f _acro_rate_max; /**< max attitude rates in acro mode */ }; - 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 80bf264889..20235f961a 100644 --- a/src/modules/mc_rate_control/mc_rate_control_params.c +++ b/src/modules/mc_rate_control/mc_rate_control_params.c @@ -412,4 +412,3 @@ PARAM_DEFINE_INT32(MC_BAT_SCALE_EN, 0); * @group Multicopter Rate Control */ PARAM_DEFINE_FLOAT(MC_DTERM_CUTOFF, 0.f); - diff --git a/src/modules/sensors/sensor_params_gyro0.c b/src/modules/sensors/sensor_params_gyro0.c index 6e324d0086..29b1448c16 100644 --- a/src/modules/sensors/sensor_params_gyro0.c +++ b/src/modules/sensors/sensor_params_gyro0.c @@ -71,4 +71,3 @@ PARAM_DEFINE_FLOAT(CAL_GYRO0_YOFF, 0.0f); * @group Sensor Calibration */ PARAM_DEFINE_FLOAT(CAL_GYRO0_ZOFF, 0.0f); - diff --git a/src/modules/sensors/sensor_params_gyro1.c b/src/modules/sensors/sensor_params_gyro1.c index 6143613c2d..584b89d7fc 100644 --- a/src/modules/sensors/sensor_params_gyro1.c +++ b/src/modules/sensors/sensor_params_gyro1.c @@ -71,4 +71,3 @@ PARAM_DEFINE_FLOAT(CAL_GYRO1_YOFF, 0.0f); * @group Sensor Calibration */ PARAM_DEFINE_FLOAT(CAL_GYRO1_ZOFF, 0.0f); - diff --git a/src/modules/sensors/sensor_params_gyro2.c b/src/modules/sensors/sensor_params_gyro2.c index 598c99b0da..3471b4272d 100644 --- a/src/modules/sensors/sensor_params_gyro2.c +++ b/src/modules/sensors/sensor_params_gyro2.c @@ -71,4 +71,3 @@ PARAM_DEFINE_FLOAT(CAL_GYRO2_YOFF, 0.0f); * @group Sensor Calibration */ PARAM_DEFINE_FLOAT(CAL_GYRO2_ZOFF, 0.0f); - diff --git a/src/systemcmds/tests/test_matrix.cpp b/src/systemcmds/tests/test_matrix.cpp index b80e54c62a..ab37da8e1b 100644 --- a/src/systemcmds/tests/test_matrix.cpp +++ b/src/systemcmds/tests/test_matrix.cpp @@ -769,14 +769,11 @@ bool MatrixTest::pseudoInverseTests() 8.f, 9.f, 10.f, 11.f }; - // *INDENT-OFF* - float data0_check[12] = { - -0.3375f, -0.1f, 0.1375f, - -0.13333333f, -0.03333333f, 0.06666667f, - 0.07083333f, 0.03333333f, -0.00416667f, - 0.275f, 0.1f, -0.075f - }; - // *INDENT-ON* + float data0_check[12] = {-0.3375f, -0.1f, 0.1375f, + -0.13333333f, -0.03333333f, 0.06666667f, + 0.07083333f, 0.03333333f, -0.00416667f, + 0.275f, 0.1f, -0.075f + }; Matrix A0(data0); Matrix A0_I = geninv(A0); @@ -792,13 +789,10 @@ bool MatrixTest::pseudoInverseTests() 3.f, 7.f, 11.f }; - // *INDENT-OFF* - float data1_check[12] = { - -0.3375f, -0.13333333f, 0.07083333f, 0.275f, - -0.1f, -0.03333333f, 0.03333333f, 0.1f, - 0.1375f, 0.06666667f, -0.00416667f, -0.075f - }; - // *INDENT-ON* + float data1_check[12] = {-0.3375f, -0.13333333f, 0.07083333f, 0.275f, + -0.1f, -0.03333333f, 0.03333333f, 0.1f, + 0.1375f, 0.06666667f, -0.00416667f, -0.075f + }; Matrix A1(data1); Matrix A1_I = geninv(A1); @@ -812,13 +806,10 @@ bool MatrixTest::pseudoInverseTests() 4, 5, 6, 7, 8, 10 }; - // *INDENT-OFF* - float data2_check[9] = { - -0.4f, -0.8f, 0.6f, - -0.4f, 4.2f, -2.4f, - 0.6f, -2.8f, 1.6f - }; - // *INDENT-ON* + float data2_check[9] = {-0.4f, -0.8f, 0.6f, + -0.4f, 4.2f, -2.4f, + 0.6f, -2.8f, 1.6f + }; SquareMatrix A2(data2); SquareMatrix A2_I = inv(A2);