Skip to content

Commit

Permalink
Merge branch 'main' into pr-force_mavlink_usb
Browse files Browse the repository at this point in the history
  • Loading branch information
dakejahl committed Nov 3, 2023
2 parents 2d7412a + 22ee90b commit 1b44427
Show file tree
Hide file tree
Showing 54 changed files with 62 additions and 52 deletions.
2 changes: 2 additions & 0 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -484,7 +484,9 @@ validate_module_configs:
@find "$(SRC_DIR)"/src/modules "$(SRC_DIR)"/src/drivers "$(SRC_DIR)"/src/lib -name *.yaml -type f \
-not -path "$(SRC_DIR)/src/lib/mixer_module/*" \
-not -path "$(SRC_DIR)/src/modules/uxrce_dds_client/dds_topics.yaml" \
-not -path "$(SRC_DIR)/src/modules/zenoh/zenoh-pico/*" \
-not -path "$(SRC_DIR)/src/lib/events/libevents/*" \
-not -path "$(SRC_DIR)/src/lib/cdrstream/*" \
-not -path "$(SRC_DIR)/src/lib/crypto/libtommath/*" -print0 | \
xargs -0 "$(SRC_DIR)"/Tools/validate_yaml.py --schema-file "$(SRC_DIR)"/validation/module_schema.yaml

Expand Down
4 changes: 2 additions & 2 deletions boards/airmind/mindpx-v2/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@ CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6500=y
CONFIG_DRIVERS_IMU_L3GD20=y
CONFIG_DRIVERS_IMU_LSM303D=y
CONFIG_DRIVERS_IMU_ST_L3GD20=y
CONFIG_DRIVERS_IMU_ST_LSM303D=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
Expand Down
4 changes: 2 additions & 2 deletions boards/av/x-v1/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_ADIS16477=y
CONFIG_DRIVERS_IMU_ADIS16497=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16477=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16497=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
Expand Down
4 changes: 2 additions & 2 deletions boards/nxp/fmuk66-v3/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@ CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_DRIVERS_DISTANCE_SENSOR_SRF05=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_FXAS21002C=y
CONFIG_DRIVERS_IMU_FXOS8701CQ=y
CONFIG_DRIVERS_IMU_NXP_FXAS21002C=y
CONFIG_DRIVERS_IMU_NXP_FXOS8701CQ=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y
Expand Down
4 changes: 2 additions & 2 deletions boards/px4/fmu-v2/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@ CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_MS5611=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_DRIVERS_IMU_L3GD20=y
CONFIG_DRIVERS_IMU_LSM303D=y
CONFIG_DRIVERS_IMU_ST_L3GD20=y
CONFIG_DRIVERS_IMU_ST_LSM303D=y
CONFIG_DRIVERS_LIGHTS_RGBLED=y
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
CONFIG_DRIVERS_PWM_OUT=y
Expand Down
5 changes: 3 additions & 2 deletions boards/px4/fmu-v3/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,9 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20608G=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_IMU_L3GD20=y
CONFIG_DRIVERS_IMU_LSM303D=y
CONFIG_DRIVERS_IMU_ST_L3GD20=y
CONFIG_DRIVERS_IMU_ST_LSM303D=y
CONFIG_COMMON_INS=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_PWM_INPUT=y
Expand Down
2 changes: 1 addition & 1 deletion platforms/common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@

set(SRCS)

