Skip to content

Commit

Permalink
Merge remote-tracking branch 'px4/master' into pr-sensors_accel_gyro_…
Browse files Browse the repository at this point in the history
…calibration_cleanup
  • Loading branch information
dagar committed Jun 18, 2020
2 parents bc34c71 + 588d551 commit 44d2f11
Show file tree
Hide file tree
Showing 132 changed files with 3,931 additions and 3,856 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/sitl_tests.yml
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@ jobs:
with:
token: ${{ secrets.ACCESS_TOKEN }}
- name: Download MAVSDK
run: wget https://github.com/mavlink/MAVSDK/releases/download/v0.24.0/mavsdk_0.24.0_ubuntu18.04_amd64.deb
run: wget https://github.com/mavlink/MAVSDK/releases/download/v0.27.0/mavsdk_0.27.0_ubuntu18.04_amd64.deb
- name: Install MAVSDK
run: dpkg -i mavsdk_0.24.0_ubuntu18.04_amd64.deb
run: dpkg -i mavsdk_0.27.0_ubuntu18.04_amd64.deb
- uses: actions/cache@v1.1.0
id: ccache-persistence
with:
Expand Down
7 changes: 6 additions & 1 deletion ROMFS/px4fmu_common/init.d-posix/10020_if750a
Original file line number Diff line number Diff line change
Expand Up @@ -8,5 +8,10 @@

sh /etc/init.d/rc.mc_defaults

set MIXER quad_x
if [ $AUTOCNF = yes ]
then
# EKF2: Multi GPS blending (as the model has 2 GPS's)
param set EKF2_GPS_MASK 7 # Uses speed, hpos and vpos accuracy
fi

set MIXER quad_x
14 changes: 14 additions & 0 deletions ROMFS/px4fmu_common/init.d-posix/1019_iris_dual_gps
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
#!/bin/sh
#
# @name 3DR Iris Quadrotor SITL (Dual GPS)
#
# @type Quadrotor Wide
#

sh /etc/init.d-posix/10016_iris

if [ $AUTOCNF = yes ]
then
# EKF2: Multi GPS blending
param set EKF2_GPS_MASK 7 # Uses speed, hpos and vpos accuracy
fi
5 changes: 3 additions & 2 deletions ROMFS/px4fmu_common/init.d-posix/1042_tiltrotor
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,9 @@ then

param set VT_F_TRANS_DUR 5.0
param set VT_F_TRANS_THR 0.75
param set VT_TILT_FW 3.1415
param set VT_TILT_TRANS 1.2
param set VT_FWD_THRUST_SC 1.1
param set VT_TILT_FW 1
param set VT_TILT_TRANS 0.6
param set VT_ELEV_MC_LOCK 0
param set VT_TYPE 1
param set VT_B_TRANS_DUR 8
Expand Down
66 changes: 39 additions & 27 deletions ROMFS/px4fmu_common/init.d/rc.sensors
Original file line number Diff line number Diff line change
Expand Up @@ -21,31 +21,6 @@ fi
# Begin Optional drivers #
###############################################################################

if [ ${VEHICLE_TYPE} = fw -o ${VEHICLE_TYPE} = vtol ]
then
if param compare CBRK_AIRSPD_CHK 0
then
sdp3x_airspeed start -X
sdp3x_airspeed start -X -a 0x22

# Pixhawk 2.1 has a MS5611 on I2C which gets wrongly
# detected as MS5525 because the chip manufacturer was so
# clever to assign the same I2C address and skip a WHO_AM_I
# register.
if [ $BOARD_FMUV3 = 21 ]
then
ms5525_airspeed start -X -b 2
else
ms5525_airspeed start -X
fi

ms4525_airspeed start -X

ets_airspeed start -X

fi
fi

if param compare -s SENS_EN_BATT 1
then
batt_smbus start -X
Expand Down Expand Up @@ -120,10 +95,47 @@ then
paw3902 -S start
fi

# probe for optional external I2C devices
if param compare SENS_EXT_I2C_PRB 1
then
# compasses
ak09916 -X -R 6 start # external AK09916 (Here2) is rotated 270 degrees yaw
hmc5883 -T -X start
ist8308 -X start
ist8310 -X start
lis2mdl -X start
lis3mdl -X start
qmc5883 -X start
rm3100 -X start

