From 7224f72654e03fa0c6a0e65e683be29df65c7b7a Mon Sep 17 00:00:00 2001 From: Jens <134612744+JensOgorek@users.noreply.github.com> Date: Tue, 3 Dec 2024 14:11:55 +0100 Subject: [PATCH] fix for all modules (#109) --- main/modules/analog.cpp | 5 ++--- main/modules/analog.h | 2 +- main/modules/bluetooth.cpp | 5 ++--- main/modules/bluetooth.h | 2 +- main/modules/can.cpp | 5 ++--- main/modules/can.h | 2 +- main/modules/canopen_master.cpp | 5 ++--- main/modules/canopen_master.h | 2 +- main/modules/canopen_motor.cpp | 5 ++--- main/modules/canopen_motor.h | 2 +- main/modules/d1_motor.cpp | 5 ++--- main/modules/d1_motor.h | 2 +- main/modules/dunker_motor.cpp | 5 ++--- main/modules/dunker_motor.h | 2 +- main/modules/dunker_wheels.cpp | 5 ++--- main/modules/dunker_wheels.h | 2 +- main/modules/expander.cpp | 8 ++++---- main/modules/expander.h | 2 +- main/modules/imu.cpp | 5 ++--- main/modules/imu.h | 2 +- main/modules/input.cpp | 5 ++--- main/modules/input.h | 3 +-- main/modules/linear_motor.cpp | 5 ++--- main/modules/linear_motor.h | 2 +- main/modules/mcp23017.cpp | 5 ++--- main/modules/mcp23017.h | 2 +- main/modules/module.cpp | 2 +- main/modules/module.h | 2 +- main/modules/motor_axis.cpp | 5 ++--- main/modules/motor_axis.h | 2 +- main/modules/odrive_motor.cpp | 5 ++--- main/modules/odrive_motor.h | 2 +- main/modules/odrive_wheels.cpp | 5 ++--- main/modules/odrive_wheels.h | 2 +- main/modules/output.cpp | 5 ++--- main/modules/output.h | 2 +- main/modules/pwm_output.cpp | 5 ++--- main/modules/pwm_output.h | 2 +- main/modules/rmd_motor.cpp | 5 ++--- main/modules/rmd_motor.h | 2 +- main/modules/rmd_pair.cpp | 5 ++--- main/modules/rmd_pair.h | 2 +- main/modules/roboclaw.cpp | 5 ++--- main/modules/roboclaw.h | 2 +- main/modules/roboclaw_motor.cpp | 5 ++--- main/modules/roboclaw_motor.h | 2 +- main/modules/roboclaw_wheels.cpp | 5 ++--- main/modules/roboclaw_wheels.h | 2 +- main/modules/serial.cpp | 5 ++--- main/modules/serial.h | 2 +- main/modules/stepper_motor.cpp | 5 ++--- main/modules/stepper_motor.h | 2 +- 52 files changed, 79 insertions(+), 104 deletions(-) diff --git a/main/modules/analog.cpp b/main/modules/analog.cpp index d076eb5..89929aa 100644 --- a/main/modules/analog.cpp +++ b/main/modules/analog.cpp @@ -6,12 +6,11 @@ #include "freertos/task.h" #include "uart.h" -const std::map &Analog::get_defaults() { - static const std::map defaults = { +const std::map Analog::get_defaults() { + return { {"raw", std::make_shared()}, {"voltage", std::make_shared()}, }; - return defaults; } Analog::Analog(const std::string name, uint8_t unit, uint8_t channel, float attenuation_level) diff --git a/main/modules/analog.h b/main/modules/analog.h index e685588..b47aad4 100644 --- a/main/modules/analog.h +++ b/main/modules/analog.h @@ -17,5 +17,5 @@ class Analog : public Module { public: Analog(const std::string name, uint8_t unit, uint8_t channel, float attenuation_level); void step() override; - static const std::map &get_defaults(); + static const std::map get_defaults(); }; diff --git a/main/modules/bluetooth.cpp b/main/modules/bluetooth.cpp index 3b6deec..93e8e29 100644 --- a/main/modules/bluetooth.cpp +++ b/main/modules/bluetooth.cpp @@ -1,9 +1,8 @@ #include "bluetooth.h" #include "uart.h" -const std::map &Bluetooth::get_defaults() { - static std::map defaults = {}; - return defaults; +const std::map Bluetooth::get_defaults() { + return {}; } Bluetooth::Bluetooth(const std::string name, const std::string device_name, MessageHandler message_handler) diff --git a/main/modules/bluetooth.h b/main/modules/bluetooth.h index ccddbfd..71d4b23 100644 --- a/main/modules/bluetooth.h +++ b/main/modules/bluetooth.h @@ -16,5 +16,5 @@ class Bluetooth : public Module { Bluetooth(const std::string name, const std::string device_name, MessageHandler message_handler); void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); }; diff --git a/main/modules/can.cpp b/main/modules/can.cpp index b1de644..4b64fa7 100644 --- a/main/modules/can.cpp +++ b/main/modules/can.cpp @@ -4,8 +4,8 @@ #include "driver/twai.h" #include -const std::map &Can::get_defaults() { - static const std::map defaults = { +const std::map Can::get_defaults() { + return { {"state", std::make_shared()}, {"tx_error_counter", std::make_shared()}, {"rx_error_counter", std::make_shared()}, @@ -17,7 +17,6 @@ const std::map &Can::get_defaults() { {"arb_lost_count", std::make_shared()}, {"bus_error_count", std::make_shared()}, }; - return defaults; } Can::Can(const std::string name, const gpio_num_t rx_pin, const gpio_num_t tx_pin, const long baud_rate) diff --git a/main/modules/can.h b/main/modules/can.h index bcdc91f..1def1ae 100644 --- a/main/modules/can.h +++ b/main/modules/can.h @@ -15,7 +15,7 @@ class Can : public Module { Can(const std::string name, const gpio_num_t rx_pin, const gpio_num_t tx_pin, const long baud_rate); void step() override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); bool receive(); void send(const uint32_t id, const uint8_t data[8], const bool rtr = false, const uint8_t dlc = 8) const; diff --git a/main/modules/canopen_master.cpp b/main/modules/canopen_master.cpp index b36f8af..8bb8fc1 100644 --- a/main/modules/canopen_master.cpp +++ b/main/modules/canopen_master.cpp @@ -1,10 +1,9 @@ #include "canopen_master.h" -const std::map &CanOpenMaster::get_defaults() { - static const std::map defaults = { +const std::map CanOpenMaster::get_defaults() { + return { {"sync_interval", std::make_shared(0)}, }; - return defaults; } CanOpenMaster::CanOpenMaster(const std::string &name, const Can_ptr can) diff --git a/main/modules/canopen_master.h b/main/modules/canopen_master.h index 7e931ad..842cf40 100644 --- a/main/modules/canopen_master.h +++ b/main/modules/canopen_master.h @@ -14,5 +14,5 @@ class CanOpenMaster : public Module, public std::enable_shared_from_this &get_defaults(); + static const std::map get_defaults(); }; diff --git a/main/modules/canopen_motor.cpp b/main/modules/canopen_motor.cpp index 01290bf..45a7df0 100644 --- a/main/modules/canopen_motor.cpp +++ b/main/modules/canopen_motor.cpp @@ -47,8 +47,8 @@ static const std::string PROP_PV_IS_MOVING{"pv_is_moving"}; static const std::string PROP_CTRL_ENA_OP{"ctrl_enable"}; static const std::string PROP_CTRL_HALT{"ctrl_halt"}; -const std::map &CanOpenMotor::get_defaults() { - static const std::map defaults = { +const std::map CanOpenMotor::get_defaults() { + return { {PROP_INITIALIZED, std::make_shared(false)}, {PROP_PENDING_READS, std::make_shared(0)}, {PROP_PENDING_WRITES, std::make_shared(0)}, @@ -68,7 +68,6 @@ const std::map &CanOpenMotor::get_defaults() { {PROP_CTRL_ENA_OP, std::make_shared(false)}, {PROP_CTRL_HALT, std::make_shared(true)}, }; - return defaults; } CanOpenMotor::CanOpenMotor(const std::string &name, Can_ptr can, int64_t node_id) diff --git a/main/modules/canopen_motor.h b/main/modules/canopen_motor.h index c5ba979..55a7b9d 100644 --- a/main/modules/canopen_motor.h +++ b/main/modules/canopen_motor.h @@ -58,7 +58,7 @@ class CanOpenMotor : public Module, public std::enable_shared_from_this arguments) override; void handle_can_msg(const uint32_t id, const int count, const uint8_t *const data) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); void stop() override; double get_position() override; diff --git a/main/modules/d1_motor.cpp b/main/modules/d1_motor.cpp index a9959fd..0f4e184 100644 --- a/main/modules/d1_motor.cpp +++ b/main/modules/d1_motor.cpp @@ -4,8 +4,8 @@ #include "utils/timing.h" #include -const std::map &D1Motor::get_defaults() { - static const std::map defaults = { +const std::map D1Motor::get_defaults() { + return { {"switch_search_speed", std::make_shared()}, {"zero_search_speed", std::make_shared()}, {"homing_acceleration", std::make_shared()}, @@ -17,7 +17,6 @@ const std::map &D1Motor::get_defaults() { {"status_word", std::make_shared(-1)}, {"status_flags", std::make_shared()}, }; - return defaults; } D1Motor::D1Motor(const std::string &name, Can_ptr can, int64_t node_id) diff --git a/main/modules/d1_motor.h b/main/modules/d1_motor.h index 756f329..2a880dd 100644 --- a/main/modules/d1_motor.h +++ b/main/modules/d1_motor.h @@ -26,7 +26,7 @@ class D1Motor : public Module, public std::enable_shared_from_this { void call(const std::string method_name, const std::vector arguments) override; void step() override; void handle_can_msg(const uint32_t id, const int count, const uint8_t *const data) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); void setup(); void home(); void profile_position(const int32_t position); diff --git a/main/modules/dunker_motor.cpp b/main/modules/dunker_motor.cpp index 993d303..b4670a2 100644 --- a/main/modules/dunker_motor.cpp +++ b/main/modules/dunker_motor.cpp @@ -4,13 +4,12 @@ #include "utils/timing.h" #include -const std::map &DunkerMotor::get_defaults() { - static const std::map defaults = { +const std::map DunkerMotor::get_defaults() { + return { {"speed", std::make_shared()}, {"m_per_turn", std::make_shared(1.0)}, {"reversed", std::make_shared()}, }; - return defaults; } DunkerMotor::DunkerMotor(const std::string &name, Can_ptr can, int64_t node_id) diff --git a/main/modules/dunker_motor.h b/main/modules/dunker_motor.h index 4fd07b8..f81057f 100644 --- a/main/modules/dunker_motor.h +++ b/main/modules/dunker_motor.h @@ -25,7 +25,7 @@ class DunkerMotor : public Module, public std::enable_shared_from_this arguments) override; void handle_can_msg(const uint32_t id, const int count, const uint8_t *const data) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); void speed(const double speed); double get_speed(); }; diff --git a/main/modules/dunker_wheels.cpp b/main/modules/dunker_wheels.cpp index e3c5bc6..449e88a 100644 --- a/main/modules/dunker_wheels.cpp +++ b/main/modules/dunker_wheels.cpp @@ -1,13 +1,12 @@ #include "dunker_wheels.h" #include -const std::map &DunkerWheels::get_defaults() { - static const std::map defaults = { +const std::map DunkerWheels::get_defaults() { + return { {"width", std::make_shared(1.0)}, {"linear_speed", std::make_shared()}, {"angular_speed", std::make_shared()}, }; - return defaults; } DunkerWheels::DunkerWheels(const std::string name, const DunkerMotor_ptr left_motor, const DunkerMotor_ptr right_motor) diff --git a/main/modules/dunker_wheels.h b/main/modules/dunker_wheels.h index 904089a..7ac1cbe 100644 --- a/main/modules/dunker_wheels.h +++ b/main/modules/dunker_wheels.h @@ -12,5 +12,5 @@ class DunkerWheels : public Module { DunkerWheels(const std::string name, const DunkerMotor_ptr left_motor, const DunkerMotor_ptr right_motor); void step() override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); }; diff --git a/main/modules/expander.cpp b/main/modules/expander.cpp index b6407a5..0666af0 100644 --- a/main/modules/expander.cpp +++ b/main/modules/expander.cpp @@ -9,14 +9,14 @@ #include #include -const std::map &Expander::get_defaults() { - static const std::map defaults = { +const std::map Expander::get_defaults() { + return { {"boot_timeout", std::make_shared(5.0)}, {"ping_interval", std::make_shared(1.0)}, {"ping_timeout", std::make_shared(2.0)}, {"is_ready", std::make_shared(false)}, - {"last_message_age", std::make_shared(0)}}; - return defaults; + {"last_message_age", std::make_shared(0)}, + }; } Expander::Expander(const std::string name, diff --git a/main/modules/expander.h b/main/modules/expander.h index a6883e5..b37f375 100644 --- a/main/modules/expander.h +++ b/main/modules/expander.h @@ -45,5 +45,5 @@ class Expander : public Module { void add_proxy(const std::string module_name, const std::string module_type, const std::vector arguments); - static const std::map &get_defaults(); + static const std::map get_defaults(); }; diff --git a/main/modules/imu.cpp b/main/modules/imu.cpp index 58df53e..ed89f08 100644 --- a/main/modules/imu.cpp +++ b/main/modules/imu.cpp @@ -4,8 +4,8 @@ #define I2C_MASTER_TX_BUF_DISABLE 0 #define I2C_MASTER_RX_BUF_DISABLE 0 -const std::map &Imu::get_defaults() { - static const std::map defaults = { +const std::map Imu::get_defaults() { + return { {"acc_x", std::make_shared()}, {"acc_y", std::make_shared()}, {"acc_z", std::make_shared()}, @@ -21,7 +21,6 @@ const std::map &Imu::get_defaults() { {"cal_acc", std::make_shared()}, {"cal_mag", std::make_shared()}, }; - return defaults; } Imu::Imu(const std::string name, i2c_port_t i2c_port, gpio_num_t sda_pin, gpio_num_t scl_pin, uint8_t address, int clk_speed) diff --git a/main/modules/imu.h b/main/modules/imu.h index df277fd..39bc6a2 100644 --- a/main/modules/imu.h +++ b/main/modules/imu.h @@ -18,5 +18,5 @@ class Imu : public Module { public: Imu(const std::string name, i2c_port_t i2c_port, gpio_num_t sda_pin, gpio_num_t scl_pin, uint8_t address, int clk_speed); void step() override; - static const std::map &get_defaults(); + static const std::map get_defaults(); }; diff --git a/main/modules/input.cpp b/main/modules/input.cpp index 8469056..aefc84c 100644 --- a/main/modules/input.cpp +++ b/main/modules/input.cpp @@ -4,14 +4,13 @@ #include #include -const std::map &Input::get_defaults() { - static const std::map defaults = { +const std::map Input::get_defaults() { + return { {"level", std::make_shared()}, {"change", std::make_shared()}, {"inverted", std::make_shared()}, {"active", std::make_shared()}, }; - return defaults; } Input::Input(const std::string name) : Module(input, name) { diff --git a/main/modules/input.h b/main/modules/input.h index 71d1bb0..d809f3c 100644 --- a/main/modules/input.h +++ b/main/modules/input.h @@ -17,8 +17,7 @@ class Input : public Module { public: void step() override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); - + static const std::map get_defaults(); std::string get_output() const override; virtual bool get_level() const = 0; }; diff --git a/main/modules/linear_motor.cpp b/main/modules/linear_motor.cpp index 09a5fb2..8ab355a 100644 --- a/main/modules/linear_motor.cpp +++ b/main/modules/linear_motor.cpp @@ -1,12 +1,11 @@ #include "linear_motor.h" #include -const std::map &LinearMotor::get_defaults() { - static const std::map defaults = { +const std::map LinearMotor::get_defaults() { + return { {"in", std::make_shared()}, {"out", std::make_shared()}, }; - return defaults; } LinearMotor::LinearMotor(const std::string name) : Module(output, name) { diff --git a/main/modules/linear_motor.h b/main/modules/linear_motor.h index a465f44..ff39e3c 100644 --- a/main/modules/linear_motor.h +++ b/main/modules/linear_motor.h @@ -17,7 +17,7 @@ class LinearMotor : public Module { public: void step() override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); }; class GpioLinearMotor : public LinearMotor { diff --git a/main/modules/mcp23017.cpp b/main/modules/mcp23017.cpp index 13c133d..7adc013 100644 --- a/main/modules/mcp23017.cpp +++ b/main/modules/mcp23017.cpp @@ -4,13 +4,12 @@ #define I2C_MASTER_TX_BUF_DISABLE 0 #define I2C_MASTER_RX_BUF_DISABLE 0 -const std::map &Mcp23017::get_defaults() { - static const std::map defaults = { +const std::map Mcp23017::get_defaults() { + return { {"levels", std::make_shared()}, {"inputs", std::make_shared(0xffff)}, // default: all pins input {"pullups", std::make_shared()}, }; - return defaults; } Mcp23017::Mcp23017(const std::string name, i2c_port_t i2c_port, gpio_num_t sda_pin, gpio_num_t scl_pin, uint8_t address, int clk_speed) diff --git a/main/modules/mcp23017.h b/main/modules/mcp23017.h index 7bfb854..d3ab94b 100644 --- a/main/modules/mcp23017.h +++ b/main/modules/mcp23017.h @@ -31,7 +31,7 @@ class Mcp23017 : public Module { Mcp23017(const std::string name, i2c_port_t i2c_port, gpio_num_t sda_pin, gpio_num_t scl_pin, uint8_t address, int clk_speed); void step() override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); bool get_level(const uint8_t number) const; void set_level(const uint8_t number, const bool value) const; diff --git a/main/modules/module.cpp b/main/modules/module.cpp index 33c0711..0d728c5 100644 --- a/main/modules/module.cpp +++ b/main/modules/module.cpp @@ -420,7 +420,7 @@ void Module::handle_can_msg(const uint32_t id, const int count, const uint8_t *d throw std::runtime_error("CAN message handler is not implemented"); } -const std::map &Module::get_module_defaults(const std::string &type_name) { +const std::map Module::get_module_defaults(const std::string &type_name) { if (type_name == "Expander") { return Expander::get_defaults(); } else if (type_name == "Input") { diff --git a/main/modules/module.h b/main/modules/module.h index 3f94469..4147b87 100644 --- a/main/modules/module.h +++ b/main/modules/module.h @@ -62,7 +62,7 @@ class Module { MessageHandler message_handler); virtual void step(); virtual void call(const std::string method_name, const std::vector arguments); - static const std::map &get_module_defaults(const std::string &type_name); + static const std::map get_module_defaults(const std::string &type_name); void call_with_shadows(const std::string method_name, const std::vector arguments); virtual std::string get_output() const; Variable_ptr get_property(const std::string property_name) const; diff --git a/main/modules/motor_axis.cpp b/main/modules/motor_axis.cpp index c3406cb..f38ff6c 100644 --- a/main/modules/motor_axis.cpp +++ b/main/modules/motor_axis.cpp @@ -2,9 +2,8 @@ #include "utils/uart.h" #include -const std::map &MotorAxis::get_defaults() { - static std::map defaults = {}; - return defaults; +const std::map MotorAxis::get_defaults() { + return {}; } MotorAxis::MotorAxis(const std::string name, const Motor_ptr motor, const Input_ptr input1, const Input_ptr input2) diff --git a/main/modules/motor_axis.h b/main/modules/motor_axis.h index 5feb507..c78c323 100644 --- a/main/modules/motor_axis.h +++ b/main/modules/motor_axis.h @@ -15,5 +15,5 @@ class MotorAxis : public Module { MotorAxis(const std::string name, const Motor_ptr motor, const Input_ptr input1, const Input_ptr input2); void step() override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); }; diff --git a/main/modules/odrive_motor.cpp b/main/modules/odrive_motor.cpp index 8951ddb..2a0b75e 100644 --- a/main/modules/odrive_motor.cpp +++ b/main/modules/odrive_motor.cpp @@ -2,8 +2,8 @@ #include #include -const std::map &ODriveMotor::get_defaults() { - static const std::map defaults = { +const std::map ODriveMotor::get_defaults() { + return { {"position", std::make_shared()}, {"speed", std::make_shared()}, {"tick_offset", std::make_shared()}, @@ -13,7 +13,6 @@ const std::map &ODriveMotor::get_defaults() { {"axis_error", std::make_shared()}, {"motor_error_flag", std::make_shared()}, }; - return defaults; } ODriveMotor::ODriveMotor(const std::string name, const Can_ptr can, const uint32_t can_id, const uint32_t version) diff --git a/main/modules/odrive_motor.h b/main/modules/odrive_motor.h index 64bc221..87c7d41 100644 --- a/main/modules/odrive_motor.h +++ b/main/modules/odrive_motor.h @@ -25,7 +25,7 @@ class ODriveMotor : public Module, public std::enable_shared_from_this arguments) override; void handle_can_msg(const uint32_t id, const int count, const uint8_t *const data) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); void power(const float torque); void speed(const float speed); void position(const float position); diff --git a/main/modules/odrive_wheels.cpp b/main/modules/odrive_wheels.cpp index cfcda2e..880055a 100644 --- a/main/modules/odrive_wheels.cpp +++ b/main/modules/odrive_wheels.cpp @@ -2,14 +2,13 @@ #include "../utils/timing.h" #include -const std::map &ODriveWheels::get_defaults() { - static const std::map defaults = { +const std::map ODriveWheels::get_defaults() { + return { {"width", std::make_shared(1.0)}, {"linear_speed", std::make_shared()}, {"angular_speed", std::make_shared()}, {"enabled", std::make_shared(true)}, }; - return defaults; } ODriveWheels::ODriveWheels(const std::string name, const ODriveMotor_ptr left_motor, const ODriveMotor_ptr right_motor) diff --git a/main/modules/odrive_wheels.h b/main/modules/odrive_wheels.h index dc02ac6..aee543c 100644 --- a/main/modules/odrive_wheels.h +++ b/main/modules/odrive_wheels.h @@ -17,5 +17,5 @@ class ODriveWheels : public Module { ODriveWheels(const std::string name, const ODriveMotor_ptr left_motor, const ODriveMotor_ptr right_motor); void step() override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); }; diff --git a/main/modules/output.cpp b/main/modules/output.cpp index d02f87f..7938b3a 100644 --- a/main/modules/output.cpp +++ b/main/modules/output.cpp @@ -3,12 +3,11 @@ #include #include -const std::map &Output::get_defaults() { - static const std::map defaults = { +const std::map Output::get_defaults() { + return { {"level", std::make_shared()}, {"change", std::make_shared()}, }; - return defaults; } Output::Output(const std::string name) : Module(output, name) { diff --git a/main/modules/output.h b/main/modules/output.h index f3f8ea7..d336e1d 100644 --- a/main/modules/output.h +++ b/main/modules/output.h @@ -17,7 +17,7 @@ class Output : public Module { public: void step() override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); }; class GpioOutput : public Output { diff --git a/main/modules/pwm_output.cpp b/main/modules/pwm_output.cpp index 747803c..dc7362a 100644 --- a/main/modules/pwm_output.cpp +++ b/main/modules/pwm_output.cpp @@ -1,12 +1,11 @@ #include "pwm_output.h" #include -const std::map &PwmOutput::get_defaults() { - static const std::map defaults = { +const std::map PwmOutput::get_defaults() { + return { {"frequency", std::make_shared(1000)}, {"duty", std::make_shared(128)}, }; - return defaults; } PwmOutput::PwmOutput(const std::string name, diff --git a/main/modules/pwm_output.h b/main/modules/pwm_output.h index 2cfd5c9..f00bcae 100644 --- a/main/modules/pwm_output.h +++ b/main/modules/pwm_output.h @@ -18,5 +18,5 @@ class PwmOutput : public Module { const ledc_channel_t ledc_channel); void step() override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); }; diff --git a/main/modules/rmd_motor.cpp b/main/modules/rmd_motor.cpp index 9d9847d..cc2e08a 100644 --- a/main/modules/rmd_motor.cpp +++ b/main/modules/rmd_motor.cpp @@ -6,15 +6,14 @@ #include #include -const std::map &RmdMotor::get_defaults() { - static const std::map defaults = { +const std::map RmdMotor::get_defaults() { + return { {"position", std::make_shared()}, {"torque", std::make_shared()}, {"speed", std::make_shared()}, {"temperature", std::make_shared()}, {"can_age", std::make_shared()}, }; - return defaults; } RmdMotor::RmdMotor(const std::string name, const Can_ptr can, const uint8_t motor_id, const int ratio) diff --git a/main/modules/rmd_motor.h b/main/modules/rmd_motor.h index 241a3e1..0897817 100644 --- a/main/modules/rmd_motor.h +++ b/main/modules/rmd_motor.h @@ -29,7 +29,7 @@ class RmdMotor : public Module, public std::enable_shared_from_this { void step() override; void call(const std::string method_name, const std::vector arguments) override; void handle_can_msg(const uint32_t id, const int count, const uint8_t *const data) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); bool power(double target_power); bool speed(double target_speed); diff --git a/main/modules/rmd_pair.cpp b/main/modules/rmd_pair.cpp index 5a116f4..1ee5999 100644 --- a/main/modules/rmd_pair.cpp +++ b/main/modules/rmd_pair.cpp @@ -3,12 +3,11 @@ #include "utils/uart.h" #include -const std::map &RmdPair::get_defaults() { - static const std::map defaults = { +const std::map RmdPair::get_defaults() { + return { {"v_max", std::make_shared(360)}, {"a_max", std::make_shared(10000)}, }; - return defaults; } RmdPair::RmdPair(const std::string name, const RmdMotor_ptr rmd1, const RmdMotor_ptr rmd2) diff --git a/main/modules/rmd_pair.h b/main/modules/rmd_pair.h index f1fea0e..cfdc3a4 100644 --- a/main/modules/rmd_pair.h +++ b/main/modules/rmd_pair.h @@ -29,5 +29,5 @@ class RmdPair : public Module { public: RmdPair(const std::string name, const RmdMotor_ptr rmd1, const RmdMotor_ptr rmd2); void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); }; diff --git a/main/modules/roboclaw.cpp b/main/modules/roboclaw.cpp index 3ce4ade..cdcc205 100644 --- a/main/modules/roboclaw.cpp +++ b/main/modules/roboclaw.cpp @@ -5,11 +5,10 @@ #define SetDWORDval(arg) (uint8_t)(((uint32_t)arg) >> 24), (uint8_t)(((uint32_t)arg) >> 16), (uint8_t)(((uint32_t)arg) >> 8), (uint8_t)arg #define SetWORDval(arg) (uint8_t)(((uint16_t)arg) >> 8), (uint8_t)arg -const std::map &RoboClaw::get_defaults() { - static const std::map defaults = { +const std::map RoboClaw::get_defaults() { + return { {"temperature", std::make_shared()}, }; - return defaults; } RoboClaw::RoboClaw(const std::string name, const ConstSerial_ptr serial, const uint8_t address) diff --git a/main/modules/roboclaw.h b/main/modules/roboclaw.h index 032ed8e..6996dff 100644 --- a/main/modules/roboclaw.h +++ b/main/modules/roboclaw.h @@ -117,7 +117,7 @@ class RoboClaw : public Module { public: RoboClaw(const std::string name, const ConstSerial_ptr serial, const uint8_t address); void step() override; - static const std::map &get_defaults(); + static const std::map get_defaults(); bool ForwardM1(uint8_t speed); bool BackwardM1(uint8_t speed); diff --git a/main/modules/roboclaw_motor.cpp b/main/modules/roboclaw_motor.cpp index 649ed2d..3fac09e 100644 --- a/main/modules/roboclaw_motor.cpp +++ b/main/modules/roboclaw_motor.cpp @@ -4,11 +4,10 @@ #define constrain(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt))) -const std::map &RoboClawMotor::get_defaults() { - static const std::map defaults = { +const std::map RoboClawMotor::get_defaults() { + return { {"position", std::make_shared()}, }; - return defaults; } RoboClawMotor::RoboClawMotor(const std::string name, const RoboClaw_ptr roboclaw, const unsigned int motor_number) diff --git a/main/modules/roboclaw_motor.h b/main/modules/roboclaw_motor.h index aca180f..3d1e8e2 100644 --- a/main/modules/roboclaw_motor.h +++ b/main/modules/roboclaw_motor.h @@ -15,7 +15,7 @@ class RoboClawMotor : public Module { RoboClawMotor(const std::string name, const RoboClaw_ptr roboclaw, const unsigned int motor_number); void step() override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); int64_t get_position() const; void power(double value); diff --git a/main/modules/roboclaw_wheels.cpp b/main/modules/roboclaw_wheels.cpp index 078c9ba..2936c6a 100644 --- a/main/modules/roboclaw_wheels.cpp +++ b/main/modules/roboclaw_wheels.cpp @@ -2,15 +2,14 @@ #include "../utils/timing.h" #include -const std::map &RoboClawWheels::get_defaults() { - static const std::map defaults = { +const std::map RoboClawWheels::get_defaults() { + return { {"width", std::make_shared(1)}, {"linear_speed", std::make_shared()}, {"angular_speed", std::make_shared()}, {"enabled", std::make_shared(true)}, {"m_per_tick", std::make_shared(1)}, }; - return defaults; } RoboClawWheels::RoboClawWheels(const std::string name, const RoboClawMotor_ptr left_motor, const RoboClawMotor_ptr right_motor) diff --git a/main/modules/roboclaw_wheels.h b/main/modules/roboclaw_wheels.h index a5a9fd4..def922c 100644 --- a/main/modules/roboclaw_wheels.h +++ b/main/modules/roboclaw_wheels.h @@ -16,5 +16,5 @@ class RoboClawWheels : public Module { RoboClawWheels(const std::string name, const RoboClawMotor_ptr left_motor, const RoboClawMotor_ptr right_motor); void step() override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); }; diff --git a/main/modules/serial.cpp b/main/modules/serial.cpp index 51884b2..721e2a2 100644 --- a/main/modules/serial.cpp +++ b/main/modules/serial.cpp @@ -8,9 +8,8 @@ #define TX_BUF_SIZE 2048 #define UART_PATTERN_QUEUE_SIZE 100 -const std::map &Serial::get_defaults() { - static const std::map defaults = {}; - return defaults; +const std::map Serial::get_defaults() { + return {}; } Serial::Serial(const std::string name, diff --git a/main/modules/serial.h b/main/modules/serial.h index f5a36b1..b824810 100644 --- a/main/modules/serial.h +++ b/main/modules/serial.h @@ -32,5 +32,5 @@ class Serial : public Module { void clear() const; std::string get_output() const override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); }; diff --git a/main/modules/stepper_motor.cpp b/main/modules/stepper_motor.cpp index ba4ff0b..8f491d3 100644 --- a/main/modules/stepper_motor.cpp +++ b/main/modules/stepper_motor.cpp @@ -13,13 +13,12 @@ #define MIN_SPEED 490 -const std::map &StepperMotor::get_defaults() { - static const std::map defaults = { +const std::map StepperMotor::get_defaults() { + return { {"position", std::make_shared()}, {"speed", std::make_shared()}, {"idle", std::make_shared(true)}, }; - return defaults; } StepperMotor::StepperMotor(const std::string name, diff --git a/main/modules/stepper_motor.h b/main/modules/stepper_motor.h index 8b5deab..bc9a775 100644 --- a/main/modules/stepper_motor.h +++ b/main/modules/stepper_motor.h @@ -45,7 +45,7 @@ class StepperMotor : public Module, virtual public Motor { const ledc_channel_t ledc_channel); void step() override; void call(const std::string method_name, const std::vector arguments) override; - static const std::map &get_defaults(); + static const std::map get_defaults(); StepperState get_state() const { return this->state; } int32_t get_target_position() const { return this->target_position; }