Add more to Voxl2 build and fix associated build errors (#20821)

- Do not pull in PWM parameters when DISABLE_PARAMS_MODULE_SCOPING is TRUE since VOXL2 has no PWM nor any of the required timer_config files that go along with that
 - Replace non-standard M_PI constants with PX4 defined M_PI_F constants
 - Include missing header file for function hrt_absolute_time declaration
 - Add new PX4_SOC_ARCH_ID for the VOXL2 board
This commit is contained in:
Eric Katzfey 2022-12-22 12:44:19 -08:00 committed by GitHub
parent 35a9dba6e6
commit c3e70b03aa
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
11 changed files with 42 additions and 4 deletions

View File

@ -6,3 +6,10 @@ CONFIG_ORB_COMMUNICATOR=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_DRIVERS_QSHELL_QURT=y
CONFIG_DRIVERS_ACTUATORS_MODALAI_ESC=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_LAND_DETECTOR=y

View File

@ -31,6 +31,11 @@
#
############################################################################
# Need to make sure that the DSP processor on VOXL2
# knows about all parameters since some modules need parameters
# from other modules that are not running on the DSP.
set(DISABLE_PARAMS_MODULE_SCOPING TRUE PARENT_SCOPE)
add_library(drivers_board
board_config.h
init.c

View File

@ -9,3 +9,10 @@ CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_DRIVERS_QSHELL_POSIX=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_MAVLINK=y

View File

@ -31,6 +31,12 @@
#
############################################################################
# Need to make sure that the Linux processor on VOXL2
# knows about all parameters since it is acting as the
# parameter server for other processors that may define
# parameters that it doesn't normally know about.
set(DISABLE_PARAMS_MODULE_SCOPING TRUE PARENT_SCOPE)
add_library(drivers_board
board_config.h
init.c

View File

@ -47,3 +47,6 @@
#include <system_config.h>
#include <px4_platform_common/board_common.h>
#define BOARD_OVERRIDE_UUID "MODALAIVOXL20000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_VOXL2

View File

@ -351,6 +351,8 @@ typedef enum PX4_SOC_ARCH_ID_t {
PX4_SOC_ARCH_ID_BBBLUE = 0x1008,
PX4_SOC_ARCH_ID_VOXL2 = 0x100A,
} PX4_SOC_ARCH_ID_t;

View File

@ -47,7 +47,7 @@ namespace control
float BlockHighPass::update(float input)
{
float b = 2 * float(M_PI) * getFCut() * getDt();
float b = 2 * M_PI_F * getFCut() * getDt();
float a = 1 / (1 + b);
setY(a * (getY() + input - getU()));
setU(input);

View File

@ -51,7 +51,7 @@ float BlockLowPass::update(float input)
setState(input);
}
float b = 2 * float(M_PI) * getFCut() * getDt();
float b = 2 * M_PI_F * getFCut() * getDt();
float a = b / (1 + b);
setState(a * input + (1 - a)*getState());
return getState();

View File

@ -79,7 +79,7 @@ public:
}
}
float b = 2 * float(M_PI) * getFCut() * getDt();
float b = 2 * M_PI_F * getFCut() * getDt();
float a = b / (1 + b);
setState(input * a + getState() * (1 - a));
return getState();

View File

@ -57,7 +57,14 @@ if(DISABLE_PARAMS_MODULE_SCOPING)
${PX4_SOURCE_DIR}/src/*.yaml
)
foreach(file_path ${yaml_files})
list(APPEND module_config_files "${file_path}")
# VOXL2 doesn't support PWM and so it has no timer configurations
# that are expected when dealing with certain pwm modules. This will
# allow those timer configurations to be skipped.
if ((${PX4_BOARD_NAME} MATCHES "MODALAI_VOXL2") AND (file_path MATCHES pwm_out))
message(STATUS "Skipping pwm file path ${file_path} for VOXL2")
else()
list(APPEND module_config_files "${file_path}")
endif()
endforeach()
list(REMOVE_DUPLICATES module_config_files)

View File

@ -42,6 +42,7 @@
#include "DataValidator.hpp"
#include <px4_platform_common/log.h>
#include <drivers/drv_hrt.h>
void DataValidator::put(uint64_t timestamp, float val, uint32_t error_count_in, uint8_t priority_in)
{