# differential pressure sensors
if [ ${VEHICLE_TYPE} = fw -o ${VEHICLE_TYPE} = vtol ]
then
if param compare CBRK_AIRSPD_CHK 0
then
sdp3x_airspeed start -X
sdp3x_airspeed start -X -a 0x22

# Pixhawk 2.1 has a MS5611 on I2C which gets wrongly
# detected as MS5525 because the chip manufacturer was so
# clever to assign the same I2C address and skip a WHO_AM_I
# register.
if [ $BOARD_FMUV3 = 21 ]
then
ms5525_airspeed start -X -b 2
else
ms5525_airspeed start -X
fi

ms4525_airspeed start -X

ets_airspeed start -X
fi
fi
fi

###############################################################################
# End Optional drivers #
###############################################################################

# Wait 20 ms for sensors (because we need to wait for the HRT and work queue callbacks to fire)
usleep 20000
sensors start
18 changes: 9 additions & 9 deletions Tools/process_sensor_caldata.py
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ def is_valid_directory(parser, arg):
plt.subplot(3,1,1)
plt.plot(sensor_gyro_0['temperature'],sensor_gyro_0['x'],'b')
plt.plot(temp_resample,gyro_0_x_resample,'r')
plt.title('Gyro 0 Bias vs Temperature')
plt.title('Gyro 0 ({}) Bias vs Temperature'.format(gyro_0_params['TC_G0_ID']))
plt.ylabel('X bias (rad/s)')
plt.xlabel('temperature (degC)')
plt.grid()
Expand Down Expand Up @@ -264,7 +264,7 @@ def is_valid_directory(parser, arg):
plt.subplot(3,1,1)
plt.plot(sensor_gyro_1['temperature'],sensor_gyro_1['x'],'b')
plt.plot(temp_resample,gyro_1_x_resample,'r')
plt.title('Gyro 1 Bias vs Temperature')
plt.title('Gyro 1 ({}) Bias vs Temperature'.format(gyro_1_params['TC_G1_ID']))
plt.ylabel('X bias (rad/s)')
plt.xlabel('temperature (degC)')
plt.grid()
Expand Down Expand Up @@ -357,7 +357,7 @@ def is_valid_directory(parser, arg):
plt.subplot(3,1,1)
plt.plot(sensor_gyro_2['temperature'],sensor_gyro_2['x'],'b')
plt.plot(temp_resample,gyro_2_x_resample,'r')
plt.title('Gyro 2 Bias vs Temperature')
plt.title('Gyro 2 ({}) Bias vs Temperature'.format(gyro_2_params['TC_G2_ID']))
plt.ylabel('X bias (rad/s)')
plt.xlabel('temperature (degC)')
plt.grid()
Expand Down Expand Up @@ -453,7 +453,7 @@ def is_valid_directory(parser, arg):
plt.subplot(3,1,1)
plt.plot(sensor_accel_0['temperature'],correction_x,'b')
plt.plot(temp_resample,correction_x_resample,'r')
plt.title('Accel 0 Bias vs Temperature')
plt.title('Accel 0 ({}) Bias vs Temperature'.format(accel_0_params['TC_A0_ID']))
plt.ylabel('X bias (m/s/s)')
plt.xlabel('temperature (degC)')
plt.grid()
Expand Down Expand Up @@ -549,7 +549,7 @@ def is_valid_directory(parser, arg):
plt.subplot(3,1,1)
plt.plot(sensor_accel_1['temperature'],correction_x,'b')
plt.plot(temp_resample,correction_x_resample,'r')
plt.title('Accel 1 Bias vs Temperature')
plt.title('Accel 1 ({}) Bias vs Temperature'.format(accel_1_params['TC_A1_ID']))
plt.ylabel('X bias (m/s/s)')
plt.xlabel('temperature (degC)')
plt.grid()
Expand Down Expand Up @@ -645,7 +645,7 @@ def is_valid_directory(parser, arg):
plt.subplot(3,1,1)
plt.plot(sensor_accel_2['temperature'],correction_x,'b')
plt.plot(temp_resample,correction_x_resample,'r')
plt.title('Accel 2 Bias vs Temperature')
plt.title('Accel 2 ({}) Bias vs Temperature'.format(accel_2_params['TC_A2_ID']))
plt.ylabel('X bias (m/s/s)')
plt.xlabel('temperature (degC)')
plt.grid()
Expand Down Expand Up @@ -715,7 +715,7 @@ def is_valid_directory(parser, arg):
# draw plots
plt.plot(sensor_baro_0['temperature'],100*sensor_baro_0['pressure']-100*median_pressure,'b')
plt.plot(temp_resample,baro_0_x_resample,'r')
plt.title('Baro 0 Bias vs Temperature')
plt.title('Baro 0 ({}) Bias vs Temperature'.format(baro_0_params['TC_B0_ID']))
plt.ylabel('Z bias (Pa)')
plt.xlabel('temperature (degC)')
plt.grid()
Expand Down Expand Up @@ -767,7 +767,7 @@ def is_valid_directory(parser, arg):
# draw plots
plt.plot(sensor_baro_1['temperature'],100*sensor_baro_1['pressure']-100*median_pressure,'b')
plt.plot(temp_resample,baro_1_x_resample,'r')
plt.title('Baro 1 Bias vs Temperature')
plt.title('Baro 1 ({}) Bias vs Temperature'.format(baro_1_params['TC_B1_ID']))
plt.ylabel('Z bias (Pa)')
plt.xlabel('temperature (degC)')
plt.grid()
Expand Down Expand Up @@ -820,7 +820,7 @@ def is_valid_directory(parser, arg):
# draw plots
plt.plot(sensor_baro_2['temperature'],100*sensor_baro_2['pressure']-100*median_pressure,'b')
plt.plot(temp_resample,baro_2_x_resample,'r')
plt.title('Baro 2 Bias vs Temperature')
plt.title('Baro 2 ({}) Bias vs Temperature'.format(baro_2_params['TC_B2_ID']))
plt.ylabel('Z bias (Pa)')
plt.xlabel('temperature (degC)')
plt.grid()
Expand Down
1 change: 1 addition & 0 deletions Tools/setup/ubuntu.sh
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,7 @@ if [[ $INSTALL_NUTTX == "true" ]]; then
libncurses-dev \
libtool \
pkg-config \
screen \
vim-common \
;