if(NOT "${PX4_PLATFORM}" MATCHES "qurt" AND NOT "${PX4_BOARD}" MATCHES "io-v2" AND NOT "${PX4_BOARD_LABEL}" MATCHES "bootloader")
if(NOT "${PX4_PLATFORM}" MATCHES "qurt" AND NOT "${PX4_PLATFORM}" MATCHES "ros2" AND NOT "${PX4_BOARD}" MATCHES "io-v2" AND NOT "${PX4_BOARD_LABEL}" MATCHES "bootloader")
list(APPEND SRCS
px4_log.cpp
px4_log_history.cpp
Expand Down
14 changes: 7 additions & 7 deletions src/drivers/imu/Kconfig
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,14 @@ menu "IMU"
menuconfig COMMON_IMU
bool "Common IMU's"
default n
select DRIVERS_IMU_ADIS16477
select DRIVERS_IMU_ADIS16497
select DRIVERS_IMU_ANALOG_DEVICES_ADIS16477
select DRIVERS_IMU_ANALOG_DEVICES_ADIS16497
select DRIVERS_IMU_ANALOG_DEVICES_ADIS16448
select DRIVERS_IMU_ANALOG_DEVICES_ADIS16470
select DRIVERS_IMU_BOSCH_BMI055
select DRIVERS_IMU_BOSCH_BMI088
select DRIVERS_IMU_FXAS21002C
select DRIVERS_IMU_FXOS8701CQ
select DRIVERS_IMU_NXP_FXAS21002C
select DRIVERS_IMU_NXP_FXOS8701CQ
select DRIVERS_IMU_INVENSENSE_ICM20602
select DRIVERS_IMU_INVENSENSE_ICM20608G
select DRIVERS_IMU_INVENSENSE_ICM20649
Expand All @@ -21,9 +21,9 @@ menu "IMU"
select DRIVERS_IMU_INVENSENSE_MPU6000
select DRIVERS_IMU_INVENSENSE_MPU6500
select DRIVERS_IMU_INVENSENSE_MPU9250
select DRIVERS_IMU_L3GD20
select DRIVERS_IMU_LSM303D
select DRIVERS_IMU_ST
select DRIVERS_IMU_ST_L3GD20
select DRIVERS_IMU_ST_LSM303D
select DRIVERS_IMU_ST_LSM9DS1
---help---
Enable default set of IMU drivers
rsource "*/Kconfig"
Expand Down
5 changes: 0 additions & 5 deletions src/drivers/imu/adis16477/Kconfig

This file was deleted.

5 changes: 0 additions & 5 deletions src/drivers/imu/adis16497/Kconfig

This file was deleted.

2 changes: 1 addition & 1 deletion src/drivers/imu/analog_devices/Kconfig
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
menu "Analog Devices"
rsource "*/Kconfig"
endmenu
endmenu #Analog Devices
File renamed without changes.
File renamed without changes.
File renamed without changes.
5 changes: 5 additions & 0 deletions src/drivers/imu/analog_devices/adis16477/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
menuconfig DRIVERS_IMU_ANALOG_DEVICES_ADIS16477
bool "adis16477"
default n
---help---
Enable support for adis16477
File renamed without changes.
File renamed without changes.
File renamed without changes.
5 changes: 5 additions & 0 deletions src/drivers/imu/analog_devices/adis16497/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
menuconfig DRIVERS_IMU_ANALOG_DEVICES_ADIS16497
bool "adis16497"
default n
---help---
Enable support for adis16497
2 changes: 1 addition & 1 deletion src/drivers/imu/bosch/Kconfig
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
menu "Bosch"
rsource "*/Kconfig"
endmenu
endmenu #Bosch
5 changes: 0 additions & 5 deletions src/drivers/imu/fxas21002c/Kconfig

This file was deleted.

5 changes: 0 additions & 5 deletions src/drivers/imu/fxos8701cq/Kconfig

This file was deleted.

5 changes: 0 additions & 5 deletions src/drivers/imu/l3gd20/Kconfig

This file was deleted.

5 changes: 0 additions & 5 deletions src/drivers/imu/lsm303d/Kconfig

This file was deleted.

3 changes: 3 additions & 0 deletions src/drivers/imu/nxp/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
menu "NXP"
rsource "*/Kconfig"
endmenu #NXP
File renamed without changes.
File renamed without changes.
File renamed without changes.
5 changes: 5 additions & 0 deletions src/drivers/imu/nxp/fxas21002c/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
menuconfig DRIVERS_IMU_NXP_FXAS21002C
bool "fxas21002c"
default n
---help---
Enable support for fxas21002c
File renamed without changes.
File renamed without changes.
File renamed without changes.
5 changes: 5 additions & 0 deletions src/drivers/imu/nxp/fxos8701cq/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
menuconfig DRIVERS_IMU_NXP_FXOS8701CQ
bool "fxos8701cq"
default n
---help---
Enable support for fxos8701cq
2 changes: 1 addition & 1 deletion src/drivers/imu/st/Kconfig
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
menu "ST"
rsource "*/Kconfig"
endmenu #Invensense
endmenu #ST
File renamed without changes.
5 changes: 5 additions & 0 deletions src/drivers/imu/st/l3gd20/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
menuconfig DRIVERS_IMU_ST_L3GD20
bool "l3gd20"
default n
---help---
Enable support for l3gd20
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
5 changes: 5 additions & 0 deletions src/drivers/imu/st/lsm303d/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
menuconfig DRIVERS_IMU_ST_LSM303D
bool "lsm303d"
default n
---help---
Enable support for lsm303d
File renamed without changes.
File renamed without changes.
File renamed without changes.
4 changes: 4 additions & 0 deletions src/lib/parameters/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -201,4 +201,8 @@ if(${PX4_PLATFORM} STREQUAL "nuttx")
target_link_libraries(parameters PRIVATE flashparams)
endif()

if(${PX4_PLATFORM} STREQUAL "posix" OR ${PX4_PLATFORM} STREQUAL "ros2")
target_include_directories(parameters PRIVATE "${CMAKE_CURRENT_SOURCE_DIR}/../../../platforms/posix/include/")
endif()

px4_add_functional_gtest(SRC ParameterTest.cpp LINKLIBS parameters)
2 changes: 1 addition & 1 deletion src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1724,7 +1724,7 @@ MavlinkReceiver::handle_message_battery_status(mavlink_message_t *msg)

battery_status.voltage_v = voltage_sum;
battery_status.voltage_filtered_v = voltage_sum;
battery_status.current_a = battery_status.current_filtered_a = (float)(battery_mavlink.current_battery) / 100.0f;
battery_status.current_a = (float)(battery_mavlink.current_battery) / 100.0f;
battery_status.current_filtered_a = battery_status.current_a;
battery_status.remaining = (float)battery_mavlink.battery_remaining / 100.0f;
battery_status.discharged_mah = (float)battery_mavlink.current_consumed;
Expand Down

0 comments on commit 1b44427

Please sign in to comment.