fix(various): Fix hardfaults when running out of memory (nullptr check) (#26516)
Build all targets / Scan for Board Targets (push) Has been cancelled
Checks / Gate Checks [check_format] (push) Has been cancelled
Checks / Gate Checks [check_newlines] (push) Has been cancelled
Checks / Gate Checks [module_documentation] (push) Has been cancelled
Checks / Gate Checks [shellcheck_all] (push) Has been cancelled
Checks / Gate Checks [validate_module_configs] (push) Has been cancelled
Checks / Unit Tests (push) Has been cancelled
Static Analysis / Clang-Tidy (push) Has been cancelled
MacOS build / build (push) Has been cancelled
Ubuntu environment build / Build and Test (ubuntu:22.04) (push) Has been cancelled
Ubuntu environment build / Build and Test (ubuntu:24.04) (push) Has been cancelled
Container build / Set Tags and Variables (push) Has been cancelled
Docs - Orchestrator / T1: Detect Changes (push) Has been cancelled
Docs - Orchestrator / T2: Metadata Sync (push) Has been cancelled
Docs - Crowdin - Upload Guide sources (en) / upload-to-crowdin (push) Has been cancelled
Failsafe Simulator Build / build (failsafe_web) (push) Has been cancelled
FLASH usage analysis / Analyzing px4_fmu-v5x (push) Has been cancelled
FLASH usage analysis / Analyzing px4_fmu-v6x (push) Has been cancelled
ITCM check / Checking nxp_mr-tropic (push) Has been cancelled
ITCM check / Checking nxp_tropic-community (push) Has been cancelled
ITCM check / Checking px4_fmu-v5x (push) Has been cancelled
ITCM check / Checking px4_fmu-v6xrt (push) Has been cancelled
MAVROS Tests / MAVROS Mission (push) Has been cancelled
MAVROS Tests / MAVROS Offboard (push) Has been cancelled
Python CI Checks / build (push) Has been cancelled
ROS Integration Tests / build (push) Has been cancelled
ROS Translation Node Tests / Build and test [humble] (push) Has been cancelled
ROS Translation Node Tests / Build and test [jazzy] (push) Has been cancelled
SITL Tests / Testing PX4 iris (push) Has been cancelled
Build all targets / Seed [${{ matrix.chip_family }}] (push) Has been cancelled
Build all targets / Build [${{ matrix.runner }}][${{ matrix.group }}] (push) Has been cancelled
Build all targets / Upload Artifacts (push) Has been cancelled
Container build / Build Container (amd64) (push) Has been cancelled
Container build / Build Container (arm64) (push) Has been cancelled
Container build / Deploy To Registry (push) Has been cancelled
Docs - Orchestrator / T2: PR Metadata (push) Has been cancelled
Docs - Orchestrator / T2: Link Check (push) Has been cancelled
Docs - Orchestrator / T3: Build Site (push) Has been cancelled
Docs - Orchestrator / T4: Deploy (push) Has been cancelled
FLASH usage analysis / Publish Results (push) Has been cancelled
Fuzzing / Fuzzing (push) Has been cancelled
SBOM Monthly Audit / audit (push) Has been cancelled
Handle stale issues and PRs / stale (push) Has been cancelled

* Fix hardfault in mavlink stream strcpy

* prevent more OOM hardfaults

* revert mavlink fallback

* delete _interpreter in mc_nn_control module

* fix build

---------

Co-authored-by: jonas <jonas.perolini@rigi.tech>
Co-authored-by: Julian Oes <julian@oes.ch>
This commit is contained in:
Jonas Perolini
2026-04-20 04:08:39 +02:00
committed by GitHub
parent 300e368e65
commit a182072792
11 changed files with 93 additions and 12 deletions
+2 -1
View File
@@ -111,7 +111,8 @@ private:
return (_gyro_data_buffer_x && _gyro_data_buffer_y && _gyro_data_buffer_z
&& _hanning_window
&& _fft_input_buffer
&& _fft_outupt_buffer);
&& _fft_outupt_buffer
&& _peak_magnitudes_all);
}
uORB::Publication<sensor_gyro_fft_s> _sensor_gyro_fft_pub{ORB_ID(sensor_gyro_fft)};
@@ -52,11 +52,19 @@ void MavlinkCommandSender::initialize()
if (_instance == nullptr) {
_instance = new MavlinkCommandSender();
if (_instance == nullptr) {
PX4_ERR("MavlinkCommandSender alloc failed");
}
}
}
MavlinkCommandSender &MavlinkCommandSender::instance()
{
if (_instance == nullptr) {
initialize();
}
return *_instance;
}
+7 -1
View File
@@ -1307,6 +1307,12 @@ Mavlink::configure_stream_threadsafe(const char *stream_name, const float rate)
/* copy stream name */
unsigned n = strlen(stream_name) + 1;
char *s = new char[n];
if (s == nullptr) {
PX4_ERR("stream allocation failed");
return;
}
strcpy(s, stream_name);
/* set subscription task */
@@ -2622,7 +2628,7 @@ Mavlink::task_main(int argc, char *argv[])
_receiver.stop();
delete _subscribe_to_stream;
delete[] _subscribe_to_stream;
_subscribe_to_stream = nullptr;
/* delete streams */
@@ -716,6 +716,12 @@ void MavlinkParametersManager::enque_uavcan_request(uavcan_parameter_request_s *
}
_uavcan_open_request_list_item *new_reqest = new _uavcan_open_request_list_item;
if (new_reqest == nullptr) {
PX4_ERR("uavcan request alloc failed");
return;
}
new_reqest->req = *req;
new_reqest->next = nullptr;
@@ -72,6 +72,10 @@ MulticopterNeuralNetworkControl::MulticopterNeuralNetworkControl() :
MulticopterNeuralNetworkControl::~MulticopterNeuralNetworkControl()
{
delete _interpreter;
_interpreter = nullptr;
_input_tensor = nullptr;
_output_tensor = nullptr;
perf_free(_loop_perf);
}
@@ -88,6 +92,14 @@ bool MulticopterNeuralNetworkControl::init()
int MulticopterNeuralNetworkControl::InitializeNetwork()
{
if (_interpreter != nullptr) {
delete _interpreter;
_interpreter = nullptr;
}
_input_tensor = nullptr;
_output_tensor = nullptr;
// Initialize the neural network
const tflite::Model *control_model = ::tflite::GetModel(control_net_tflite);
@@ -103,11 +115,18 @@ int MulticopterNeuralNetworkControl::InitializeNetwork()
static uint8_t tensor_arena[kTensorArenaSize];
_interpreter = new tflite::MicroInterpreter(control_model, resolver, tensor_arena, kTensorArenaSize);
if (_interpreter == nullptr) {
PX4_ERR("interpreter alloc failed");
return -1;
}
// Allocate memory for the model's tensors
TfLiteStatus allocate_status = _interpreter->AllocateTensors();
if (allocate_status != kTfLiteOk) {
PX4_ERR("AllocateTensors() failed");
delete _interpreter;
_interpreter = nullptr;
return -1;
}
@@ -115,6 +134,8 @@ int MulticopterNeuralNetworkControl::InitializeNetwork()
if (_input_tensor == nullptr) {
PX4_ERR("Input tensor is null");
delete _interpreter;
_interpreter = nullptr;
return -1;
}
+3 -3
View File
@@ -149,9 +149,9 @@ private:
uint8 _mode_request_id{231}; //Random value
int8 _arming_check_id{-1};
int8 _mode_id{-1};
tflite::MicroInterpreter *_interpreter;
TfLiteTensor *_input_tensor;
TfLiteTensor *_output_tensor;
tflite::MicroInterpreter *_interpreter{nullptr};
TfLiteTensor *_input_tensor{nullptr};
TfLiteTensor *_output_tensor{nullptr};
float _input_data[15];
trajectory_setpoint_s _trajectory_setpoint;
vehicle_angular_velocity_s _angular_velocity;
+6
View File
@@ -527,6 +527,12 @@ Replay::readAndAddSubscription(std::ifstream &file, uint16_t msg_size)
}
Subscription *subscription = new Subscription();
if (subscription == nullptr) {
delete compat;
return ReadAndAndAddSubResult::kFailure;
}
subscription->orb_meta = orb_meta;
subscription->multi_id = multi_id;
subscription->compat = compat;
@@ -54,6 +54,11 @@ DataValidatorGroup::DataValidatorGroup(unsigned siblings)
for (unsigned i = 0; i < siblings; i++) {
next = new DataValidator();
if (next == nullptr) {
PX4_ERR("alloc failed");
break;
}
if (i == 0) {
_first = next;
@@ -64,7 +69,7 @@ DataValidatorGroup::DataValidatorGroup(unsigned siblings)
prev = next;
}
_last = next;
_last = prev;
if (_first) {
_timeout_interval_us = _first->get_timeout();
@@ -89,8 +94,14 @@ DataValidator *DataValidatorGroup::add_new_validator()
return nullptr;
}
_last->setSibling(validator);
_last = validator;
if (_last) {
_last->setSibling(validator);
_last = validator;
} else {
_first = _last = validator;
}
_last->set_timeout(_timeout_interval_us);
return _last;
}
@@ -483,6 +483,11 @@ void SimulatorMavlink::handle_message_hil_gps(const mavlink_message_t *msg)
if (_sensor_gps_pubs[i] == nullptr) {
_sensor_gps_pubs[i] = new uORB::PublicationMulti<sensor_gps_s> {ORB_ID(sensor_gps)};
if (_sensor_gps_pubs[i] == nullptr) {
break;
}
_gps_ids[i] = hil_gps.id;
device::Device::DeviceId device_id;
@@ -1588,6 +1593,11 @@ int SimulatorMavlink::publish_distance_topic(const mavlink_distance_sensor_t *di
if (_dist_pubs[i] == nullptr) {
_dist_pubs[i] = new uORB::PublicationMulti<distance_sensor_s> {ORB_ID(distance_sensor)};
if (_dist_pubs[i] == nullptr) {
break;
}
_dist_sensor_ids[i] = dist.device_id;
_dist_pubs[i]->publish(dist);
break;
@@ -884,12 +884,12 @@ bool UxrceddsClient::setBaudrate(int fd, unsigned baud)
bool UxrceddsClient::add_replier(SrvBase *replier)
{
if (_num_of_repliers < MAX_NUM_REPLIERS) {
_repliers[_num_of_repliers] = replier;
_num_of_repliers++;
if (replier == nullptr || _num_of_repliers >= MAX_NUM_REPLIERS) {
return true;
}
_repliers[_num_of_repliers] = replier;
_num_of_repliers++;
return false;
}
@@ -79,6 +79,12 @@ VtolAttitudeControl::VtolAttitudeControl() :
exit_and_cleanup(desc);
}
if (_vtol_type == nullptr) {
PX4_ERR("vtol type allocation failed");
exit_and_cleanup(desc);
return;
}
_flaps_setpoint_pub.advertise();
_spoilers_setpoint_pub.advertise();
_vtol_vehicle_status_pub.advertise();
@@ -302,6 +308,12 @@ VtolAttitudeControl::Run()
#endif // !ENABLE_LOCKSTEP_SCHEDULER
if (_vtol_type == nullptr) {
PX4_ERR("vtol type unavailable");
exit_and_cleanup(desc);
return;
}
if (!_initialized) {
if (_vtol_type->init()) {