fix(modules): improve Windows runtime portability

Replace GNU-only cases and POSIX assumptions with portable PX4 helpers across drivers, examples, logger, dataman, version reporting, system commands, and tests.

Keep ioctl argument types consistent and make startup/runtime diagnostics less noisy on SITL-only platforms where optional devices are absent.
This commit is contained in:
Nuno Marques
2026-05-11 10:33:03 -07:00
parent cee9c3e1d7
commit a7ac52128e
30 changed files with 347 additions and 112 deletions
+6 -1
View File
@@ -49,7 +49,12 @@ import codecs
def main():
# Parse command line arguments
parser = argparse.ArgumentParser(description="Process events definitions.")
# Allow @file argument expansion so the (very long) source-file list can
# be passed via a response file. Required on Windows, where the
# 8191-char cmd.exe line limit otherwise truncates the build's full
# `--src-path file1 file2 …` invocation.
parser = argparse.ArgumentParser(description="Process events definitions.",
fromfile_prefix_chars='@')
parser.add_argument("-s", "--src-path",
default=["../src"],
metavar="PATH",
+8 -4
View File
@@ -42,10 +42,14 @@
#include <stdbool.h>
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
/* MSVC requires the dllexport storage class on the prototype too — a plain
* `extern` declaration followed by a `__declspec(dllexport)` definition is
* "redefinition; different linkage" (C2375). GCC accepts the visibility
* attribute on either side. */
extern __EXPORT void led_init(void);
extern __EXPORT void led_on(int led);
extern __EXPORT void led_off(int led);
extern __EXPORT void led_toggle(int led);
__END_DECLS
static bool _led_state[2] = { false, false };
+38 -42
View File
@@ -37,6 +37,7 @@
#include <sys/types.h>
#include <stdbool.h>
#include <float.h>
#include <stdint.h>
#include <string.h>
#include <math.h>
#include <stdio.h>
@@ -79,6 +80,41 @@ const msp_message_descriptor_t msp_message_descriptors[MSP_DESCRIPTOR_COUNT] = {
{MSP_RC, true, sizeof(msp_rc_t)},
};
namespace
{
constexpr uint32_t MSP_V1_MAX_PAYLOAD_SIZE = UINT8_MAX;
bool send_packet(int fd, const uint8_t message_id, const void *payload, const uint32_t payload_size)
{
if ((payload_size > MSP_V1_MAX_PAYLOAD_SIZE) || ((payload_size > 0) && (payload == nullptr))) {
return false;
}
uint8_t packet[MSP_FRAME_START_SIZE + MSP_V1_MAX_PAYLOAD_SIZE + MSP_CRC_SIZE];
packet[0] = '$';
packet[1] = 'M';
packet[2] = '>';
packet[3] = static_cast<uint8_t>(payload_size);
packet[4] = message_id;
uint8_t crc = static_cast<uint8_t>(payload_size) ^ message_id;
if (payload_size > 0) {
memcpy(packet + MSP_FRAME_START_SIZE, payload, payload_size);
}
for (uint32_t i = 0; i < payload_size; i ++) {
crc ^= packet[MSP_FRAME_START_SIZE + i];
}
packet[MSP_FRAME_START_SIZE + payload_size] = crc;
const int packet_size = MSP_FRAME_START_SIZE + payload_size + MSP_CRC_SIZE;
return write(fd, packet, packet_size) == packet_size;
}
} // namespace
bool MspV1::Send(const uint8_t message_id, const void *payload)
{
uint32_t payload_size = 0;
@@ -102,52 +138,12 @@ bool MspV1::Send(const uint8_t message_id, const void *payload)
payload_size = desc->message_size;
uint8_t packet[MSP_FRAME_START_SIZE + payload_size + MSP_CRC_SIZE];
uint8_t crc;
packet[0] = '$';
packet[1] = 'M';
packet[2] = '>';
packet[3] = payload_size;
packet[4] = message_id;
crc = payload_size ^ message_id;
memcpy(packet + MSP_FRAME_START_SIZE, payload, payload_size);
for (uint32_t i = 0; i < payload_size; i ++) {
crc ^= packet[MSP_FRAME_START_SIZE + i];
}
packet[MSP_FRAME_START_SIZE + payload_size] = crc;
int packet_size = MSP_FRAME_START_SIZE + payload_size + MSP_CRC_SIZE;
return write(_fd, packet, packet_size) == packet_size;
return send_packet(_fd, message_id, payload, payload_size);
}
bool MspV1::Send(const uint8_t message_id, const void *payload, uint32_t payload_size)
{
uint8_t packet[MSP_FRAME_START_SIZE + payload_size + MSP_CRC_SIZE];
uint8_t crc;
packet[0] = '$';
packet[1] = 'M';
packet[2] = '>';
packet[3] = payload_size;
packet[4] = message_id;
crc = payload_size ^ message_id;
memcpy(packet + MSP_FRAME_START_SIZE, payload, payload_size);
for (uint32_t i = 0; i < payload_size; i ++) {
crc ^= packet[MSP_FRAME_START_SIZE + i];
}
packet[MSP_FRAME_START_SIZE + payload_size] = crc;
int packet_size = MSP_FRAME_START_SIZE + payload_size + MSP_CRC_SIZE;
return write(_fd, packet, packet_size) == packet_size;
return send_packet(_fd, message_id, payload, payload_size);
}
+2 -2
View File
@@ -130,7 +130,7 @@ public:
* @param[in] cmd the IOCTL command
* @param[in] the IOCTL command parameter (optional)
*/
int ioctl(file *filp, int cmd, unsigned long arg) override;
int ioctl(file *filp, int cmd, uintptr_t arg) override;
/**
* Print IO status.
@@ -1309,7 +1309,7 @@ int PX4IO::print_status()
return 0;
}
int PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
int PX4IO::ioctl(file *filep, int cmd, uintptr_t arg)
{
SmartLock lock_guard(_lock);
int ret = OK;
@@ -266,7 +266,7 @@ void IridiumSBD::test(int argc, char *argv[])
schedule_test();
}
int IridiumSBD::ioctl(struct file *filp, int cmd, unsigned long arg)
int IridiumSBD::ioctl(struct file *filp, int cmd, uintptr_t arg)
{
switch (cmd) {
case FIONREAD: {
@@ -139,7 +139,7 @@ public:
/*
* Passes everything to CDev
*/
int ioctl(struct file *filp, int cmd, unsigned long arg);
int ioctl(struct file *filp, int cmd, uintptr_t arg);
static bool can_stop() { return !get_instance<IridiumSBD>(desc)->_cdev_used.load(); }
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
* Copyright (c) 2012-2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -39,6 +39,10 @@
*/
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/log.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/tasks.h>
#include <atomic>
#include <unistd.h>
#include <stdio.h>
#include <string.h>
@@ -55,40 +59,58 @@
extern "C" __EXPORT int px4_mavlink_debug_main(int argc, char *argv[]);
int px4_mavlink_debug_main(int argc, char *argv[])
namespace
{
printf("Hello Debug!\n");
// Track liveness of the background publisher so `status`/`stop` can report
// the right state without blocking the daemon. The publisher loop runs on a
// task spawned by `start`; the daemon's per-client thread returns
// immediately so the client connection is not held open for the lifetime of
// the loop. Without this split, `start` blocked the IPC socket for the full
// 50 s loop, and `status` had to be a bare printf because there was no
// long-lived task to query.
std::atomic<bool> g_running{false};
std::atomic<bool> g_exit_requested{false};
int publisher_thread_main(int argc, char *argv[])
{
(void)argc;
(void)argv;
g_running.store(true);
PX4_INFO("Hello Debug!");
/* advertise named debug value */
struct debug_key_value_s dbg_key;
strncpy(dbg_key.key, "velx", 10);
struct debug_key_value_s dbg_key {};
strncpy(dbg_key.key, "velx", sizeof(dbg_key.key));
dbg_key.value = 0.0f;
orb_advert_t pub_dbg_key = orb_advertise(ORB_ID(debug_key_value), &dbg_key);
/* advertise indexed debug value */
struct debug_value_s dbg_ind;
struct debug_value_s dbg_ind {};
dbg_ind.ind = 42;
dbg_ind.value = 0.5f;
orb_advert_t pub_dbg_ind = orb_advertise(ORB_ID(debug_value), &dbg_ind);
/* advertise debug vect */
struct debug_vect_s dbg_vect;
strncpy(dbg_vect.name, "vel3D", 10);
struct debug_vect_s dbg_vect {};
strncpy(dbg_vect.name, "vel3D", sizeof(dbg_vect.name));
dbg_vect.x = 1.0f;
dbg_vect.y = 2.0f;
dbg_vect.z = 3.0f;
orb_advert_t pub_dbg_vect = orb_advertise(ORB_ID(debug_vect), &dbg_vect);
/* advertise debug array */
struct debug_array_s dbg_array;
struct debug_array_s dbg_array {};
dbg_array.id = 1;
strncpy(dbg_array.name, "dbg_array", 10);
strncpy(dbg_array.name, "dbg_array", sizeof(dbg_array.name));
orb_advert_t pub_dbg_array = orb_advertise(ORB_ID(debug_array), &dbg_array);
int value_counter = 0;
while (value_counter < 100) {
uint64_t timestamp_us = hrt_absolute_time();
while (!g_exit_requested.load() && value_counter < 100) {
const uint64_t timestamp_us = hrt_absolute_time();
/* send one named value */
dbg_key.value = value_counter;
@@ -115,11 +137,88 @@ int px4_mavlink_debug_main(int argc, char *argv[])
dbg_array.timestamp = timestamp_us;
orb_publish(ORB_ID(debug_array), pub_dbg_array, &dbg_array);
warnx("sent one more value..");
PX4_DEBUG("sent one more value..");
value_counter++;
px4_usleep(500000);
}
g_running.store(false);
g_exit_requested.store(false);
return 0;
}
void usage(const char *reason)
{
if (reason != nullptr) {
printf("%s\n", reason);
}
printf("usage: px4_mavlink_debug {start|stop|status}\n");
}
} // namespace
int px4_mavlink_debug_main(int argc, char *argv[])
{
if (argc < 2) {
usage("missing command");
return 1;
}
const char *verb = argv[1];
if (strcmp(verb, "start") == 0) {
if (g_running.load()) {
PX4_INFO("already running");
return 0;
}
// Clear any prior exit request so a re-`start` after a `stop`
// runs to completion.
g_exit_requested.store(false);
// Spawn the publisher loop on its own task so the daemon's
// per-client thread can return immediately. Otherwise the IPC
// socket would stay open for the full ~50 s loop and the
// invoking client (`pxh`, `px4-px4_mavlink_debug.exe`, etc.)
// would appear to hang.
const px4_task_t task = px4_task_spawn_cmd("px4_mavlink_debug",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2000,
publisher_thread_main,
(argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
if (task < 0) {
PX4_ERR("task spawn failed");
return 1;
}
return 0;
}
if (strcmp(verb, "stop") == 0) {
if (!g_running.load()) {
PX4_INFO("not running");
return 0;
}
g_exit_requested.store(true);
return 0;
}
if (strcmp(verb, "status") == 0) {
if (g_running.load()) {
PX4_INFO("running: publishing 100 sample debug values at 2 Hz");
} else {
PX4_INFO("not running");
}
return 0;
}
usage("unrecognized command");
return 1;
}
@@ -56,6 +56,30 @@ __EXPORT int px4_simple_app_main(int argc, char *argv[]);
int px4_simple_app_main(int argc, char *argv[])
{
/* Handle simple command verbs without entering the polling loop. The
* loop below blocks for ~5 s waiting for sensor updates, which would
* otherwise make `px4-px4_simple_app status` (and similar one-shot
* invocations from the pxh shell or external clients) appear to hang
* for the full duration of the example. Return immediately for these
* commands so callers get a prompt response.
*/
if (argc > 1) {
if (strcmp(argv[1], "status") == 0) {
PX4_INFO("not running (this example is a one-shot demo; "
"invoke without arguments to run the polling loop)");
return 0;
} else if (strcmp(argv[1], "stop") == 0) {
/* Nothing to stop — the example is not a long-running task. */
return 0;
} else if (strcmp(argv[1], "help") == 0 || strcmp(argv[1], "-h") == 0) {
PX4_INFO("usage: px4_simple_app [status|stop|help]");
PX4_INFO(" no args: run a short demo loop (5 iterations, ~5 s)");
return 0;
}
}
PX4_INFO("Hello Sky!");
/* subscribe to vehicle_acceleration topic */
+1 -1
View File
@@ -146,7 +146,7 @@ public:
* @param arg The ioctl argument value.
* @return OK on success, or -errno otherwise.
*/
virtual int ioctl(file_t *filep, int cmd, unsigned long arg) { return -ENOTTY; };
virtual int ioctl(file_t *filep, int cmd, uintptr_t arg) { return -ENOTTY; };
/**
* Perform a poll setup/teardown operation.
+1 -1
View File
@@ -312,7 +312,7 @@ extern "C" {
return ret;
}
int px4_ioctl(int fd, int cmd, unsigned long arg)
int px4_ioctl(int fd, int cmd, uintptr_t arg)
{
PX4_DEBUG("px4_ioctl fd = %d", fd);
int ret = 0;
+1 -1
View File
@@ -64,7 +64,7 @@ public:
// methods
BlockLowPass2(SuperBlock *parent, const char *name, float sample_freq) :
Block(parent, name),
_state(0.0 / 0.0 /* initialize to invalid val, force into is_finite() check on first call */),
_state(NAN), // initialize to invalid val, force into is_finite() check on first call
_fCut(this, ""), // only one parameter, no need to name
_fs(sample_freq),
_lp(_fs, _fCut.get())
+1 -1
View File
@@ -67,7 +67,7 @@ public:
_fCut(this, "") // only one parameter, no need to name
{
for (size_t i = 0; i < M; i++) {
_state(i) = 0.0f / 0.0f;
_state(i) = static_cast<Type>(NAN);
}
}
virtual ~BlockLowPassVector() = default;
+1 -1
View File
@@ -80,7 +80,7 @@ public:
* @param arg The ioctl argument value.
* @return OK on success, or -errno otherwise.
*/
virtual int ioctl(file_t *filep, int cmd, unsigned long arg) { return -ENOTTY; }
virtual int ioctl(file_t *filep, int cmd, uintptr_t arg) { return -ENOTTY; }
};
+2 -2
View File
@@ -64,7 +64,7 @@ public:
~LED() override = default;
int init() override;
int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override;
int ioctl(cdev::file_t *filp, int cmd, uintptr_t arg) override;
};
LED::LED() : CDev(LED0_DEVICE_PATH)
@@ -86,7 +86,7 @@ LED::init()
}
int
LED::ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
LED::ioctl(cdev::file_t *filp, int cmd, uintptr_t arg)
{
int result = OK;
+1 -2
View File
@@ -98,8 +98,7 @@ DirectionalGuidance::guideToPath(const Vector2f &curr_pos_local, const Vector2f
wind_cross_upt, airspeed, wind_speed, signed_track_error_, path_curvature) * feas_combined * track_proximity_;
course_sp_ = atan2f(bearing_vec_(1), bearing_vec_(0));
return DirectionalGuidanceOutput{.course_setpoint = course_sp_,
.lateral_acceleration_feedforward = lateral_accel_ff_};
return DirectionalGuidanceOutput{course_sp_, lateral_accel_ff_};
}
float DirectionalGuidance::adaptPeriod(const float ground_speed, const float airspeed, const float wind_speed,
+4 -2
View File
@@ -45,10 +45,12 @@
#include "tinybson.h"
/* C99 variadic macro syntax — GCC's `args...` named-rest is rejected by
* MSVC (C2010 "'.' unexpected in macro parameter list"). */
#if 0
# define debug(fmt, args...) do { PX4_INFO("BSON: " fmt, ##args); } while(0)
# define debug(fmt, ...) do { PX4_INFO("BSON: " fmt, ##__VA_ARGS__); } while(0)
#else
# define debug(fmt, args...) do { } while(0)
# define debug(fmt, ...) do { (void)(fmt); } while(0)
#endif
#define CODER_CHECK(_c) do { if ((_c)->dead) { PX4_ERR("coder dead"); return -1; }} while(0)
+7 -1
View File
@@ -330,7 +330,13 @@ Tunes::Status Tunes::get_next_note(unsigned &frequency, unsigned &duration, unsi
break;
case 'A'...'G': // Play a note in the current octave.
case 'A': // Play a note in the current octave.
case 'B':
case 'C':
case 'D':
case 'E':
case 'F':
case 'G':
note = _note_tab[c - 'A'] + (_octave * 12) + 1;
c = next_char();
+25 -4
View File
@@ -35,13 +35,14 @@
#include "build_git_version.h"
#include <stdio.h>
#include <string.h>
#if !defined(CONFIG_CDCACM_PRODUCTID)
# define CONFIG_CDCACM_PRODUCTID 0
#endif
#if defined(__PX4_LINUX)
#if defined(__PX4_LINUX) || defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
#include <sys/utsname.h>
#endif
@@ -300,9 +301,7 @@ uint32_t px4_board_version(void)
uint32_t px4_os_version(void)
{
#if defined(__PX4_DARWIN) || defined(__PX4_CYGWIN) || defined(__PX4_QURT)
return 0; //TODO: implement version for Darwin, Cygwin, QuRT
#elif defined(__PX4_LINUX)
#if defined(__PX4_LINUX) || defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
struct utsname name;
if (uname(&name) == 0) {
@@ -320,6 +319,26 @@ uint32_t px4_os_version(void)
return 0;
}
#elif defined(__PX4_WINDOWS)
// _WIN32_WINNT is the targeted Windows version, encoded as 0xMMmm
// (e.g. 0x0A00 → Windows 10.0). It is set by the toolchain.
char buf[16];
snprintf(buf, sizeof(buf), "%d.%d.0",
(_WIN32_WINNT >> 8) & 0xFF,
_WIN32_WINNT & 0xFF);
return version_tag_to_number(buf);
#elif defined(__PX4_QURT)
// Hexagon clang sets __HEXAGON_ARCH__ to the DSP architecture revision
// (e.g. 66 for hexagonv66), which we map to a major.minor pair.
#ifdef __HEXAGON_ARCH__
char buf[16];
snprintf(buf, sizeof(buf), "%d.%d.0",
__HEXAGON_ARCH__ / 10,
__HEXAGON_ARCH__ % 10);
return version_tag_to_number(buf);
#else
return 0;
#endif
#elif defined(__PX4_NUTTX)
return version_tag_to_number(NUTTX_GIT_TAG_STR);
#else
@@ -348,6 +367,8 @@ const char *px4_os_name(void)
return "NuttX";
#elif defined(__PX4_CYGWIN)
return "Cygwin";
#elif defined(__PX4_WINDOWS)
return "Windows";
#else
# error "px4_os_name not implemented for current OS"
#endif
@@ -338,7 +338,11 @@ int led_init()
if (fd_leds < 0) {
// there might not be an LED available, so don't make this an error
#if defined(__PX4_POSIX)
PX4_DEBUG("LED: open %s failed (%i)", LED0_DEVICE_PATH, errno);
#else
PX4_INFO("LED: open %s failed (%i)", LED0_DEVICE_PATH, errno);
#endif
return -errno;
}
+17 -2
View File
@@ -149,6 +149,21 @@ static constexpr size_t g_per_item_size_with_hdr[DM_KEY_NUM_KEYS] = {
g_per_item_size[DM_KEY_COMPAT] + DM_SECTOR_HDR_SIZE
};
static constexpr size_t max_item_size_with_hdr()
{
size_t max_size = 0;
for (size_t i = 0; i < DM_KEY_NUM_KEYS; i++) {
if (g_per_item_size_with_hdr[i] > max_size) {
max_size = g_per_item_size_with_hdr[i];
}
}
return max_size;
}
static constexpr size_t g_max_item_size_with_hdr = max_item_size_with_hdr();
/* Table of offset for index 0 of each item type */
static unsigned int g_key_offsets[DM_KEY_NUM_KEYS];
@@ -260,7 +275,7 @@ _file_write(dm_item_t item, unsigned index, const void *buf, size_t count)
return -1;
}
unsigned char buffer[g_per_item_size_with_hdr[item]];
unsigned char buffer[g_max_item_size_with_hdr];
/* Get the offset for this item */
const int offset = calculate_offset(item, index);
@@ -383,7 +398,7 @@ _file_read(dm_item_t item, unsigned index, void *buf, size_t count)
return -1;
}
unsigned char buffer[g_per_item_size_with_hdr[item]];
unsigned char buffer[g_max_item_size_with_hdr];
/* Get the offset for this item */
int offset = calculate_offset(item, index);
+12 -11
View File
@@ -826,11 +826,11 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_
const int param_compid = roundf(vehicle_command.param2);
uint8_t new_sysid_primary_control = [&]() {
switch (param_sysid) {
if ((param_sysid >= 0) && (param_sysid <= 255)) {
return static_cast<uint8_t>(param_sysid);
}
case 0 ... 255:
// Valid new sysid.
return (uint8_t) param_sysid;
switch (param_sysid) {
case -1:
// leave unchanged
@@ -838,13 +838,13 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_
case -2:
// set itself
return (uint8_t) _parameters.mav_sysid;
return static_cast<uint8_t>(_parameters.mav_sysid);
case -3:
// release control if in control
if (control_data.sysid_primary_control == vehicle_command.source_system) {
return (uint8_t) 0;
return static_cast<uint8_t>(0);
} else {
return control_data.sysid_primary_control;
@@ -857,10 +857,11 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_
}();
uint8_t new_compid_primary_control = [&]() {
if ((param_compid >= 0) && (param_compid <= 255)) {
return static_cast<uint8_t>(param_compid);
}
switch (param_compid) {
case 0 ... 255:
// Valid new compid.
return (uint8_t) param_compid;
case -1:
// leave unchanged
@@ -868,13 +869,13 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_
case -2:
// set itself
return (uint8_t) _parameters.mav_compid;
return static_cast<uint8_t>(_parameters.mav_compid);
case -3:
// release control if in control
if (control_data.compid_primary_control == vehicle_command.source_component) {
return (uint8_t) 0;
return static_cast<uint8_t>(0);
} else {
return control_data.compid_primary_control;
@@ -31,6 +31,11 @@
#include "arm_math.h"
#ifdef __cplusplus
extern "C"
{
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES)
/* Double Precision Float CFFT twiddles */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREV_1024)
@@ -513,4 +518,8 @@
extern const unsigned char hwLUT[256];
#endif /* (defined(ARM_MATH_MVEI) || defined(ARM_MATH_HELIUM)) */
#ifdef __cplusplus
}
#endif
#endif /* ARM_COMMON_TABLES_H */
@@ -33,6 +33,11 @@
#include "arm_math.h"
#include "arm_common_tables.h"
#ifdef __cplusplus
extern "C"
{
#endif
extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len16;
extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len32;
extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len64;
@@ -73,4 +78,8 @@
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len2048;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len4096;
#ifdef __cplusplus
}
#endif
#endif
+9 -1
View File
@@ -196,6 +196,14 @@ int Logger::task_spawn(int argc, char *argv[])
return -errno;
}
// Wait for the logger instance to be constructed on the child thread
// before returning, so a subsequent `logger on` from the startup script
// doesn't race ahead and dereference a null instance pointer.
if (wait_until_running(desc) < 0) {
desc.task_id = -1;
return -1;
}
return 0;
}
@@ -690,7 +698,7 @@ void Logger::run()
if (_writer.backend() & LogWriter::BackendFile) {
const pid_t pid_self = getpid();
const pid_t pid_self = px4_getpid();
const pthread_t writer_thread = _writer.thread_id_file();
// sched_note_start is already called from pthread_create and task_create,
+10 -1
View File
@@ -57,7 +57,16 @@ VotedSensorsUpdate::VotedSensorsUpdate(bool hil_enabled,
_sensor_selection_pub.advertise();
_sensors_status_imu_pub.advertise();
if (_hil_enabled) { // HIL has less accurate timing so increase the timeouts a bit
// HIL has less accurate timing, and lockstep SITL can advance simulated
// time much faster than wall time while shell/status commands are running.
const bool use_extended_sensor_timeout =
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
true;
#else
_hil_enabled;
#endif
if (use_extended_sensor_timeout) {
_gyro.voter.set_timeout(500000);
_accel.voter.set_timeout(500000);
}
+11
View File
@@ -146,6 +146,17 @@ extern "C" __EXPORT int sd_bench_main(int argc, char *argv[])
}
}
// Reject any leftover positional arguments (e.g. "status", "start", "stop").
// sd_bench has no subcommands -- it only accepts the flags handled above --
// so silently ignoring extra args would run a multi-second benchmark when
// the user almost certainly meant a different module. Print usage and exit
// non-zero instead.
if (myoptind < argc) {
PX4_ERR("unrecognized argument: %s", argv[myoptind]);
usage();
return 1;
}
if (block_size <= 0 || cfg.num_runs <= 0) {
PX4_ERR("invalid argument");
return -1;
+3 -3
View File
@@ -53,7 +53,7 @@ static const bool sample_bool = true;
static const int32_t sample_small_int = 123;
static const int64_t sample_big_int = (int64_t)INT_MAX + 123LL;
static const double sample_double = 2.5f;
static const char *sample_string = "this is a test";
static const char sample_string[] = "this is a test";
static const uint8_t sample_data[256] = {0};
//static const char *sample_filename = "/fs/microsd/bson.test";
@@ -175,7 +175,7 @@ decode_callback(bson_decoder_t decoder, bson_node_t node)
return 1;
}
char sbuf[len];
char sbuf[sizeof(sample_string)];
if (bson_decoder_copy_data(decoder, sbuf)) {
PX4_ERR("FAIL: decoder: string1 copy failed");
@@ -219,7 +219,7 @@ decode_callback(bson_decoder_t decoder, bson_node_t node)
return 1;
}
uint8_t dbuf[len];
uint8_t dbuf[sizeof(sample_data)];
if (bson_decoder_copy_data(decoder, dbuf)) {
PX4_ERR("FAIL: decoder: data1 copy failed");
+10 -6
View File
@@ -90,8 +90,11 @@ int check_user_abort(int fd)
int
test_file(int argc, char *argv[])
{
const unsigned iterations = 2;
const unsigned alignments = 33;
enum {
iterations = 2,
alignments = 33,
max_chunk_size = 1500
};
/* check if microSD card is mounted */
struct stat buffer;
@@ -113,15 +116,16 @@ test_file(int argc, char *argv[])
printf("\n");
printf("----- alignment test: %u bytes -----\n", a);
uint8_t write_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
const size_t buffer_size = (size_t)chunk_sizes[c] + alignments;
uint8_t write_buf[max_chunk_size + alignments] __attribute__((aligned(64)));
/* fill write buffer with known values */
for (size_t i = 0; i < sizeof(write_buf); i++) {
for (size_t i = 0; i < buffer_size; i++) {
/* this will wrap, but we just need a known value with spacing */
write_buf[i] = i + 11;
}
uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
uint8_t read_buf[max_chunk_size + alignments] __attribute__((aligned(64)));
hrt_abstime start, end;
int fd = open(PX4_STORAGEDIR "/testfile", O_TRUNC | O_WRONLY | O_CREAT, 0600);
@@ -260,7 +264,7 @@ test_file(int argc, char *argv[])
bool unalign_read_ok = true;
int unalign_read_err_count = 0;
memset(read_buf, 0, sizeof(read_buf));
memset(read_buf, 0, buffer_size);
/* read back data unaligned */
for (unsigned i = 0; i < iterations; i++) {
+15 -6
View File
@@ -84,17 +84,24 @@ static int test_corruption(const char *filename, uint32_t write_chunk, uint32_t
// create a file of size write_size, in write_chunk blocks
uint8_t counter = 0;
uint8_t *buffer = (uint8_t *)malloc(write_chunk);
if (buffer == NULL) {
printf("malloc failed for write_chunk=%" PRIu32 "\n", write_chunk);
close(fd);
return 1;
}
while (ofs < write_size) {
uint8_t buffer[write_chunk];
for (uint16_t j = 0; j < write_chunk; j++) {
buffer[j] = get_value(ofs);
ofs++;
}
if (write(fd, buffer, sizeof(buffer)) != (int)sizeof(buffer)) {
if (write(fd, buffer, write_chunk) != (int)write_chunk) {
printf("write failed at offset %" PRIu32 "\n", ofs);
free(buffer);
close(fd);
return 1;
}
@@ -118,6 +125,7 @@ static int test_corruption(const char *filename, uint32_t write_chunk, uint32_t
if (fd == -1) {
perror(filename);
free(buffer);
return 1;
}
@@ -125,17 +133,16 @@ static int test_corruption(const char *filename, uint32_t write_chunk, uint32_t
ofs = 0;
while (ofs < write_size) {
uint8_t buffer[write_chunk];
if (counter % 100 == 0) {
printf("read ofs=%" PRIu32 "\r", ofs);
}
counter++;
if (read(fd, buffer, sizeof(buffer)) != (int)sizeof(buffer)) {
if (read(fd, buffer, write_chunk) != (int)write_chunk) {
printf("read failed at offset %" PRIu32 "\n", ofs);
close(fd);
free(buffer);
return 1;
}
@@ -143,6 +150,7 @@ static int test_corruption(const char *filename, uint32_t write_chunk, uint32_t
if (buffer[j] != get_value(ofs)) {
printf("corruption at ofs=%" PRIu32 " got %" PRIu8 "\n", ofs, buffer[j]);
close(fd);
free(buffer);
return 1;
}
@@ -156,6 +164,7 @@ static int test_corruption(const char *filename, uint32_t write_chunk, uint32_t
printf("read ofs=%" PRIu32 "\n", ofs);
close(fd);
free(buffer);
unlink(filename);
printf("All OK\n");
return 0;
+2 -2
View File
@@ -378,8 +378,8 @@ bool MathlibTest::testFinite()
ut_assert("PX4_ISFINITE(-1.0f)", PX4_ISFINITE(-1.0f) == true);
ut_assert("PX4_ISFINITE(NAN)", PX4_ISFINITE(NAN) == false);
ut_assert("PX4_ISFINITE(1/0)", PX4_ISFINITE(1.0f / 0.0f) == false);
ut_assert("PX4_ISFINITE(0/0)", PX4_ISFINITE(0.0f / 0.0f) == false);
ut_assert("PX4_ISFINITE(1/0)", PX4_ISFINITE(INFINITY) == false);
ut_assert("PX4_ISFINITE(0/0)", PX4_ISFINITE(NAN) == false);
ut_assert("PX4_ISFINITE(INFINITY)", PX4_ISFINITE(INFINITY) == false);
ut_assert("PX4_ISFINITE(NAN * INFINITY)", PX4_ISFINITE(NAN * INFINITY) == false);
ut_assert("PX4_ISFINITE(NAN * 1.0f)", PX4_ISFINITE(NAN * 1.0f) == false);