forked from Archive/PX4-Autopilot
Fix trailing whitespace, EOF newline, indentation
This commit is contained in:
parent
1d3da86abb
commit
904ab16558
|
@ -71,4 +71,3 @@ CONFIG:
|
||||||
buildType: MinSizeRel
|
buildType: MinSizeRel
|
||||||
settings:
|
settings:
|
||||||
CONFIG: holybro_durandal-v1_default
|
CONFIG: holybro_durandal-v1_default
|
||||||
|
|
|
@ -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)
|
* [Pixhawk 3 Pro](https://docs.px4.io/master/en/flight_controller/pixhawk3_pro.html)
|
||||||
* FMUv5 (ARM Cortex M7)
|
* FMUv5 (ARM Cortex M7)
|
||||||
* [Pixhawk 4](https://docs.px4.io/master/en/flight_controller/pixhawk4.html)
|
* [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+](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)
|
* [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)
|
* [Airmind MindPX V2.8](http://www.mindpx.net/assets/accessories/UserGuide_MindPX.pdf)
|
||||||
|
|
|
@ -30,7 +30,7 @@ set PWM_OUT 12345678
|
||||||
|
|
||||||
if [ $AUTOCNF = yes ]
|
if [ $AUTOCNF = yes ]
|
||||||
then
|
then
|
||||||
###############################################
|
###############################################
|
||||||
# Attitude & rate gains
|
# Attitude & rate gains
|
||||||
###############################################
|
###############################################
|
||||||
# Roll
|
# Roll
|
||||||
|
@ -53,7 +53,7 @@ then
|
||||||
param set MC_YAW_FF 0.00000
|
param set MC_YAW_FF 0.00000
|
||||||
param set MC_YAWRATE_MAX 700.00000
|
param set MC_YAWRATE_MAX 700.00000
|
||||||
|
|
||||||
###############################################
|
###############################################
|
||||||
# Multirotor Position Gains
|
# Multirotor Position Gains
|
||||||
###############################################
|
###############################################
|
||||||
param set MPC_ACC_HOR 8.0000
|
param set MPC_ACC_HOR 8.0000
|
||||||
|
@ -138,7 +138,7 @@ then
|
||||||
param set MAV_1_FORWARD 1
|
param set MAV_1_FORWARD 1
|
||||||
param set MAV_1_RATE 800000
|
param set MAV_1_RATE 800000
|
||||||
param set SER_TEL2_BAUD 921600
|
param set SER_TEL2_BAUD 921600
|
||||||
|
|
||||||
# Disable internal magnetometer sensor
|
# Disable internal magnetometer sensor
|
||||||
param set CAL_MAG0_EN 0
|
param set CAL_MAG0_EN 0
|
||||||
# Enable external magnetometer sensor
|
# Enable external magnetometer sensor
|
||||||
|
|
|
@ -51,7 +51,7 @@ fi
|
||||||
# be running from last time
|
# be running from last time
|
||||||
pkill -x gazebo || true
|
pkill -x gazebo || true
|
||||||
|
|
||||||
# Do NOT kill PX4 if debug in ide
|
# Do NOT kill PX4 if debug in ide
|
||||||
if [ "$debugger" != "ide" ]; then
|
if [ "$debugger" != "ide" ]; then
|
||||||
pkill -x px4 || true
|
pkill -x px4 || true
|
||||||
pkill -x px4_$model || true
|
pkill -x px4_$model || true
|
||||||
|
|
|
@ -15,4 +15,3 @@ config BOARD_USE_PROBES
|
||||||
|
|
||||||
---help---
|
---help---
|
||||||
Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers.
|
Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers.
|
||||||
|
|
||||||
|
|
|
@ -15,5 +15,3 @@ config BOARD_USE_PROBES
|
||||||
|
|
||||||
---help---
|
---help---
|
||||||
Select to use GPIO FMU-CH1-6 to provide timing signals from selected drivers.
|
Select to use GPIO FMU-CH1-6 to provide timing signals from selected drivers.
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -43,4 +43,3 @@ add_subdirectory(../stm32_common/tone_alarm tone_alarm)
|
||||||
add_subdirectory(../stm32_common/version version)
|
add_subdirectory(../stm32_common/version version)
|
||||||
|
|
||||||
add_subdirectory(px4io_serial)
|
add_subdirectory(px4io_serial)
|
||||||
|
|
||||||
|
|
|
@ -56,4 +56,3 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include <px4_platform/adc.h>
|
#include <px4_platform/adc.h>
|
||||||
|
|
||||||
|
|
|
@ -32,6 +32,4 @@
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
|
||||||
#include "../../../stm32_common/include/px4_arch/io_timer.h"
|
#include "../../../stm32_common/include/px4_arch/io_timer.h"
|
||||||
|
|
||||||
|
|
|
@ -54,4 +54,3 @@ int stm32h7_flash_writeprotect(size_t block, bool enabled);
|
||||||
#define stm32_flash_lock() stm32h7_flash_lock(PX4_FLASH_BASE)
|
#define stm32_flash_lock() stm32h7_flash_lock(PX4_FLASH_BASE)
|
||||||
|
|
||||||
__END_DECLS
|
__END_DECLS
|
||||||
|
|
||||||
|
|
|
@ -35,4 +35,3 @@
|
||||||
|
|
||||||
#define PX4IO_SERIAL_BUF_ALIGN ARMV7M_DCACHE_LINESIZE
|
#define PX4IO_SERIAL_BUF_ALIGN ARMV7M_DCACHE_LINESIZE
|
||||||
#include "../../../stm32_common/include/px4_arch/px4io_serial.h"
|
#include "../../../stm32_common/include/px4_arch/px4io_serial.h"
|
||||||
|
|
||||||
|
|
|
@ -545,4 +545,3 @@ ArchPX4IOSerial::_abort_dma()
|
||||||
|
|
||||||
rICR = rISR & rISR_ERR_FLAGS_MASK; /* clear the flags */
|
rICR = rISR & rISR_ERR_FLAGS_MASK; /* clear the flags */
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -37,4 +37,3 @@ uint32_t px4_arch_adc_dn_fullcount(void)
|
||||||
{
|
{
|
||||||
return 1 << 12; // 12 bit ADC
|
return 1 << 12; // 12 bit ADC
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
# libuavcan_kinetis
|
# libuavcan_kinetis
|
||||||
Libuavcan platform driver for Kinetis FlexCAN
|
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:
|
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
|
2. Build time command line configuartion clock source
|
||||||
- Curently the driver use `const uavcan::uint8_t CLOCKSEL = 0;` To Select OSCERCLK
|
- 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
|
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 */
|
/* Layout of Fifo, filters and Message buffers */
|
||||||
|
|
|
@ -14,4 +14,3 @@ install(DIRECTORY include/uavcan_kinetis DESTINATION include)
|
||||||
install(TARGETS uavcan_kinetis_driver DESTINATION lib)
|
install(TARGETS uavcan_kinetis_driver DESTINATION lib)
|
||||||
|
|
||||||
# vim: set et ft=cmake fenc=utf-8 ff=unix sts=4 sw=4 ts=4 :)
|
# vim: set et ft=cmake fenc=utf-8 ff=unix sts=4 sw=4 ts=4 :)
|
||||||
|
|
||||||
|
|
|
@ -14,4 +14,3 @@ install(DIRECTORY include/uavcan_stm32 DESTINATION include)
|
||||||
install(TARGETS uavcan_stm32_driver DESTINATION lib)
|
install(TARGETS uavcan_stm32_driver DESTINATION lib)
|
||||||
|
|
||||||
# vim: set et ft=cmake fenc=utf-8 ff=unix sts=4 sw=4 ts=4 :)
|
# vim: set et ft=cmake fenc=utf-8 ff=unix sts=4 sw=4 ts=4 :)
|
||||||
|
|
||||||
|
|
|
@ -182,4 +182,3 @@ private:
|
||||||
matrix::Vector3f _acro_rate_max; /**< max attitude rates in acro mode */
|
matrix::Vector3f _acro_rate_max; /**< max attitude rates in acro mode */
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -412,4 +412,3 @@ PARAM_DEFINE_INT32(MC_BAT_SCALE_EN, 0);
|
||||||
* @group Multicopter Rate Control
|
* @group Multicopter Rate Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(MC_DTERM_CUTOFF, 0.f);
|
PARAM_DEFINE_FLOAT(MC_DTERM_CUTOFF, 0.f);
|
||||||
|
|
||||||
|
|
|
@ -71,4 +71,3 @@ PARAM_DEFINE_FLOAT(CAL_GYRO0_YOFF, 0.0f);
|
||||||
* @group Sensor Calibration
|
* @group Sensor Calibration
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_ZOFF, 0.0f);
|
PARAM_DEFINE_FLOAT(CAL_GYRO0_ZOFF, 0.0f);
|
||||||
|
|
||||||
|
|
|
@ -71,4 +71,3 @@ PARAM_DEFINE_FLOAT(CAL_GYRO1_YOFF, 0.0f);
|
||||||
* @group Sensor Calibration
|
* @group Sensor Calibration
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_ZOFF, 0.0f);
|
PARAM_DEFINE_FLOAT(CAL_GYRO1_ZOFF, 0.0f);
|
||||||
|
|
||||||
|
|
|
@ -71,4 +71,3 @@ PARAM_DEFINE_FLOAT(CAL_GYRO2_YOFF, 0.0f);
|
||||||
* @group Sensor Calibration
|
* @group Sensor Calibration
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_ZOFF, 0.0f);
|
PARAM_DEFINE_FLOAT(CAL_GYRO2_ZOFF, 0.0f);
|
||||||
|
|
||||||
|
|
|
@ -769,14 +769,11 @@ bool MatrixTest::pseudoInverseTests()
|
||||||
8.f, 9.f, 10.f, 11.f
|
8.f, 9.f, 10.f, 11.f
|
||||||
};
|
};
|
||||||
|
|
||||||
// *INDENT-OFF*
|
float data0_check[12] = {-0.3375f, -0.1f, 0.1375f,
|
||||||
float data0_check[12] = {
|
-0.13333333f, -0.03333333f, 0.06666667f,
|
||||||
-0.3375f, -0.1f, 0.1375f,
|
0.07083333f, 0.03333333f, -0.00416667f,
|
||||||
-0.13333333f, -0.03333333f, 0.06666667f,
|
0.275f, 0.1f, -0.075f
|
||||||
0.07083333f, 0.03333333f, -0.00416667f,
|
};
|
||||||
0.275f, 0.1f, -0.075f
|
|
||||||
};
|
|
||||||
// *INDENT-ON*
|
|
||||||
|
|
||||||
Matrix<float, 3, 4> A0(data0);
|
Matrix<float, 3, 4> A0(data0);
|
||||||
Matrix<float, 4, 3> A0_I = geninv(A0);
|
Matrix<float, 4, 3> A0_I = geninv(A0);
|
||||||
|
@ -792,13 +789,10 @@ bool MatrixTest::pseudoInverseTests()
|
||||||
3.f, 7.f, 11.f
|
3.f, 7.f, 11.f
|
||||||
};
|
};
|
||||||
|
|
||||||
// *INDENT-OFF*
|
float data1_check[12] = {-0.3375f, -0.13333333f, 0.07083333f, 0.275f,
|
||||||
float data1_check[12] = {
|
-0.1f, -0.03333333f, 0.03333333f, 0.1f,
|
||||||
-0.3375f, -0.13333333f, 0.07083333f, 0.275f,
|
0.1375f, 0.06666667f, -0.00416667f, -0.075f
|
||||||
-0.1f, -0.03333333f, 0.03333333f, 0.1f,
|
};
|
||||||
0.1375f, 0.06666667f, -0.00416667f, -0.075f
|
|
||||||
};
|
|
||||||
// *INDENT-ON*
|
|
||||||
|
|
||||||
Matrix<float, 4, 3> A1(data1);
|
Matrix<float, 4, 3> A1(data1);
|
||||||
Matrix<float, 3, 4> A1_I = geninv(A1);
|
Matrix<float, 3, 4> A1_I = geninv(A1);
|
||||||
|
@ -812,13 +806,10 @@ bool MatrixTest::pseudoInverseTests()
|
||||||
4, 5, 6,
|
4, 5, 6,
|
||||||
7, 8, 10
|
7, 8, 10
|
||||||
};
|
};
|
||||||
// *INDENT-OFF*
|
float data2_check[9] = {-0.4f, -0.8f, 0.6f,
|
||||||
float data2_check[9] = {
|
-0.4f, 4.2f, -2.4f,
|
||||||
-0.4f, -0.8f, 0.6f,
|
0.6f, -2.8f, 1.6f
|
||||||
-0.4f, 4.2f, -2.4f,
|
};
|
||||||
0.6f, -2.8f, 1.6f
|
|
||||||
};
|
|
||||||
// *INDENT-ON*
|
|
||||||
|
|
||||||
SquareMatrix<float, 3> A2(data2);
|
SquareMatrix<float, 3> A2(data2);
|
||||||
SquareMatrix<float, 3> A2_I = inv(A2);
|
SquareMatrix<float, 3> A2_I = inv(A2);
|
||||||
|
|
Loading…
Reference in New Issue