Skip to content

Commit

Permalink
Merge branch 'main' into display-x11-docker
Browse files Browse the repository at this point in the history
  • Loading branch information
Martin-Schlodinski authored Aug 25, 2024
2 parents dabe0c0 + 510d3cf commit 8edbd42
Show file tree
Hide file tree
Showing 10 changed files with 755 additions and 741 deletions.
10 changes: 9 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -113,12 +113,20 @@ include(px4_parse_function_args)
include(px4_git)

execute_process(
COMMAND git describe --exclude ext/* --always --tags
COMMAND git describe --exclude ext/* --tags --match "v[0-9]*"
OUTPUT_VARIABLE PX4_GIT_TAG
OUTPUT_STRIP_TRAILING_WHITESPACE
RESULTS_VARIABLE GIT_DESCRIBE_RESULT
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)

# if proper git tag unavilable default to v0.0.0
if(NOT ${GIT_DESCRIBE_RESULT} MATCHES "0")
set(PX4_GIT_TAG "v0.0.0")
endif()

message(STATUS "PX4_GIT_TAG: ${PX4_GIT_TAG}")

# git describe to X.Y.Z version
string(REPLACE "." ";" VERSION_LIST ${PX4_GIT_TAG})

Expand Down
3 changes: 2 additions & 1 deletion src/lib/version/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,8 @@ endif()

set(px4_git_ver_header ${CMAKE_CURRENT_BINARY_DIR}/build_git_version.h)
add_custom_command(OUTPUT ${px4_git_ver_header}
COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/px_update_git_header.py ${px4_git_ver_header} --validate
COMMAND
${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/px_update_git_header.py ${px4_git_ver_header} --validate --git_tag '${PX4_GIT_TAG}'
DEPENDS
${CMAKE_CURRENT_SOURCE_DIR}/px_update_git_header.py
${git_dir_path}/HEAD
Expand Down
26 changes: 10 additions & 16 deletions src/lib/version/px_update_git_header.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
generate a version header file. The working directory is expected to be
the root of Firmware.""")
parser.add_argument('filename', metavar='version.h', help='Header output file')
parser.add_argument('--git_tag', help='git tag string')
parser.add_argument('-v', '--verbose', dest='verbose', action='store_true',
help='Verbose output', default=False)
parser.add_argument('--validate', dest='validate', action='store_true',
Expand All @@ -36,8 +37,11 @@


# PX4
git_describe_cmd = 'git describe --exclude ext/* --always --tags --dirty'
git_tag = subprocess.check_output(git_describe_cmd.split(),
if args.git_tag:
git_tag = args.git_tag
else:
git_describe_cmd = 'git describe --exclude ext/* --always --tags --dirty'
git_tag = subprocess.check_output(git_describe_cmd.split(),
stderr=subprocess.STDOUT).decode('utf-8').strip()

try:
Expand All @@ -57,17 +61,7 @@
# now check the version format
m = re.match(r'v([0-9]+)\.([0-9]+)\.[0-9]+(((-dev)|(-alpha[0-9]+)|(-beta[0-9]+)|(-rc[0-9]+))|'\
r'(-[0-9]+\.[0-9]+\.[0-9]+((-dev)|(-alpha[0-9]+)|(-beta[0-9]+)|([-]?rc[0-9]+))?))?$', git_tag_test)
if m:
# format matches, check the major and minor numbers
major = int(m.group(1))
minor = int(m.group(2))
if major < 1 or (major == 1 and minor < 9):
print("")
print("Error: PX4 version too low, expected at least v1.9.0")
print("Check the git tag (current tag: '{:}')".format(git_tag_test))
print("")
sys.exit(1)
else:
if not m:
print("")
print("Error: the git tag '{:}' does not match the expected format.".format(git_tag_test))
print("")
Expand Down Expand Up @@ -103,9 +97,9 @@
if tag_or_branch is None:
# replace / so it can be used as directory name
tag_or_branch = git_branch_name.replace('/', '-')
# either a release or master branch (used for metadata)
# either a release or main branch (used for metadata)
if not tag_or_branch.startswith('release-'):
tag_or_branch = 'master'
tag_or_branch = 'main'

header += f"""
#define PX4_GIT_VERSION_STR "{git_version}"
Expand All @@ -115,7 +109,7 @@
#define PX4_GIT_OEM_VERSION_STR "{oem_tag}"
#define PX4_GIT_TAG_OR_BRANCH_NAME "{tag_or_branch}" // special variable: git tag, release or master branch
#define PX4_GIT_TAG_OR_BRANCH_NAME "{tag_or_branch}" // special variable: git tag, release or main branch
"""


Expand Down
27 changes: 14 additions & 13 deletions src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -698,11 +698,23 @@ Commander::Commander() :
// default for vtol is rotary wing
_vtol_vehicle_status.vehicle_vtol_state = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC;

_param_mav_comp_id = param_find("MAV_COMP_ID");
_param_mav_sys_id = param_find("MAV_SYS_ID");
param_t param_mav_comp_id = param_find("MAV_COMP_ID");
param_t param_mav_sys_id = param_find("MAV_SYS_ID");
_param_mav_type = param_find("MAV_TYPE");
_param_rc_map_fltmode = param_find("RC_MAP_FLTMODE");

int32_t value_int32 = 0;

// MAV_SYS_ID => vehicle_status.system_id
if ((param_mav_sys_id != PARAM_INVALID) && (param_get(param_mav_sys_id, &value_int32) == PX4_OK)) {
_vehicle_status.system_id = value_int32;
}

// MAV_COMP_ID => vehicle_status.component_id
if ((param_mav_comp_id != PARAM_INVALID) && (param_get(param_mav_comp_id, &value_int32) == PX4_OK)) {
_vehicle_status.component_id = value_int32;
}

updateParameters();
}

Expand Down Expand Up @@ -1682,22 +1694,11 @@ void Commander::updateParameters()

int32_t value_int32 = 0;

// MAV_SYS_ID => vehicle_status.system_id
if ((_param_mav_sys_id != PARAM_INVALID) && (param_get(_param_mav_sys_id, &value_int32) == PX4_OK)) {
_vehicle_status.system_id = value_int32;
}

// MAV_COMP_ID => vehicle_status.component_id
if ((_param_mav_comp_id != PARAM_INVALID) && (param_get(_param_mav_comp_id, &value_int32) == PX4_OK)) {
_vehicle_status.component_id = value_int32;
}

// MAV_TYPE -> vehicle_status.system_type
if ((_param_mav_type != PARAM_INVALID) && (param_get(_param_mav_type, &value_int32) == PX4_OK)) {
_vehicle_status.system_type = value_int32;
}


_vehicle_status.avoidance_system_required = _param_com_obs_avoid.get();

_auto_disarm_killed.set_hysteresis_time_from(false, _param_com_kill_disarm.get() * 1_s);
Expand Down
2 changes: 0 additions & 2 deletions src/modules/commander/Commander.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -324,8 +324,6 @@ class Commander : public ModuleBase<Commander>, public ModuleParams
perf_counter_t _preflight_check_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": preflight check")};

// optional parameters
param_t _param_mav_comp_id{PARAM_INVALID};
param_t _param_mav_sys_id{PARAM_INVALID};
param_t _param_mav_type{PARAM_INVALID};
param_t _param_rc_map_fltmode{PARAM_INVALID};

Expand Down
10 changes: 7 additions & 3 deletions src/modules/ekf2/EKF/ekf_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -898,17 +898,21 @@ void Ekf::updateIMUBiasInhibit(const imuSample &imu_delayed)
// inhibit learning of imu accel bias if the manoeuvre levels are too high to protect against the effect of sensor nonlinearities or bad accel data is detected
// xy accel bias learning is also disabled on ground as those states are poorly observable when perpendicular to the gravity vector
{
const Vector3f gyro_corrected = imu_delayed.delta_ang / imu_delayed.delta_ang_dt - _state.gyro_bias;

const float alpha = math::constrain((imu_delayed.delta_ang_dt / _params.acc_bias_learn_tc), 0.f, 1.f);
const float beta = 1.f - alpha;
_ang_rate_magnitude_filt = fmaxf(imu_delayed.delta_ang.norm() / imu_delayed.delta_ang_dt,
beta * _ang_rate_magnitude_filt);

_ang_rate_magnitude_filt = fmaxf(gyro_corrected.norm(), beta * _ang_rate_magnitude_filt);
}

{
const Vector3f accel_corrected = imu_delayed.delta_vel / imu_delayed.delta_vel_dt - _state.accel_bias;

const float alpha = math::constrain((imu_delayed.delta_vel_dt / _params.acc_bias_learn_tc), 0.f, 1.f);
const float beta = 1.f - alpha;

_accel_magnitude_filt = fmaxf(imu_delayed.delta_vel.norm() / imu_delayed.delta_vel_dt, beta * _accel_magnitude_filt);
_accel_magnitude_filt = fmaxf(accel_corrected.norm(), beta * _accel_magnitude_filt);
}


Expand Down
Loading

0 comments on commit 8edbd42

Please sign in to comment.