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

Function calls with properties #114

Closed
wants to merge 11 commits into from
2 changes: 1 addition & 1 deletion main/modules/analog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ const std::map<std::string, Variable_ptr> Analog::get_defaults() {

Analog::Analog(const std::string name, uint8_t unit, uint8_t channel, float attenuation_level)
: Module(analog, name), unit(unit), channel(channel) {
this->properties = Analog::get_defaults();
this->merge_properties(Analog::get_defaults());

if (unit < 1 || unit > 2) {
echo("error: invalid unit, using default 1");
Expand Down
2 changes: 1 addition & 1 deletion main/modules/bluetooth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ Bluetooth::Bluetooth(const std::string name, const std::string device_name, Mess
echo("error in bluetooth message handler: %s", e.what());
}
});
this->properties = Bluetooth::get_defaults();
this->merge_properties(Bluetooth::get_defaults());
}

void Bluetooth::call(const std::string method_name, const std::vector<ConstExpression_ptr> arguments) {
Expand Down
27 changes: 25 additions & 2 deletions main/modules/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ Can::Can(const std::string name, const gpio_num_t rx_pin, const gpio_num_t tx_pi
g_config.rx_queue_len = 20;
g_config.tx_queue_len = 20;

this->properties = Can::get_defaults();
this->merge_properties(Can::get_defaults());

ESP_ERROR_CHECK(twai_driver_install(&g_config, &t_config, &f_config));
ESP_ERROR_CHECK(twai_start());
Expand Down Expand Up @@ -102,7 +102,7 @@ bool Can::receive() {
message.data);
}

if (this->output_on) {
if (!this->properties.at("muted")->boolean_value) {
static char buffer[256];
int pos = csprintf(buffer, sizeof(buffer), "%s %03lx", this->name.c_str(), message.identifier);
if (!(message.flags & TWAI_MSG_FLAG_RTR)) {
Expand Down Expand Up @@ -190,3 +190,26 @@ void Can::subscribe(const uint32_t id, const Module_ptr module) {
}
this->subscribers[id] = module;
}

void Can::write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) {
if (property_name == "can_mode") {
const std::string can_mode = expression->evaluate_string();
if (can_mode == "start") {
if (twai_start() != ESP_OK) {
throw std::runtime_error("could not start twai driver");
}
} else if (can_mode == "stop") {
if (twai_stop() != ESP_OK) {
throw std::runtime_error("could not stop twai driver");
}
} else if (can_mode == "recover") {
if (twai_initiate_recovery() != ESP_OK) {
throw std::runtime_error("could not initiate recovery");
}
} else {
throw std::runtime_error("unsupported can_mode");
}
} else {
Module::write_property(property_name, expression, from_expander);
}
}
1 change: 1 addition & 0 deletions main/modules/can.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +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;
void write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) override;
static const std::map<std::string, Variable_ptr> get_defaults();

bool receive();
Expand Down
2 changes: 1 addition & 1 deletion main/modules/canopen_master.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ const std::map<std::string, Variable_ptr> CanOpenMaster::get_defaults() {

CanOpenMaster::CanOpenMaster(const std::string &name, const Can_ptr can)
: Module(canopen_master, name), can(can) {
this->properties = CanOpenMaster::get_defaults();
this->merge_properties(CanOpenMaster::get_defaults());
}

void CanOpenMaster::step() {
Expand Down
53 changes: 52 additions & 1 deletion main/modules/canopen_motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ CanOpenMotor::CanOpenMotor(const std::string &name, Can_ptr can, int64_t node_id
: Module(canopen_motor, name), can(can), node_id(check_node_id(node_id)),
current_op_mode_disp(OP_MODE_NONE), current_op_mode(OP_MODE_NONE) {

this->properties = CanOpenMotor::get_defaults();
this->merge_properties(CanOpenMotor::get_defaults());
}

void CanOpenMotor::wait_for_sdo_writes(uint32_t timeout_ms) {
Expand Down Expand Up @@ -505,3 +505,54 @@ void CanOpenMotor::speed(const double speed, const double acceleration) {
this->properties[PROP_CTRL_HALT]->boolean_value = false;
send_control_word(build_ctrl_word(false));
}

void CanOpenMotor::write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) {
if (property_name == "set_target_position") {
int32_t target_position = expression->evaluate_integer();
int32_t offset = this->properties[PROP_OFFSET]->integer_value;
send_target_position(target_position + offset);
} else if (property_name == "set_target_velocity") {
int32_t target_velocity = expression->evaluate_integer();
send_target_velocity(target_velocity);
} else if (property_name == "enter_mode") {
const std::string mode = expression->evaluate_string();
int32_t velocity = this->properties[PROP_VELOCITY]->integer_value;
if (mode == "enter_pp_mode") {
enter_position_mode(velocity);
} else if (mode == "enter_pv_mode") {
enter_velocity_mode(velocity);
} else {
throw std::runtime_error("invalid mode");
}
} else if (property_name == "set_profile_acceleration") {
uint16_t acceleration = expression->evaluate_integer();
set_profile_acceleration(acceleration);
} else if (property_name == "set_profile_deceleration") {
uint16_t deceleration = expression->evaluate_integer();
set_profile_deceleration(deceleration);
} else if (property_name == "set_profile_quick_stop_deceleration") {
uint16_t deceleration = expression->evaluate_integer();
set_profile_quick_stop_deceleration(deceleration);
} else if (property_name == "commit_target_position") {
if (expression->evaluate_boolean()) {
send_control_word(build_ctrl_word(true));
}
} else if (property_name == "set_ctrl_halt") {
this->properties[PROP_CTRL_HALT]->boolean_value = expression->evaluate_boolean();
send_control_word(build_ctrl_word(false));
} else if (property_name == "set_ctrl_enable") {
this->properties[PROP_CTRL_ENA_OP]->boolean_value = expression->evaluate_boolean();
send_control_word(build_ctrl_word(false));
} else if (property_name == "reset_fault") {
if (expression->evaluate_boolean()) {
this->properties[PROP_CTRL_HALT]->boolean_value = true;
uint16_t ctrl_word = build_ctrl_word(false);
ctrl_word |= (1 << 7);
send_control_word(ctrl_word);
ctrl_word &= ~(1 << 7);
send_control_word(ctrl_word);
}
} else {
Module::write_property(property_name, expression, from_expander);
}
}
1 change: 1 addition & 0 deletions main/modules/canopen_motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ class CanOpenMotor : public Module, public std::enable_shared_from_this<CanOpenM
CanOpenMotor(const std::string &name, const Can_ptr can, int64_t node_id);
void subscribe_to_can();
void call(const std::string method_name, const std::vector<ConstExpression_ptr> arguments) override;
void write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) 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();

Expand Down
2 changes: 1 addition & 1 deletion main/modules/core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ void Core::call(const std::string method_name, const std::vector<ConstExpression
this->output_list.push_back({module, property_name, precision});
}
}
this->output_on = true;
this->properties.at("muted")->boolean_value = false;
} else if (method_name == "startup_checksum") {
uint16_t checksum = 0;
for (char const &c : Storage::startup) {
Expand Down
22 changes: 21 additions & 1 deletion main/modules/d1_motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ const std::map<std::string, Variable_ptr> D1Motor::get_defaults() {

D1Motor::D1Motor(const std::string &name, Can_ptr can, int64_t node_id)
: Module(d1_motor, name), can(can), node_id(check_node_id(node_id)) {
this->properties = D1Motor::get_defaults();
this->merge_properties(D1Motor::get_defaults());
}

void D1Motor::subscribe_to_can() {
Expand Down Expand Up @@ -197,3 +197,23 @@ void D1Motor::profile_velocity(const int32_t velocity) {
void D1Motor::stop() {
this->sdo_write(0x6040, 0, 16, 7);
}

void D1Motor::write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) {
if (property_name == "setup") {
this->setup();
} else if (property_name == "home") {
this->home();
} else if (property_name == "profile_position") {
int32_t position = expression->evaluate_integer();
this->profile_position(position);
} else if (property_name == "profile_velocity") {
int32_t velocity = expression->evaluate_integer();
this->profile_velocity(velocity);
} else if (property_name == "stop") {
this->stop();
} else if (property_name == "reset") {
this->sdo_write(0x6040, 0, 16, 143);
} else {
Module::write_property(property_name, expression, from_expander);
}
}
1 change: 1 addition & 0 deletions main/modules/d1_motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ class D1Motor : public Module, public std::enable_shared_from_this<D1Motor> {
D1Motor(const std::string &name, const Can_ptr can, int64_t node_id);
void subscribe_to_can();
void call(const std::string method_name, const std::vector<ConstExpression_ptr> arguments) override;
void write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) 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();
Expand Down
19 changes: 18 additions & 1 deletion main/modules/dunker_motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ const std::map<std::string, Variable_ptr> DunkerMotor::get_defaults() {

DunkerMotor::DunkerMotor(const std::string &name, Can_ptr can, int64_t node_id)
: Module(dunker_motor, name), can(can), node_id(check_node_id(node_id)) {
this->properties = DunkerMotor::get_defaults();
this->merge_properties(DunkerMotor::get_defaults());
}

void DunkerMotor::subscribe_to_can() {
Expand Down Expand Up @@ -145,3 +145,20 @@ void DunkerMotor::speed(const double speed) {
double DunkerMotor::get_speed() {
return this->properties.at("speed")->number_value;
}

void DunkerMotor::write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) {
if (property_name == "enable") {
if (expression->evaluate_boolean()) {
this->sdo_write(0x4004, 1, 8, 1);
}
} else if (property_name == "disable") {
if (expression->evaluate_boolean()) {
this->sdo_write(0x4004, 1, 8, 0);
}
} else if (property_name == "speed") {
double speed = expression->evaluate_number();
this->speed(speed);
} else {
Module::write_property(property_name, expression, from_expander);
}
}
1 change: 1 addition & 0 deletions main/modules/dunker_motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ class DunkerMotor : public Module, public std::enable_shared_from_this<DunkerMot
DunkerMotor(const std::string &name, const Can_ptr can, int64_t node_id);
void subscribe_to_can();
void call(const std::string method_name, const std::vector<ConstExpression_ptr> arguments) override;
void write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) 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();
void speed(const double speed);
Expand Down
2 changes: 1 addition & 1 deletion main/modules/dunker_wheels.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ const std::map<std::string, Variable_ptr> DunkerWheels::get_defaults() {

DunkerWheels::DunkerWheels(const std::string name, const DunkerMotor_ptr left_motor, const DunkerMotor_ptr right_motor)
: Module(dunker_wheels, name), left_motor(left_motor), right_motor(right_motor) {
this->properties = DunkerWheels::get_defaults();
this->merge_properties(DunkerWheels::get_defaults());
}

void DunkerWheels::step() {
Expand Down
2 changes: 1 addition & 1 deletion main/modules/expander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ Expander::Expander(const std::string name,
enable_pin(enable_pin),
message_handler(message_handler) {

this->properties = Expander::get_defaults();
this->merge_properties(Expander::get_defaults());

this->serial->enable_line_detection();
if (boot_pin != GPIO_NUM_NC && enable_pin != GPIO_NUM_NC) {
Expand Down
2 changes: 1 addition & 1 deletion main/modules/imu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ Imu::Imu(const std::string name, i2c_port_t i2c_port, gpio_num_t sda_pin, gpio_n
} catch (std::exception &ex) {
throw std::runtime_error(std::string("imu setup failed: ") + ex.what());
}
this->properties = Imu::get_defaults();
this->merge_properties(Imu::get_defaults());
}

void Imu::step() {
Expand Down
19 changes: 18 additions & 1 deletion main/modules/input.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ const std::map<std::string, Variable_ptr> Input::get_defaults() {
}

Input::Input(const std::string name) : Module(input, name) {
this->properties = Input::get_defaults();
this->merge_properties(Input::get_defaults());
}

void Input::step() {
Expand Down Expand Up @@ -80,3 +80,20 @@ void McpInput::set_pull_mode(const gpio_pull_mode_t mode) const {
}
this->mcp->set_pullup(this->number, mode == GPIO_PULLUP_ONLY);
}

void Input::write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) {
if (property_name == "pullmode") {
const std::string pull_mode = expression->evaluate_string();
if (pull_mode == "pullup") {
this->set_pull_mode(GPIO_PULLUP_ONLY);
} else if (pull_mode == "pulldown") {
this->set_pull_mode(GPIO_PULLDOWN_ONLY);
} else if (pull_mode == "pulloff") {
this->set_pull_mode(GPIO_FLOATING);
} else {
throw std::runtime_error("invalid pullmode");
}
} else {
Module::write_property(property_name, expression, from_expander);
}
}
1 change: 1 addition & 0 deletions main/modules/input.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ class Input : public Module {
public:
void step() override;
void call(const std::string method_name, const std::vector<ConstExpression_ptr> arguments) override;
void write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) override;
static const std::map<std::string, Variable_ptr> get_defaults();
std::string get_output() const override;
virtual bool get_level() const = 0;
Expand Down
23 changes: 22 additions & 1 deletion main/modules/linear_motor.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include "linear_motor.h"
#include <memory>
#include <stdexcept>

const std::map<std::string, Variable_ptr> LinearMotor::get_defaults() {
return {
Expand All @@ -9,7 +10,7 @@ const std::map<std::string, Variable_ptr> LinearMotor::get_defaults() {
}

LinearMotor::LinearMotor(const std::string name) : Module(output, name) {
this->properties = LinearMotor::get_defaults();
this->merge_properties(LinearMotor::get_defaults());
}

void LinearMotor::step() {
Expand Down Expand Up @@ -100,3 +101,23 @@ void McpLinearMotor::set_in(bool level) const {
void McpLinearMotor::set_out(bool level) const {
return this->mcp->set_level(this->move_out, level);
}

void LinearMotor::write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) {
if (property_name == "mode") {
const std::string mode = expression->evaluate_string();
if (mode == "in") {
this->set_in(1);
this->set_out(0);
} else if (mode == "out") {
this->set_in(0);
this->set_out(1);
} else if (mode == "stop") {
this->set_in(0);
this->set_out(0);
} else {
throw std::runtime_error("invalid mode");
}
} else {
Module::write_property(property_name, expression, from_expander);
}
}
1 change: 1 addition & 0 deletions main/modules/linear_motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ class LinearMotor : public Module {
public:
void step() override;
void call(const std::string method_name, const std::vector<ConstExpression_ptr> arguments) override;
void write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) override;
static const std::map<std::string, Variable_ptr> get_defaults();
};

Expand Down
20 changes: 19 additions & 1 deletion main/modules/mcp23017.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ Mcp23017::Mcp23017(const std::string name, i2c_port_t i2c_port, gpio_num_t sda_p
throw std::runtime_error("could not install i2c driver");
}

this->properties = Mcp23017::get_defaults();
this->merge_properties(Mcp23017::get_defaults());

this->set_inputs(this->properties.at("inputs")->integer_value);
this->set_pullups(this->properties.at("pullups")->integer_value);
Expand Down Expand Up @@ -157,3 +157,21 @@ void Mcp23017::set_pullup(const uint8_t number, const bool value) const {
this->properties.at("pullups")->integer_value = pullups;
this->set_pullups(pullups);
}

void Mcp23017::write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) {
if (property_name == "levels") {
uint16_t value = expression->evaluate_integer();
this->properties.at("levels")->integer_value = value;
this->write_pins(value);
} else if (property_name == "pullups") {
uint16_t value = expression->evaluate_integer();
this->properties.at("pullups")->integer_value = value;
this->set_pullups(value);
} else if (property_name == "inputs") {
uint16_t value = expression->evaluate_integer();
this->properties.at("inputs")->integer_value = value;
this->set_inputs(value);
} else {
Module::write_property(property_name, expression, from_expander);
}
}
1 change: 1 addition & 0 deletions main/modules/mcp23017.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +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;
void write_property(const std::string property_name, const ConstExpression_ptr expression, const bool from_expander) override;
static const std::map<std::string, Variable_ptr> get_defaults();

bool get_level(const uint8_t number) const;
Expand Down
Loading