Expand Down
2 changes: 1 addition & 1 deletion Tools/sitl_gazebo
4 changes: 0 additions & 4 deletions boards/airmind/mindpx-v2/init/rc.board_sensors
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,6 @@

adc start

# External I2C bus
hmc5883 -T -X start
qmc5883 -X start

# Internal I2C bus
hmc5883 -T -I -R 12 start
qmc5883 -I -R 12 start
Expand Down
5 changes: 0 additions & 5 deletions boards/av/x-v1/init/rc.board_sensors
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,3 @@ then
# try to start adis16497 only if pmw3901 isn't enabled, or parameter doesn't exists
adis16497 -S start
fi

# Possible external compasses
ist8310 -X start
hmc5883 -T -X start
qmc5883 -X start
4 changes: 2 additions & 2 deletions boards/bitcraze/crazyflie/init/rc.board_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,6 @@ fi

if [ $AUTOCNF = yes ]
then

# don't probe external I2C
param set SENS_EXT_I2C_PRB 0
fi

4 changes: 3 additions & 1 deletion boards/cuav/x7pro/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -32,13 +32,14 @@ px4_add_board(
imu/adis16448
imu/adis16477
imu/adis16497
imu/bmi088
imu/bosch/bmi088
imu/invensense/icm20649
imu/invensense/icm20689
irlock
lights/blinkm
lights/rgbled
lights/rgbled_ncp5623c
lights/rgbled_pwm
magnetometer # all available magnetometer drivers
mkblctrl
optical_flow # all available optical flow drivers
Expand All @@ -50,6 +51,7 @@ px4_add_board(
pwm_out
rc_input
roboclaw
safety_button
tap_esc
telemetry # all available telemetry drivers
test_ppm
Expand Down
3 changes: 3 additions & 0 deletions boards/cuav/x7pro/init/rc.board_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -36,3 +36,6 @@ then
fi

set LOGGER_BUF 64

rgbled_pwm start
safety_button start
7 changes: 0 additions & 7 deletions boards/cuav/x7pro/init/rc.board_sensors
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,3 @@ ms5611 -s -b 4 start
# SPI6 (internal)
icm20649 -s -b 6 -R 2 start
ms5611 -s -b 6 start


# Possible external compasses
ist8310 -X start
hmc5883 -T -X start
qmc5883 -X start
lis3mdl -X start
24 changes: 12 additions & 12 deletions boards/cuav/x7pro/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,7 @@
#define GPIO_nLED_GREEN /* PI6 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN6)
#define GPIO_nLED_BLUE /* PI7 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN7)

#define BOARD_HAS_CONTROL_STATUS_LEDS 1
#define BOARD_OVERLOAD_LED LED_RED
#define BOARD_ARMED_STATE_LED LED_BLUE
#define BOARD_HAS_LED_PWM 1

/* ADC channels */
#define PX4_ADC_GPIO \
Expand Down Expand Up @@ -122,17 +120,17 @@
#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_ADC /* Brick 2 is Chosen */
#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB is Chosen */

#define GPIO_nVDD_5V_HIPOWER_EN /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11)
#define GPIO_VDD_5V_HIPOWER_EN /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11)
#define GPIO_nVDD_5V_PERIPH_EN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4)
#define GPIO_VDD_5V_RC_EN /* PG5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN5)
#define GPIO_VDD_3V3_SD_CARD_EN /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN7)

#define GPIO_nVDD_5V_HIPOWER_OC /* PJ3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTJ|GPIO_PIN3)
#define GPIO_VDD_5V_HIPOWER_OC /* PJ3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTJ|GPIO_PIN3)
#define GPIO_nVDD_5V_PERIPH_OC /* PJ4 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTJ|GPIO_PIN4)

/* Power switch controls ******************************************************/
#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, !(on_true))
#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_HIPOWER_EN, !(on_true))
#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_EN, (on_true))
#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true))

#define SPEKTRUM_POWER(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_RC_EN, (on_true))
Expand Down Expand Up @@ -176,10 +174,12 @@
/* RSSI_IN */
#define GPIO_RSSI_IN /* PB0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)

/* Safety Switch is only on PX4IO */
#define GPIO_nSAFETY_SWITCH_LED_OUT /* PE12 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN12) // FMU_LED_AMBER
/* Safety Switch is only on FMU */
#define FMU_LED_AMBER /* PE12 */ (GPIO_OUTPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN12) // FMU_LED_AMBER
#define GPIO_BTN_SAFETY /* PE10 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN10) // SAFETY_SW

#define GPIO_LED_SAFETY FMU_LED_AMBER

/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore
* provides the true logic GPIO BOARD_ADC_xxxx macros.
Expand All @@ -189,7 +189,7 @@
#define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
#define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID))
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_PERIPH_OC))
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_HIPOWER_OC))
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_OC))


