Skip to content

Commit a3fe4e0

Browse files
Register module defaults using static initialization pattern (#125)
* [revert] revert to property initialisation without get_defaults * [updatess] remove get_defaults * [update] remove default property handling from proxy * [feat] awaiting proxy broadcasts with expander * [refactor] refactoring * [feat] register defaults before main * [feat] change to regsiter style * [fix] blank line * [fix] added blank line to output * [fix] added blank lines * add type definitions for defaults functions and registry --------- Co-authored-by: Falko Schindler <falko@zauberzeug.com>
1 parent dec2c01 commit a3fe4e0

28 files changed

+79
-53
lines changed

main/modules/analog.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,8 @@
66
#include "freertos/task.h"
77
#include "uart.h"
88

9+
REGISTER_MODULE_DEFAULTS(Analog)
10+
911
const std::map<std::string, Variable_ptr> Analog::get_defaults() {
1012
return {
1113
{"raw", std::make_shared<IntegerVariable>()},

main/modules/bluetooth.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
#include "bluetooth.h"
22
#include "uart.h"
33

4+
REGISTER_MODULE_DEFAULTS(Bluetooth)
5+
46
const std::map<std::string, Variable_ptr> Bluetooth::get_defaults() {
57
return {};
68
}

main/modules/can.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,8 @@
44
#include "driver/twai.h"
55
#include <stdexcept>
66

7+
REGISTER_MODULE_DEFAULTS(Can)
8+
79
const std::map<std::string, Variable_ptr> Can::get_defaults() {
810
return {
911
{"state", std::make_shared<StringVariable>()},

main/modules/canopen_master.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
#include "canopen_master.h"
22

3+
REGISTER_MODULE_DEFAULTS(CanOpenMaster)
4+
35
const std::map<std::string, Variable_ptr> CanOpenMaster::get_defaults() {
46
return {
57
{"sync_interval", std::make_shared<IntegerVariable>(0)},

main/modules/canopen_motor.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,8 @@ static const std::string PROP_PV_IS_MOVING{"pv_is_moving"};
4747
static const std::string PROP_CTRL_ENA_OP{"ctrl_enable"};
4848
static const std::string PROP_CTRL_HALT{"ctrl_halt"};
4949

50+
REGISTER_MODULE_DEFAULTS(CanOpenMotor)
51+
5052
const std::map<std::string, Variable_ptr> CanOpenMotor::get_defaults() {
5153
return {
5254
{PROP_INITIALIZED, std::make_shared<BooleanVariable>(false)},

main/modules/d1_motor.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,8 @@
44
#include "utils/timing.h"
55
#include <cinttypes>
66

7+
REGISTER_MODULE_DEFAULTS(D1Motor)
8+
79
const std::map<std::string, Variable_ptr> D1Motor::get_defaults() {
810
return {
911
{"switch_search_speed", std::make_shared<IntegerVariable>()},

main/modules/dunker_motor.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,8 @@
44
#include "utils/timing.h"
55
#include <cinttypes>
66

7+
REGISTER_MODULE_DEFAULTS(DunkerMotor)
8+
79
const std::map<std::string, Variable_ptr> DunkerMotor::get_defaults() {
810
return {
911
{"speed", std::make_shared<NumberVariable>()},

main/modules/dunker_wheels.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
#include "dunker_wheels.h"
22
#include <memory>
33

4+
REGISTER_MODULE_DEFAULTS(DunkerWheels)
5+
46
const std::map<std::string, Variable_ptr> DunkerWheels::get_defaults() {
57
return {
68
{"width", std::make_shared<NumberVariable>(1.0)},

main/modules/expander.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,8 @@
99
#include <cstring>
1010
#include <stdexcept>
1111

12+
REGISTER_MODULE_DEFAULTS(Expander)
13+
1214
const std::map<std::string, Variable_ptr> Expander::get_defaults() {
1315
return {
1416
{"boot_timeout", std::make_shared<NumberVariable>(5.0)},

main/modules/imu.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,8 @@
44
#define I2C_MASTER_TX_BUF_DISABLE 0
55
#define I2C_MASTER_RX_BUF_DISABLE 0
66

7+
REGISTER_MODULE_DEFAULTS(Imu)
8+
79
const std::map<std::string, Variable_ptr> Imu::get_defaults() {
810
return {
911
{"acc_x", std::make_shared<NumberVariable>()},

0 commit comments

Comments
 (0)