module_base: remove CRTP template pattern to reduce flash bloat (#26476)

* module_base: claude rewrite to remove CRTP bloat

* module_base: apply to all drivers/modules

* format

* fix build errors

* fix missing syntax

* remove reference to module.h in files that need module_base.h

* remove old ModuleBase<T>

* add module_base.cpp to px4_protected_layers.cmake

* fix IridiumSBD can_stop()

* fix IridiumSBD.cpp

* clang-tidy: downcast static cast

* get_instance() template accessor, revert clang-tidy global

* rename module_base.h to module.h

* revert changes in zenoh/Kconfig.topics
This commit is contained in:
Jacob Dahl
2026-02-18 17:17:17 -09:00
committed by GitHub
parent 657854ae1b
commit ce3e62841f
227 changed files with 1741 additions and 1496 deletions

View File

@@ -43,6 +43,8 @@
#include <drivers/drv_hrt.h>
#include <drivers/drv_io_heater.h>
ModuleBase::Descriptor Core_Heater::desc{task_spawn, custom_command, print_usage};
# ifndef GPIO_CORE_HEATER_OUTPUT
# error "To use the heater driver, the board_config.h must define and initialize GPIO_CORE_HEATER_OUTPUT"
# endif
@@ -62,7 +64,7 @@ Core_Heater::~Core_Heater()
int Core_Heater::custom_command(int argc, char *argv[])
{
// Check if the driver is running.
if (!is_running()) {
if (!is_running(desc)) {
PX4_INFO("not running");
return PX4_ERROR;
}
@@ -117,7 +119,7 @@ bool Core_Heater::initialize_topics()
void Core_Heater::Run()
{
if (should_exit()) {
exit_and_cleanup();
exit_and_cleanup(desc);
return;
}
@@ -216,8 +218,8 @@ int Core_Heater::task_spawn(int argc, char *argv[])
return PX4_ERROR;
}
_object.store(core_heater);
_task_id = task_id_is_work_queue;
desc.object.store(core_heater);
desc.task_id = task_id_is_work_queue;
core_heater->start();
return 0;
@@ -257,5 +259,5 @@ Background process running periodically on the LP work queue to regulate IMU tem
extern "C" __EXPORT int core_heater_main(int argc, char *argv[])
{
return Core_Heater::main(argc, argv);
return ModuleBase::main(Core_Heater::desc, argc, argv);
}

View File

@@ -56,9 +56,11 @@ using namespace time_literals;
#define CONTROLLER_PERIOD_DEFAULT 10000
#define TEMPERATURE_TARGET_THRESHOLD 2.5f
class Core_Heater : public ModuleBase<Core_Heater>, public ModuleParams, public px4::ScheduledWorkItem
class Core_Heater : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem
{
public:
static Descriptor desc;
Core_Heater();
virtual ~Core_Heater();

View File

@@ -33,6 +33,8 @@
#include "NavioRGBLed.hpp"
ModuleBase::Descriptor NavioRGBLed::desc{task_spawn, custom_command, print_usage};
NavioRGBLed::NavioRGBLed() :
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default)
{
@@ -130,8 +132,8 @@ int NavioRGBLed::task_spawn(int argc, char *argv[])
NavioRGBLed *instance = new NavioRGBLed();
if (instance) {
_object.store(instance);
_task_id = task_id_is_work_queue;
desc.object.store(instance);
desc.task_id = task_id_is_work_queue;
if (instance->init() == PX4_OK) {
return PX4_OK;
@@ -142,8 +144,8 @@ int NavioRGBLed::task_spawn(int argc, char *argv[])
}
delete instance;
_object.store(nullptr);
_task_id = -1;
desc.object.store(nullptr);
desc.task_id = -1;
return PX4_ERROR;
}
@@ -170,5 +172,5 @@ Emlid Navio2 RGB LED driver.
extern "C" __EXPORT int navio_rgbled_main(int argc, char *argv[])
{
return NavioRGBLed::main(argc, argv);
return ModuleBase::main(NavioRGBLed::desc, argc, argv);
}

View File

@@ -40,9 +40,11 @@
#include <lib/led/led.h>
class NavioRGBLed : public ModuleBase<NavioRGBLed>, public px4::ScheduledWorkItem
class NavioRGBLed : public ModuleBase, public px4::ScheduledWorkItem
{
public:
static Descriptor desc;
NavioRGBLed();
~NavioRGBLed() override;

View File

@@ -49,6 +49,8 @@
using namespace time_literals;
ModuleBase::Descriptor GhstRc::desc{task_spawn, custom_command, print_usage};
uint32_t GhstRc::baudrate = GHST_BAUDRATE;
GhstRc::GhstRc(const char *device) :
@@ -114,8 +116,8 @@ int GhstRc::task_spawn(int argc, char *argv[])
return PX4_ERROR;
}
_object.store(instance);
_task_id = task_id_is_work_queue;
desc.object.store(instance);
desc.task_id = task_id_is_work_queue;
instance->ScheduleNow();
@@ -174,7 +176,7 @@ void GhstRc::Run()
if (should_exit()) {
ScheduleClear();
_rc_fd = -1;
exit_and_cleanup();
exit_and_cleanup(desc);
return;
}
@@ -308,5 +310,5 @@ This module parses the GHST RC uplink protocol and can generate GHST downlink te
extern "C" __EXPORT int ghst_rc_main(int argc, char *argv[])
{
return GhstRc::main(argc, argv);
return ModuleBase::main(GhstRc::desc, argc, argv);
}

View File

@@ -54,9 +54,11 @@
#define GHST_MAX_NUM_CHANNELS (16)
class GhstRc : public ModuleBase<GhstRc>, public ModuleParams, public px4::ScheduledWorkItem
class GhstRc : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem
{
public:
static Descriptor desc;
GhstRc(const char *device);
~GhstRc() override;

View File

@@ -59,6 +59,8 @@
#include "rc_controller.hpp"
ModuleBase::Descriptor RC_ControllerModule::desc{task_spawn, custom_command, print_usage};
int RC_ControllerModule::print_status()
{
PX4_INFO("Running");
@@ -69,35 +71,35 @@ int RC_ControllerModule::print_status()
int RC_ControllerModule::custom_command(int argc, char *argv[])
{
if (!is_running()) {
if (!is_running(desc)) {
print_usage("not running");
return 1;
}
if (!strcmp(argv[0], "throttle")) {
uint16_t val = atoi(argv[1]);
get_instance()->set_throttle(val);
get_instance<RC_ControllerModule>(desc)->set_throttle(val);
PX4_INFO("Setting throttle to %u", val);
return 0;
}
if (!strcmp(argv[0], "yaw")) {
uint16_t val = atoi(argv[1]);
get_instance()->set_yaw(val);
get_instance<RC_ControllerModule>(desc)->set_yaw(val);
PX4_INFO("Setting yaw to %u", val);
return 0;
}
if (!strcmp(argv[0], "pitch")) {
uint16_t val = atoi(argv[1]);
get_instance()->set_pitch(val);
get_instance<RC_ControllerModule>(desc)->set_pitch(val);
PX4_INFO("Setting pitch to %u", val);
return 0;
}
if (!strcmp(argv[0], "roll")) {
uint16_t val = atoi(argv[1]);
get_instance()->set_roll(val);
get_instance<RC_ControllerModule>(desc)->set_roll(val);
PX4_INFO("Setting roll to %u", val);
return 0;
}
@@ -106,17 +108,24 @@ int RC_ControllerModule::custom_command(int argc, char *argv[])
}
int RC_ControllerModule::run_trampoline(int argc, char *argv[])
{
return ModuleBase::run_trampoline_impl(desc, [](int ac, char *av[]) -> ModuleBase * {
return RC_ControllerModule::instantiate(ac, av);
}, argc, argv);
}
int RC_ControllerModule::task_spawn(int argc, char *argv[])
{
_task_id = px4_task_spawn_cmd("RC_ControllerModule",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX,
1024,
(px4_main_t)&run_trampoline,
(char *const *)argv);
desc.task_id = px4_task_spawn_cmd("RC_ControllerModule",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX,
1024,
(px4_main_t)&run_trampoline,
(char *const *)argv);
if (_task_id < 0) {
_task_id = -1;
if (desc.task_id < 0) {
desc.task_id = -1;
return -errno;
}
@@ -252,5 +261,5 @@ int RC_ControllerModule::print_usage(const char *reason)
int rc_controller_main(int argc, char *argv[])
{
return RC_ControllerModule::main(argc, argv);
return ModuleBase::main(RC_ControllerModule::desc, argc, argv);
}

View File

@@ -41,9 +41,11 @@
extern "C" __EXPORT int rc_controller_main(int argc, char *argv[]);
class RC_ControllerModule : public ModuleBase<RC_ControllerModule>, public ModuleParams
class RC_ControllerModule : public ModuleBase, public ModuleParams
{
public:
static Descriptor desc;
RC_ControllerModule();
virtual ~RC_ControllerModule() = default;
@@ -51,6 +53,9 @@ public:
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase */
static int run_trampoline(int argc, char *argv[]);
/** @see ModuleBase */
static RC_ControllerModule *instantiate(int argc, char *argv[]);

View File

@@ -41,6 +41,8 @@
using namespace std;
ModuleBase::Descriptor VoxlSaveCalParams::desc{task_spawn, custom_command, print_usage};
static bool debug = false;
VoxlSaveCalParams::VoxlSaveCalParams() :
@@ -145,7 +147,7 @@ VoxlSaveCalParams::Run()
{
if (should_exit()) {
_parameter_primary_set_value_request_sub.unregisterCallback();
exit_and_cleanup();
exit_and_cleanup(desc);
return;
}
@@ -186,8 +188,8 @@ int VoxlSaveCalParams::task_spawn(int argc, char *argv[])
VoxlSaveCalParams *instance = new VoxlSaveCalParams();
if (instance) {
_object.store(instance);
_task_id = task_id_is_work_queue;
desc.object.store(instance);
desc.task_id = task_id_is_work_queue;
if (instance->init()) {
return PX4_OK;
@@ -198,8 +200,8 @@ int VoxlSaveCalParams::task_spawn(int argc, char *argv[])
}
delete instance;
_object.store(nullptr);
_task_id = -1;
desc.object.store(nullptr);
desc.task_id = -1;
return PX4_ERROR;
}
@@ -230,5 +232,5 @@ This implements autosaving of calibration parameters on VOXL2 platform.
extern "C" __EXPORT int voxl_save_cal_params_main(int argc, char *argv[])
{
return VoxlSaveCalParams::main(argc, argv);
return ModuleBase::main(VoxlSaveCalParams::desc, argc, argv);
}

View File

@@ -46,10 +46,12 @@
using namespace time_literals;
class VoxlSaveCalParams : public ModuleBase<VoxlSaveCalParams>, public ModuleParams,
class VoxlSaveCalParams : public ModuleBase, public ModuleParams,
public px4::WorkItem
{
public:
static Descriptor desc;
VoxlSaveCalParams();
~VoxlSaveCalParams() = default;