/* This board provides a DMA pool and APIs */
Expand Down Expand Up @@ -220,8 +220,8 @@
GPIO_nPOWER_IN_C, \
GPIO_nVDD_5V_PERIPH_EN, \
GPIO_nVDD_5V_PERIPH_OC, \
GPIO_nVDD_5V_HIPOWER_EN, \
GPIO_nVDD_5V_HIPOWER_OC, \
GPIO_VDD_5V_HIPOWER_EN, \
GPIO_VDD_5V_HIPOWER_OC, \
GPIO_VDD_5V_RC_EN, \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1), \
Expand All @@ -233,7 +233,7 @@
GPIO_OTGFS_VBUS, \
PX4_GPIO_PIN_OFF(GPIO_HS_USB_EN), \
GPIO_RSSI_IN, \
GPIO_nSAFETY_SWITCH_LED_OUT, \
FMU_LED_AMBER, \
GPIO_BTN_SAFETY, \
}

Expand Down
7 changes: 1 addition & 6 deletions boards/cuav/x7pro/src/led.c
Original file line number Diff line number Diff line change
Expand Up @@ -64,17 +64,12 @@ __END_DECLS

# define xlat(p) (p)
static uint32_t g_ledmap[] = {
GPIO_nLED_BLUE, // Indexed by LED_BLUE
GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER
GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY (defaulted to an input)
GPIO_nLED_GREEN, // Indexed by LED_GREEN
FMU_LED_AMBER, // Indexed by LED_SAFETY (defaulted to an output)
};

__EXPORT void led_init(void)
{
/* Configure LED GPIOs for output */
g_ledmap[2] = GPIO_nSAFETY_SWITCH_LED_OUT;

for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
if (g_ledmap[l] != 0) {
stm32_configgpio(g_ledmap[l]);
Expand Down
Loading

0 comments on commit 44d2f11

Please sign in to comment.