Changes to allow the commander module to be built and run on Qurt (#21186)

* Changed exclusion to rely on the definition of PX4_STORAGEDIR
This commit is contained in:
Eric Katzfey 2023-03-06 06:49:07 -08:00 committed by GitHub
parent dc4926dc4d
commit daa302cdbe
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
9 changed files with 22 additions and 10 deletions

View File

@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_MUORB_SLPI=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_COMMANDER=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_ORB_COMMUNICATOR=y

View File

@ -99,7 +99,10 @@ __END_DECLS
#define PX4_ROOTFSDIR CONFIG_BOARD_ROOTFSDIR
// Qurt doesn't have an SD card for storage
#ifndef __PX4_QURT
#define PX4_STORAGEDIR PX4_ROOTFSDIR
#endif
/****************************************************************************
* Defines for POSIX and ROS

View File

@ -166,11 +166,12 @@ static px4_task_t px4_task_spawn_internal(const char *name, int priority, px4_ma
return -1;
} else {
//px4_clock_gettimemap[task_index].argv_storage[i], argv[i]);
strcpy(taskmap[task_index].argv_storage[i], argv[i]);
taskmap[task_index].argv[i] = taskmap[task_index].argv_storage[i];
}
} else {
// Must add NULL at end of argv
taskmap[task_index].argv[i] = nullptr;
break;
}
@ -420,13 +421,13 @@ int px4_sem_timedwait(px4_sem_t *sem, const struct timespec *ts)
return 0;
}
int px4_prctl(int option, const char *arg2, pthread_t pid)
int px4_prctl(int option, const char *arg2, px4_task_t pid)
{
int rv = -1;
pthread_mutex_lock(&task_mutex);
for (int i = 0; i < PX4_MAX_TASKS; i++) {
if (taskmap[i].isused && taskmap[i].tid == pid) {
if (taskmap[i].isused && taskmap[i].tid == (pthread_t) pid) {
rv = pthread_attr_setthreadname(&taskmap[i].attr, arg2);
return rv;
}

View File

@ -50,7 +50,7 @@
#include <uORB/topics/qshell_retval.h>
#include <drivers/drv_hrt.h>
#define MAX_ARGS 8 // max number of whitespace separated args after app name
#define MAX_ARGS 16 // max number of whitespace separated args after app name
px4::AppState QShell::appState;

View File

@ -231,8 +231,10 @@ private:
hrt_abstime _last_disarmed_timestamp{0};
hrt_abstime _overload_start{0}; ///< time when CPU overload started
hrt_abstime _led_armed_state_toggle{0};
hrt_abstime _led_overload_toggle{0};
#if !defined(CONFIG_ARCH_LEDS) && defined(BOARD_HAS_CONTROL_STATUS_LEDS)
hrt_abstime _led_armed_state_toggle {0};
#endif
hrt_abstime _led_overload_toggle {0};
hrt_abstime _last_health_and_arming_check{0};

View File

@ -40,6 +40,7 @@
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/failsafe_flags.h>
#include <systemlib/mavlink_log.h>
#include <drivers/drv_hrt.h>
#include <stdint.h>
#include <limits.h>

View File

@ -68,7 +68,6 @@
#include "checks/vtolCheck.hpp"
#include "checks/offboardCheck.hpp"
class HealthAndArmingChecks : public ModuleParams
{
public:

View File

@ -38,12 +38,14 @@
#ifdef __PX4_DARWIN
#include <sys/param.h>
#include <sys/mount.h>
#else
#elif defined(PX4_STORAGEDIR)
#include <sys/statfs.h>
#endif
void SdCardChecks::checkAndReport(const Context &context, Report &reporter)
{
#ifdef PX4_STORAGEDIR
if (_param_com_arm_sdcard.get() > 0) {
struct statfs statfs_buf;
@ -125,4 +127,5 @@ void SdCardChecks::checkAndReport(const Context &context, Report &reporter)
}
#endif /* __PX4_NUTTX */
#endif /* PX4_STORAGEDIR */
}

View File

@ -44,11 +44,13 @@ public:
void checkAndReport(const Context &context, Report &reporter) override;
private:
bool _sdcard_detected{false};
#ifdef PX4_STORAGEDIR
bool _sdcard_detected {false};
#ifdef __PX4_NUTTX
bool _hardfault_checked_once {false};
bool _hardfault_file_present{false};
bool _hardfault_file_present {false};
#endif
#endif
DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase,