Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Property assignment fix #109

Merged
merged 1 commit into from
Dec 3, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 2 additions & 3 deletions main/modules/analog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,11 @@
#include "freertos/task.h"
#include "uart.h"

const std::map<std::string, Variable_ptr> &Analog::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> Analog::get_defaults() {
return {
{"raw", std::make_shared<IntegerVariable>()},
{"voltage", std::make_shared<NumberVariable>()},
};
return defaults;
}

Analog::Analog(const std::string name, uint8_t unit, uint8_t channel, float attenuation_level)
Expand Down
2 changes: 1 addition & 1 deletion main/modules/analog.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();
};
5 changes: 2 additions & 3 deletions main/modules/bluetooth.cpp
Original file line number Diff line number Diff line change
@@ -1,9 +1,8 @@
#include "bluetooth.h"
#include "uart.h"

const std::map<std::string, Variable_ptr> &Bluetooth::get_defaults() {
static std::map<std::string, Variable_ptr> defaults = {};
return defaults;
const std::map<std::string, Variable_ptr> Bluetooth::get_defaults() {
return {};
}

Bluetooth::Bluetooth(const std::string name, const std::string device_name, MessageHandler message_handler)
Expand Down
2 changes: 1 addition & 1 deletion main/modules/bluetooth.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<ConstExpression_ptr> arguments) override;
static const std::map<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();
};
5 changes: 2 additions & 3 deletions main/modules/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
#include "driver/twai.h"
#include <stdexcept>

const std::map<std::string, Variable_ptr> &Can::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> Can::get_defaults() {
return {
{"state", std::make_shared<StringVariable>()},
{"tx_error_counter", std::make_shared<IntegerVariable>()},
{"rx_error_counter", std::make_shared<IntegerVariable>()},
Expand All @@ -17,7 +17,6 @@ const std::map<std::string, Variable_ptr> &Can::get_defaults() {
{"arb_lost_count", std::make_shared<IntegerVariable>()},
{"bus_error_count", std::make_shared<IntegerVariable>()},
};
return defaults;
}

Can::Can(const std::string name, const gpio_num_t rx_pin, const gpio_num_t tx_pin, const long baud_rate)
Expand Down
2 changes: 1 addition & 1 deletion main/modules/can.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<ConstExpression_ptr> arguments) override;
static const std::map<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> 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;
Expand Down
5 changes: 2 additions & 3 deletions main/modules/canopen_master.cpp
Original file line number Diff line number Diff line change
@@ -1,10 +1,9 @@
#include "canopen_master.h"

const std::map<std::string, Variable_ptr> &CanOpenMaster::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> CanOpenMaster::get_defaults() {
return {
{"sync_interval", std::make_shared<IntegerVariable>(0)},
};
return defaults;
}

CanOpenMaster::CanOpenMaster(const std::string &name, const Can_ptr can)
Expand Down
2 changes: 1 addition & 1 deletion main/modules/canopen_master.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,5 +14,5 @@ class CanOpenMaster : public Module, public std::enable_shared_from_this<CanOpen
public:
CanOpenMaster(const std::string &name, const Can_ptr can);
void step() override;
static const std::map<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();
};
5 changes: 2 additions & 3 deletions main/modules/canopen_motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string, Variable_ptr> &CanOpenMotor::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> CanOpenMotor::get_defaults() {
return {
{PROP_INITIALIZED, std::make_shared<BooleanVariable>(false)},
{PROP_PENDING_READS, std::make_shared<IntegerVariable>(0)},
{PROP_PENDING_WRITES, std::make_shared<IntegerVariable>(0)},
Expand All @@ -68,7 +68,6 @@ const std::map<std::string, Variable_ptr> &CanOpenMotor::get_defaults() {
{PROP_CTRL_ENA_OP, std::make_shared<BooleanVariable>(false)},
{PROP_CTRL_HALT, std::make_shared<BooleanVariable>(true)},
};
return defaults;
}

CanOpenMotor::CanOpenMotor(const std::string &name, Can_ptr can, int64_t node_id)
Expand Down
2 changes: 1 addition & 1 deletion main/modules/canopen_motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ class CanOpenMotor : public Module, public std::enable_shared_from_this<CanOpenM
void subscribe_to_can();
void call(const std::string method_name, const std::vector<ConstExpression_ptr> arguments) override;
void handle_can_msg(const uint32_t id, const int count, const uint8_t *const data) override;
static const std::map<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();

void stop() override;
double get_position() override;
Expand Down
5 changes: 2 additions & 3 deletions main/modules/d1_motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
#include "utils/timing.h"
#include <cinttypes>

const std::map<std::string, Variable_ptr> &D1Motor::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> D1Motor::get_defaults() {
return {
{"switch_search_speed", std::make_shared<IntegerVariable>()},
{"zero_search_speed", std::make_shared<IntegerVariable>()},
{"homing_acceleration", std::make_shared<IntegerVariable>()},
Expand All @@ -17,7 +17,6 @@ const std::map<std::string, Variable_ptr> &D1Motor::get_defaults() {
{"status_word", std::make_shared<IntegerVariable>(-1)},
{"status_flags", std::make_shared<IntegerVariable>()},
};
return defaults;
}

D1Motor::D1Motor(const std::string &name, Can_ptr can, int64_t node_id)
Expand Down
2 changes: 1 addition & 1 deletion main/modules/d1_motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class D1Motor : public Module, public std::enable_shared_from_this<D1Motor> {
void call(const std::string method_name, const std::vector<ConstExpression_ptr> 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<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();
void setup();
void home();
void profile_position(const int32_t position);
Expand Down
5 changes: 2 additions & 3 deletions main/modules/dunker_motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,12 @@
#include "utils/timing.h"
#include <cinttypes>

const std::map<std::string, Variable_ptr> &DunkerMotor::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> DunkerMotor::get_defaults() {
return {
{"speed", std::make_shared<NumberVariable>()},
{"m_per_turn", std::make_shared<NumberVariable>(1.0)},
{"reversed", std::make_shared<BooleanVariable>()},
};
return defaults;
}

DunkerMotor::DunkerMotor(const std::string &name, Can_ptr can, int64_t node_id)
Expand Down
2 changes: 1 addition & 1 deletion main/modules/dunker_motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ class DunkerMotor : public Module, public std::enable_shared_from_this<DunkerMot
void subscribe_to_can();
void call(const std::string method_name, const std::vector<ConstExpression_ptr> arguments) override;
void handle_can_msg(const uint32_t id, const int count, const uint8_t *const data) override;
static const std::map<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();
void speed(const double speed);
double get_speed();
};
5 changes: 2 additions & 3 deletions main/modules/dunker_wheels.cpp
Original file line number Diff line number Diff line change
@@ -1,13 +1,12 @@
#include "dunker_wheels.h"
#include <memory>

const std::map<std::string, Variable_ptr> &DunkerWheels::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> DunkerWheels::get_defaults() {
return {
{"width", std::make_shared<NumberVariable>(1.0)},
{"linear_speed", std::make_shared<NumberVariable>()},
{"angular_speed", std::make_shared<NumberVariable>()},
};
return defaults;
}

DunkerWheels::DunkerWheels(const std::string name, const DunkerMotor_ptr left_motor, const DunkerMotor_ptr right_motor)
Expand Down
2 changes: 1 addition & 1 deletion main/modules/dunker_wheels.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<ConstExpression_ptr> arguments) override;
static const std::map<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();
};
8 changes: 4 additions & 4 deletions main/modules/expander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,14 +9,14 @@
#include <cstring>
#include <stdexcept>

const std::map<std::string, Variable_ptr> &Expander::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> Expander::get_defaults() {
return {
{"boot_timeout", std::make_shared<NumberVariable>(5.0)},
{"ping_interval", std::make_shared<NumberVariable>(1.0)},
{"ping_timeout", std::make_shared<NumberVariable>(2.0)},
{"is_ready", std::make_shared<BooleanVariable>(false)},
{"last_message_age", std::make_shared<IntegerVariable>(0)}};
return defaults;
{"last_message_age", std::make_shared<IntegerVariable>(0)},
};
}

Expander::Expander(const std::string name,
Expand Down
2 changes: 1 addition & 1 deletion main/modules/expander.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,5 +45,5 @@ class Expander : public Module {
void add_proxy(const std::string module_name,
const std::string module_type,
const std::vector<ConstExpression_ptr> arguments);
static const std::map<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();
};
5 changes: 2 additions & 3 deletions main/modules/imu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
#define I2C_MASTER_TX_BUF_DISABLE 0
#define I2C_MASTER_RX_BUF_DISABLE 0

const std::map<std::string, Variable_ptr> &Imu::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> Imu::get_defaults() {
return {
{"acc_x", std::make_shared<NumberVariable>()},
{"acc_y", std::make_shared<NumberVariable>()},
{"acc_z", std::make_shared<NumberVariable>()},
Expand All @@ -21,7 +21,6 @@ const std::map<std::string, Variable_ptr> &Imu::get_defaults() {
{"cal_acc", std::make_shared<NumberVariable>()},
{"cal_mag", std::make_shared<NumberVariable>()},
};
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)
Expand Down
2 changes: 1 addition & 1 deletion main/modules/imu.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();
};
5 changes: 2 additions & 3 deletions main/modules/input.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,14 +4,13 @@
#include <memory>
#include <stdexcept>

const std::map<std::string, Variable_ptr> &Input::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> Input::get_defaults() {
return {
{"level", std::make_shared<IntegerVariable>()},
{"change", std::make_shared<IntegerVariable>()},
{"inverted", std::make_shared<BooleanVariable>()},
{"active", std::make_shared<BooleanVariable>()},
};
return defaults;
}

Input::Input(const std::string name) : Module(input, name) {
Expand Down
3 changes: 1 addition & 2 deletions main/modules/input.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,7 @@ class Input : public Module {
public:
void step() override;
void call(const std::string method_name, const std::vector<ConstExpression_ptr> arguments) override;
static const std::map<std::string, Variable_ptr> &get_defaults();

static const std::map<std::string, Variable_ptr> get_defaults();
std::string get_output() const override;
virtual bool get_level() const = 0;
};
Expand Down
5 changes: 2 additions & 3 deletions main/modules/linear_motor.cpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,11 @@
#include "linear_motor.h"
#include <memory>

const std::map<std::string, Variable_ptr> &LinearMotor::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> LinearMotor::get_defaults() {
return {
{"in", std::make_shared<BooleanVariable>()},
{"out", std::make_shared<BooleanVariable>()},
};
return defaults;
}

LinearMotor::LinearMotor(const std::string name) : Module(output, name) {
Expand Down
2 changes: 1 addition & 1 deletion main/modules/linear_motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ class LinearMotor : public Module {
public:
void step() override;
void call(const std::string method_name, const std::vector<ConstExpression_ptr> arguments) override;
static const std::map<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();
};

class GpioLinearMotor : public LinearMotor {
Expand Down
5 changes: 2 additions & 3 deletions main/modules/mcp23017.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,12 @@
#define I2C_MASTER_TX_BUF_DISABLE 0
#define I2C_MASTER_RX_BUF_DISABLE 0

const std::map<std::string, Variable_ptr> &Mcp23017::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> Mcp23017::get_defaults() {
return {
{"levels", std::make_shared<IntegerVariable>()},
{"inputs", std::make_shared<IntegerVariable>(0xffff)}, // default: all pins input
{"pullups", std::make_shared<IntegerVariable>()},
};
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)
Expand Down
2 changes: 1 addition & 1 deletion main/modules/mcp23017.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<ConstExpression_ptr> arguments) override;
static const std::map<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();

bool get_level(const uint8_t number) const;
void set_level(const uint8_t number, const bool value) const;
Expand Down
2 changes: 1 addition & 1 deletion main/modules/module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string, Variable_ptr> &Module::get_module_defaults(const std::string &type_name) {
const std::map<std::string, Variable_ptr> Module::get_module_defaults(const std::string &type_name) {
if (type_name == "Expander") {
return Expander::get_defaults();
} else if (type_name == "Input") {
Expand Down
2 changes: 1 addition & 1 deletion main/modules/module.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ class Module {
MessageHandler message_handler);
virtual void step();
virtual void call(const std::string method_name, const std::vector<ConstExpression_ptr> arguments);
static const std::map<std::string, Variable_ptr> &get_module_defaults(const std::string &type_name);
static const std::map<std::string, Variable_ptr> get_module_defaults(const std::string &type_name);
void call_with_shadows(const std::string method_name, const std::vector<ConstExpression_ptr> arguments);
virtual std::string get_output() const;
Variable_ptr get_property(const std::string property_name) const;
Expand Down
5 changes: 2 additions & 3 deletions main/modules/motor_axis.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,8 @@
#include "utils/uart.h"
#include <stdexcept>

const std::map<std::string, Variable_ptr> &MotorAxis::get_defaults() {
static std::map<std::string, Variable_ptr> defaults = {};
return defaults;
const std::map<std::string, Variable_ptr> MotorAxis::get_defaults() {
return {};
}

MotorAxis::MotorAxis(const std::string name, const Motor_ptr motor, const Input_ptr input1, const Input_ptr input2)
Expand Down
2 changes: 1 addition & 1 deletion main/modules/motor_axis.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<ConstExpression_ptr> arguments) override;
static const std::map<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();
};
5 changes: 2 additions & 3 deletions main/modules/odrive_motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
#include <cstring>
#include <memory>

const std::map<std::string, Variable_ptr> &ODriveMotor::get_defaults() {
static const std::map<std::string, Variable_ptr> defaults = {
const std::map<std::string, Variable_ptr> ODriveMotor::get_defaults() {
return {
{"position", std::make_shared<NumberVariable>()},
{"speed", std::make_shared<NumberVariable>()},
{"tick_offset", std::make_shared<NumberVariable>()},
Expand All @@ -13,7 +13,6 @@ const std::map<std::string, Variable_ptr> &ODriveMotor::get_defaults() {
{"axis_error", std::make_shared<IntegerVariable>()},
{"motor_error_flag", std::make_shared<IntegerVariable>()},
};
return defaults;
}

ODriveMotor::ODriveMotor(const std::string name, const Can_ptr can, const uint32_t can_id, const uint32_t version)
Expand Down
2 changes: 1 addition & 1 deletion main/modules/odrive_motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ class ODriveMotor : public Module, public std::enable_shared_from_this<ODriveMot
void subscribe_to_can();
void call(const std::string method_name, const std::vector<ConstExpression_ptr> arguments) override;
void handle_can_msg(const uint32_t id, const int count, const uint8_t *const data) override;
static const std::map<std::string, Variable_ptr> &get_defaults();
static const std::map<std::string, Variable_ptr> get_defaults();
void power(const float torque);
void speed(const float speed);
void position(const float position);
Expand Down
Loading