From 5e1547e979b17a794918b0f53a8f6ef0f6c70ea0 Mon Sep 17 00:00:00 2001 From: Yannis Chatzikonstantinou Date: Wed, 24 Apr 2024 01:46:21 +0300 Subject: [PATCH 1/5] add protocol implementation for 2.0.x spec --- include/tinymovr/can.hpp | 2 + include/tinymovr/commutation_sensor.hpp | 27 +++++++ include/tinymovr/external_spi.hpp | 26 ++++++ include/tinymovr/hall.hpp | 22 +++++ include/tinymovr/helpers.hpp | 8 +- include/tinymovr/motor.hpp | 4 - include/tinymovr/onboard.hpp | 22 +++++ include/tinymovr/position_sensor.hpp | 27 +++++++ include/tinymovr/scheduler.hpp | 3 +- include/tinymovr/select.hpp | 26 ++++++ include/tinymovr/sensors.hpp | 29 +++++++ include/tinymovr/setup.hpp | 29 +++++++ include/tinymovr/tinymovr.hpp | 103 +++++++++++++++++++----- include/tinymovr/user_frame.hpp | 26 ++++++ src/tinymovr/can.cpp | 29 +++++-- src/tinymovr/commutation_sensor.cpp | 79 ++++++++++++++++++ src/tinymovr/controller.cpp | 32 ++++---- src/tinymovr/current.cpp | 42 +++++----- src/tinymovr/external_spi.cpp | 68 ++++++++++++++++ src/tinymovr/hall.cpp | 34 ++++++++ src/tinymovr/homing.cpp | 24 +++--- src/tinymovr/motor.cpp | 72 +++++------------ src/tinymovr/onboard.cpp | 34 ++++++++ src/tinymovr/position.cpp | 12 +-- src/tinymovr/position_sensor.cpp | 79 ++++++++++++++++++ src/tinymovr/scheduler.cpp | 17 +++- src/tinymovr/select.cpp | 12 +++ src/tinymovr/sensors.cpp | 12 +++ src/tinymovr/setup.cpp | 12 +++ src/tinymovr/stall_detect.cpp | 18 ++--- src/tinymovr/tinymovr.cpp | 28 ++++++- src/tinymovr/traj_planner.cpp | 44 +++++----- src/tinymovr/user_frame.cpp | 68 ++++++++++++++++ src/tinymovr/velocity.cpp | 36 ++++----- src/tinymovr/voltage.cpp | 4 +- src/tinymovr/watchdog.cpp | 16 ++-- 36 files changed, 916 insertions(+), 210 deletions(-) create mode 100644 include/tinymovr/commutation_sensor.hpp create mode 100644 include/tinymovr/external_spi.hpp create mode 100644 include/tinymovr/hall.hpp create mode 100644 include/tinymovr/onboard.hpp create mode 100644 include/tinymovr/position_sensor.hpp create mode 100644 include/tinymovr/select.hpp create mode 100644 include/tinymovr/sensors.hpp create mode 100644 include/tinymovr/setup.hpp create mode 100644 include/tinymovr/user_frame.hpp create mode 100644 src/tinymovr/commutation_sensor.cpp create mode 100644 src/tinymovr/external_spi.cpp create mode 100644 src/tinymovr/hall.cpp create mode 100644 src/tinymovr/onboard.cpp create mode 100644 src/tinymovr/position_sensor.cpp create mode 100644 src/tinymovr/select.cpp create mode 100644 src/tinymovr/sensors.cpp create mode 100644 src/tinymovr/setup.cpp create mode 100644 src/tinymovr/user_frame.cpp diff --git a/include/tinymovr/can.hpp b/include/tinymovr/can.hpp index 6f44d56..06852f0 100644 --- a/include/tinymovr/can.hpp +++ b/include/tinymovr/can.hpp @@ -20,5 +20,7 @@ class Can_ : Node void set_rate(uint32_t value); uint32_t get_id(void); void set_id(uint32_t value); + bool get_heartbeat(void); + void set_heartbeat(bool value); }; diff --git a/include/tinymovr/commutation_sensor.hpp b/include/tinymovr/commutation_sensor.hpp new file mode 100644 index 0000000..207d565 --- /dev/null +++ b/include/tinymovr/commutation_sensor.hpp @@ -0,0 +1,27 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#pragma once + +#include + +class Commutation_sensor_ : Node +{ + public: + + Commutation_sensor_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value): + Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; + uint8_t get_connection(void); + void set_connection(uint8_t value); + float get_bandwidth(void); + void set_bandwidth(float value); + int32_t get_raw_angle(void); + float get_position_estimate(void); + float get_velocity_estimate(void); + +}; diff --git a/include/tinymovr/external_spi.hpp b/include/tinymovr/external_spi.hpp new file mode 100644 index 0000000..40078d7 --- /dev/null +++ b/include/tinymovr/external_spi.hpp @@ -0,0 +1,26 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#pragma once + +#include + +class External_spi_ : Node +{ + public: + + External_spi_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value): + Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; + uint8_t get_type(void); + void set_type(uint8_t value); + uint8_t get_rate(void); + void set_rate(uint8_t value); + bool get_calibrated(void); + uint8_t get_errors(void); + +}; diff --git a/include/tinymovr/hall.hpp b/include/tinymovr/hall.hpp new file mode 100644 index 0000000..9d9a1e2 --- /dev/null +++ b/include/tinymovr/hall.hpp @@ -0,0 +1,22 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#pragma once + +#include + +class Hall_ : Node +{ + public: + + Hall_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value): + Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; + bool get_calibrated(void); + uint8_t get_errors(void); + +}; diff --git a/include/tinymovr/helpers.hpp b/include/tinymovr/helpers.hpp index 4428625..4e76723 100644 --- a/include/tinymovr/helpers.hpp +++ b/include/tinymovr/helpers.hpp @@ -22,11 +22,11 @@ #endif #define CAN_EP_SIZE (12) -#define CAN_EP_MASK ((1 << CAN_EP_SIZE) - 1) +#define CAN_EP_MASK ((1UL << CAN_EP_SIZE) - 1) #define CAN_SEQ_SIZE (9) -#define CAN_SEQ_MASK (((1 << CAN_SEQ_SIZE) - 1) << CAN_EP_SIZE) +#define CAN_SEQ_MASK (((1UL << CAN_SEQ_SIZE) - 1) << CAN_EP_SIZE) #define CAN_DEV_SIZE (8) -#define CAN_DEV_MASK (((1 << CAN_DEV_SIZE) - 1) << (CAN_EP_SIZE + CAN_SEQ_SIZE)) +#define CAN_DEV_MASK (((1UL << CAN_DEV_SIZE) - 1) << (CAN_EP_SIZE + CAN_SEQ_SIZE)) typedef void (*send_callback)(uint32_t arbitration_id, uint8_t *data, uint8_t dlc, bool rtr); typedef bool (*recv_callback)(uint32_t *arbitration_id, uint8_t *data, uint8_t *dlc); @@ -48,7 +48,7 @@ class Node { uint8_t _dlc; uint32_t get_arbitration_id(uint32_t cmd_id) { - return ((this->can_node_id << (CAN_EP_SIZE + CAN_SEQ_SIZE)) & CAN_DEV_MASK) | (cmd_id & CAN_EP_MASK); + return ((((uint32_t)this->can_node_id) << (CAN_EP_SIZE + CAN_SEQ_SIZE)) & CAN_DEV_MASK) | (cmd_id & CAN_EP_MASK); } void send(uint32_t cmd_id, uint8_t *data, uint8_t data_size, bool rtr) { diff --git a/include/tinymovr/motor.hpp b/include/tinymovr/motor.hpp index ce298bf..8b35308 100644 --- a/include/tinymovr/motor.hpp +++ b/include/tinymovr/motor.hpp @@ -24,10 +24,6 @@ class Motor_ : Node void set_pole_pairs(uint8_t value); uint8_t get_type(void); void set_type(uint8_t value); - float get_offset(void); - void set_offset(float value); - int8_t get_direction(void); - void set_direction(int8_t value); bool get_calibrated(void); float get_I_cal(void); void set_I_cal(float value); diff --git a/include/tinymovr/onboard.hpp b/include/tinymovr/onboard.hpp new file mode 100644 index 0000000..fd1fcae --- /dev/null +++ b/include/tinymovr/onboard.hpp @@ -0,0 +1,22 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#pragma once + +#include + +class Onboard_ : Node +{ + public: + + Onboard_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value): + Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; + bool get_calibrated(void); + uint8_t get_errors(void); + +}; diff --git a/include/tinymovr/position_sensor.hpp b/include/tinymovr/position_sensor.hpp new file mode 100644 index 0000000..a86f827 --- /dev/null +++ b/include/tinymovr/position_sensor.hpp @@ -0,0 +1,27 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#pragma once + +#include + +class Position_sensor_ : Node +{ + public: + + Position_sensor_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value): + Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; + uint8_t get_connection(void); + void set_connection(uint8_t value); + float get_bandwidth(void); + void set_bandwidth(float value); + int32_t get_raw_angle(void); + float get_position_estimate(void); + float get_velocity_estimate(void); + +}; diff --git a/include/tinymovr/scheduler.hpp b/include/tinymovr/scheduler.hpp index 2fe9bbc..faf6299 100644 --- a/include/tinymovr/scheduler.hpp +++ b/include/tinymovr/scheduler.hpp @@ -16,6 +16,7 @@ class Scheduler_ : Node Scheduler_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value): Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; - uint8_t get_errors(void); + uint32_t get_load(void); + uint8_t get_warnings(void); }; diff --git a/include/tinymovr/select.hpp b/include/tinymovr/select.hpp new file mode 100644 index 0000000..015c857 --- /dev/null +++ b/include/tinymovr/select.hpp @@ -0,0 +1,26 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#pragma once + +#include +#include +#include + +class Select_ : Node +{ + public: + + Select_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value): + Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) + , position_sensor(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) + , commutation_sensor(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; + Position_sensor_ position_sensor; + Commutation_sensor_ commutation_sensor; + +}; diff --git a/include/tinymovr/sensors.hpp b/include/tinymovr/sensors.hpp new file mode 100644 index 0000000..0c3d5ad --- /dev/null +++ b/include/tinymovr/sensors.hpp @@ -0,0 +1,29 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#pragma once + +#include +#include +#include +#include + +class Sensors_ : Node +{ + public: + + Sensors_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value): + Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) + , user_frame(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) + , setup(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) + , select(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; + User_frame_ user_frame; + Setup_ setup; + Select_ select; + +}; diff --git a/include/tinymovr/setup.hpp b/include/tinymovr/setup.hpp new file mode 100644 index 0000000..4bd744a --- /dev/null +++ b/include/tinymovr/setup.hpp @@ -0,0 +1,29 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#pragma once + +#include +#include +#include +#include + +class Setup_ : Node +{ + public: + + Setup_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value): + Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) + , onboard(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) + , external_spi(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) + , hall(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; + Onboard_ onboard; + External_spi_ external_spi; + Hall_ hall; + +}; diff --git a/include/tinymovr/tinymovr.hpp b/include/tinymovr/tinymovr.hpp index 400e186..b736b9e 100644 --- a/include/tinymovr/tinymovr.hpp +++ b/include/tinymovr/tinymovr.hpp @@ -13,29 +13,34 @@ #include #include #include -#include +#include #include #include #include -static uint32_t avlos_proto_hash = 4118115615; +static uint32_t avlos_proto_hash = 3704894695; enum errors_flags { ERRORS_NONE = 0, - ERRORS_UNDERVOLTAGE = (1 << 0), - ERRORS_DRIVER_FAULT = (1 << 1), - ERRORS_CHARGE_PUMP_FAULT_STAT = (1 << 2), - ERRORS_CHARGE_PUMP_FAULT = (1 << 3), - ERRORS_DRV10_DISABLE = (1 << 4), - ERRORS_DRV32_DISABLE = (1 << 5), - ERRORS_DRV54_DISABLE = (1 << 6) + ERRORS_UNDERVOLTAGE = (1 << 0) }; -enum scheduler_errors_flags +enum warnings_flags { - SCHEDULER_ERRORS_NONE = 0, - SCHEDULER_ERRORS_CONTROL_BLOCK_REENTERED = (1 << 0) + WARNINGS_NONE = 0, + WARNINGS_DRIVER_FAULT = (1 << 0), + WARNINGS_CHARGE_PUMP_FAULT_STAT = (1 << 1), + WARNINGS_CHARGE_PUMP_FAULT = (1 << 2), + WARNINGS_DRV10_DISABLE = (1 << 3), + WARNINGS_DRV32_DISABLE = (1 << 4), + WARNINGS_DRV54_DISABLE = (1 << 5) +}; + +enum scheduler_warnings_flags +{ + SCHEDULER_WARNINGS_NONE = 0, + SCHEDULER_WARNINGS_CONTROL_BLOCK_REENTERED = (1 << 0) }; enum controller_warnings_flags @@ -60,11 +65,25 @@ enum motor_errors_flags MOTOR_ERRORS_INVALID_POLE_PAIRS = (1 << 2) }; -enum encoder_errors_flags +enum sensors_setup_onboard_errors_flags +{ + SENSORS_SETUP_ONBOARD_ERRORS_NONE = 0, + SENSORS_SETUP_ONBOARD_ERRORS_CALIBRATION_FAILED = (1 << 0), + SENSORS_SETUP_ONBOARD_ERRORS_READING_UNSTABLE = (1 << 1) +}; + +enum sensors_setup_external_spi_errors_flags { - ENCODER_ERRORS_NONE = 0, - ENCODER_ERRORS_CALIBRATION_FAILED = (1 << 0), - ENCODER_ERRORS_READING_UNSTABLE = (1 << 1) + SENSORS_SETUP_EXTERNAL_SPI_ERRORS_NONE = 0, + SENSORS_SETUP_EXTERNAL_SPI_ERRORS_CALIBRATION_FAILED = (1 << 0), + SENSORS_SETUP_EXTERNAL_SPI_ERRORS_READING_UNSTABLE = (1 << 1) +}; + +enum sensors_setup_hall_errors_flags +{ + SENSORS_SETUP_HALL_ERRORS_NONE = 0, + SENSORS_SETUP_HALL_ERRORS_CALIBRATION_FAILED = (1 << 0), + SENSORS_SETUP_HALL_ERRORS_READING_UNSTABLE = (1 << 1) }; enum traj_planner_errors_flags @@ -80,16 +99,56 @@ enum homing_warnings_flags HOMING_WARNINGS_HOMING_TIMEOUT = (1 << 0) }; +enum controller_state_options +{ + CONTROLLER_STATE_IDLE = 0, + CONTROLLER_STATE_CALIBRATE = 1, + CONTROLLER_STATE_CL_CONTROL = 2 +}; + +enum controller_mode_options +{ + CONTROLLER_MODE_CURRENT = 0, + CONTROLLER_MODE_VELOCITY = 1, + CONTROLLER_MODE_POSITION = 2, + CONTROLLER_MODE_TRAJECTORY = 3, + CONTROLLER_MODE_HOMING = 4 +}; + enum motor_type_options { MOTOR_TYPE_HIGH_CURRENT = 0, MOTOR_TYPE_GIMBAL = 1 }; -enum encoder_type_options +enum sensors_setup_external_spi_type_options +{ + SENSORS_SETUP_EXTERNAL_SPI_TYPE_MA7XX = 0, + SENSORS_SETUP_EXTERNAL_SPI_TYPE_AS5047 = 1, + SENSORS_SETUP_EXTERNAL_SPI_TYPE_AMT22 = 2 +}; + +enum sensors_setup_external_spi_rate_options +{ + SENSORS_SETUP_EXTERNAL_SPI_RATE_1_5Mbps = 0, + SENSORS_SETUP_EXTERNAL_SPI_RATE_3Mbps = 1, + SENSORS_SETUP_EXTERNAL_SPI_RATE_6Mbps = 2, + SENSORS_SETUP_EXTERNAL_SPI_RATE_8Mbps = 3, + SENSORS_SETUP_EXTERNAL_SPI_RATE_12Mbps = 4 +}; + +enum sensors_select_position_sensor_connection_options +{ + SENSORS_SELECT_POSITION_SENSOR_CONNECTION_ONBOARD = 0, + SENSORS_SELECT_POSITION_SENSOR_CONNECTION_EXTERNAL_SPI = 1, + SENSORS_SELECT_POSITION_SENSOR_CONNECTION_HALL = 2 +}; + +enum sensors_select_commutation_sensor_connection_options { - ENCODER_TYPE_INTERNAL = 0, - ENCODER_TYPE_HALL = 1 + SENSORS_SELECT_COMMUTATION_SENSOR_CONNECTION_ONBOARD = 0, + SENSORS_SELECT_COMMUTATION_SENSOR_CONNECTION_EXTERNAL_SPI = 1, + SENSORS_SELECT_COMMUTATION_SENSOR_CONNECTION_HALL = 2 }; class Tinymovr : Node @@ -102,7 +161,7 @@ class Tinymovr : Node , controller(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) , comms(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) , motor(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) - , encoder(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) + , sensors(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) , traj_planner(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) , homing(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) , watchdog(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; @@ -116,15 +175,17 @@ class Tinymovr : Node float get_temp(void); bool get_calibrated(void); uint8_t get_errors(void); + uint8_t get_warnings(void); void save_config(); void erase_config(); void reset(); void enter_dfu(); + uint32_t get_config_size(void); Scheduler_ scheduler; Controller_ controller; Comms_ comms; Motor_ motor; - Encoder_ encoder; + Sensors_ sensors; Traj_planner_ traj_planner; Homing_ homing; Watchdog_ watchdog; diff --git a/include/tinymovr/user_frame.hpp b/include/tinymovr/user_frame.hpp new file mode 100644 index 0000000..b918afb --- /dev/null +++ b/include/tinymovr/user_frame.hpp @@ -0,0 +1,26 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#pragma once + +#include + +class User_frame_ : Node +{ + public: + + User_frame_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value): + Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; + float get_position_estimate(void); + float get_velocity_estimate(void); + float get_offset(void); + void set_offset(float value); + float get_multiplier(void); + void set_multiplier(float value); + +}; diff --git a/src/tinymovr/can.cpp b/src/tinymovr/can.cpp index 33b1da0..e6fd312 100644 --- a/src/tinymovr/can.cpp +++ b/src/tinymovr/can.cpp @@ -11,8 +11,8 @@ uint32_t Can_::get_rate(void) { uint32_t value = 0; - this->send(42, this->_data, 0, true); - if (this->recv(42, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(45, this->_data, 0, true); + if (this->recv(45, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -22,14 +22,14 @@ uint32_t Can_::get_rate(void) void Can_::set_rate(uint32_t value) { write_le(value, this->_data); - this->send(42, this->_data, sizeof(uint32_t), false); + this->send(45, this->_data, sizeof(uint32_t), false); } uint32_t Can_::get_id(void) { uint32_t value = 0; - this->send(43, this->_data, 0, true); - if (this->recv(43, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(46, this->_data, 0, true); + if (this->recv(46, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -39,7 +39,24 @@ uint32_t Can_::get_id(void) void Can_::set_id(uint32_t value) { write_le(value, this->_data); - this->send(43, this->_data, sizeof(uint32_t), false); + this->send(46, this->_data, sizeof(uint32_t), false); +} + +bool Can_::get_heartbeat(void) +{ + bool value = 0; + this->send(47, this->_data, 0, true); + if (this->recv(47, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +void Can_::set_heartbeat(bool value) +{ + write_le(value, this->_data); + this->send(47, this->_data, sizeof(bool), false); } diff --git a/src/tinymovr/commutation_sensor.cpp b/src/tinymovr/commutation_sensor.cpp new file mode 100644 index 0000000..32df1ea --- /dev/null +++ b/src/tinymovr/commutation_sensor.cpp @@ -0,0 +1,79 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#include + +uint8_t Commutation_sensor_::get_connection(void) +{ + uint8_t value = 0; + this->send(72, this->_data, 0, true); + if (this->recv(72, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +void Commutation_sensor_::set_connection(uint8_t value) +{ + write_le(value, this->_data); + this->send(72, this->_data, sizeof(uint8_t), false); +} + +float Commutation_sensor_::get_bandwidth(void) +{ + float value = 0; + this->send(73, this->_data, 0, true); + if (this->recv(73, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +void Commutation_sensor_::set_bandwidth(float value) +{ + write_le(value, this->_data); + this->send(73, this->_data, sizeof(float), false); +} + +int32_t Commutation_sensor_::get_raw_angle(void) +{ + int32_t value = 0; + this->send(74, this->_data, 0, true); + if (this->recv(74, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +float Commutation_sensor_::get_position_estimate(void) +{ + float value = 0; + this->send(75, this->_data, 0, true); + if (this->recv(75, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +float Commutation_sensor_::get_velocity_estimate(void) +{ + float value = 0; + this->send(76, this->_data, 0, true); + if (this->recv(76, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + + + diff --git a/src/tinymovr/controller.cpp b/src/tinymovr/controller.cpp index 9bd6447..d45dd38 100644 --- a/src/tinymovr/controller.cpp +++ b/src/tinymovr/controller.cpp @@ -11,8 +11,8 @@ uint8_t Controller_::get_state(void) { uint8_t value = 0; - this->send(15, this->_data, 0, true); - if (this->recv(15, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(18, this->_data, 0, true); + if (this->recv(18, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -22,14 +22,14 @@ uint8_t Controller_::get_state(void) void Controller_::set_state(uint8_t value) { write_le(value, this->_data); - this->send(15, this->_data, sizeof(uint8_t), false); + this->send(18, this->_data, sizeof(uint8_t), false); } uint8_t Controller_::get_mode(void) { uint8_t value = 0; - this->send(16, this->_data, 0, true); - if (this->recv(16, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(19, this->_data, 0, true); + if (this->recv(19, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -39,14 +39,14 @@ uint8_t Controller_::get_mode(void) void Controller_::set_mode(uint8_t value) { write_le(value, this->_data); - this->send(16, this->_data, sizeof(uint8_t), false); + this->send(19, this->_data, sizeof(uint8_t), false); } uint8_t Controller_::get_warnings(void) { uint8_t value = 0; - this->send(17, this->_data, 0, true); - if (this->recv(17, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(20, this->_data, 0, true); + if (this->recv(20, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -56,8 +56,8 @@ uint8_t Controller_::get_warnings(void) uint8_t Controller_::get_errors(void) { uint8_t value = 0; - this->send(18, this->_data, 0, true); - if (this->recv(18, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(21, this->_data, 0, true); + if (this->recv(21, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -67,27 +67,27 @@ uint8_t Controller_::get_errors(void) void Controller_::calibrate() { - this->send(36, this->_data, 0, true); + this->send(39, this->_data, 0, true); } void Controller_::idle() { - this->send(37, this->_data, 0, true); + this->send(40, this->_data, 0, true); } void Controller_::position_mode() { - this->send(38, this->_data, 0, true); + this->send(41, this->_data, 0, true); } void Controller_::velocity_mode() { - this->send(39, this->_data, 0, true); + this->send(42, this->_data, 0, true); } void Controller_::current_mode() { - this->send(40, this->_data, 0, true); + this->send(43, this->_data, 0, true); } float Controller_::set_pos_vel_setpoints(float pos_setpoint, float vel_setpoint) @@ -98,7 +98,7 @@ float Controller_::set_pos_vel_setpoints(float pos_setpoint, float vel_setpoint) write_le(vel_setpoint, this->_data + data_len); data_len += sizeof(vel_setpoint); - this->send(41, this->_data, data_len, false); + this->send(44, this->_data, data_len, false); float value = 0; this->send(17, this->_data, 0, true); if (this->recv(17, this->_data, &(this->_dlc), this->delay_us_value)) diff --git a/src/tinymovr/current.cpp b/src/tinymovr/current.cpp index c7873f8..ee0d769 100644 --- a/src/tinymovr/current.cpp +++ b/src/tinymovr/current.cpp @@ -11,8 +11,8 @@ float Current_::get_Iq_setpoint(void) { float value = 0; - this->send(27, this->_data, 0, true); - if (this->recv(27, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(30, this->_data, 0, true); + if (this->recv(30, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -22,14 +22,14 @@ float Current_::get_Iq_setpoint(void) void Current_::set_Iq_setpoint(float value) { write_le(value, this->_data); - this->send(27, this->_data, sizeof(float), false); + this->send(30, this->_data, sizeof(float), false); } float Current_::get_Id_setpoint(void) { float value = 0; - this->send(28, this->_data, 0, true); - if (this->recv(28, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(31, this->_data, 0, true); + if (this->recv(31, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -39,8 +39,8 @@ float Current_::get_Id_setpoint(void) float Current_::get_Iq_limit(void) { float value = 0; - this->send(29, this->_data, 0, true); - if (this->recv(29, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(32, this->_data, 0, true); + if (this->recv(32, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -50,14 +50,14 @@ float Current_::get_Iq_limit(void) void Current_::set_Iq_limit(float value) { write_le(value, this->_data); - this->send(29, this->_data, sizeof(float), false); + this->send(32, this->_data, sizeof(float), false); } float Current_::get_Iq_estimate(void) { float value = 0; - this->send(30, this->_data, 0, true); - if (this->recv(30, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(33, this->_data, 0, true); + if (this->recv(33, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -67,8 +67,8 @@ float Current_::get_Iq_estimate(void) float Current_::get_bandwidth(void) { float value = 0; - this->send(31, this->_data, 0, true); - if (this->recv(31, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(34, this->_data, 0, true); + if (this->recv(34, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -78,14 +78,14 @@ float Current_::get_bandwidth(void) void Current_::set_bandwidth(float value) { write_le(value, this->_data); - this->send(31, this->_data, sizeof(float), false); + this->send(34, this->_data, sizeof(float), false); } float Current_::get_Iq_p_gain(void) { float value = 0; - this->send(32, this->_data, 0, true); - if (this->recv(32, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(35, this->_data, 0, true); + if (this->recv(35, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -95,8 +95,8 @@ float Current_::get_Iq_p_gain(void) float Current_::get_max_Ibus_regen(void) { float value = 0; - this->send(33, this->_data, 0, true); - if (this->recv(33, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(36, this->_data, 0, true); + if (this->recv(36, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -106,14 +106,14 @@ float Current_::get_max_Ibus_regen(void) void Current_::set_max_Ibus_regen(float value) { write_le(value, this->_data); - this->send(33, this->_data, sizeof(float), false); + this->send(36, this->_data, sizeof(float), false); } float Current_::get_max_Ibrake(void) { float value = 0; - this->send(34, this->_data, 0, true); - if (this->recv(34, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(37, this->_data, 0, true); + if (this->recv(37, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -123,7 +123,7 @@ float Current_::get_max_Ibrake(void) void Current_::set_max_Ibrake(float value) { write_le(value, this->_data); - this->send(34, this->_data, sizeof(float), false); + this->send(37, this->_data, sizeof(float), false); } diff --git a/src/tinymovr/external_spi.cpp b/src/tinymovr/external_spi.cpp new file mode 100644 index 0000000..55bb381 --- /dev/null +++ b/src/tinymovr/external_spi.cpp @@ -0,0 +1,68 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#include + +uint8_t External_spi_::get_type(void) +{ + uint8_t value = 0; + this->send(61, this->_data, 0, true); + if (this->recv(61, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +void External_spi_::set_type(uint8_t value) +{ + write_le(value, this->_data); + this->send(61, this->_data, sizeof(uint8_t), false); +} + +uint8_t External_spi_::get_rate(void) +{ + uint8_t value = 0; + this->send(62, this->_data, 0, true); + if (this->recv(62, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +void External_spi_::set_rate(uint8_t value) +{ + write_le(value, this->_data); + this->send(62, this->_data, sizeof(uint8_t), false); +} + +bool External_spi_::get_calibrated(void) +{ + bool value = 0; + this->send(63, this->_data, 0, true); + if (this->recv(63, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +uint8_t External_spi_::get_errors(void) +{ + uint8_t value = 0; + this->send(64, this->_data, 0, true); + if (this->recv(64, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + + + diff --git a/src/tinymovr/hall.cpp b/src/tinymovr/hall.cpp new file mode 100644 index 0000000..9a9ce6d --- /dev/null +++ b/src/tinymovr/hall.cpp @@ -0,0 +1,34 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#include + +bool Hall_::get_calibrated(void) +{ + bool value = 0; + this->send(65, this->_data, 0, true); + if (this->recv(65, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +uint8_t Hall_::get_errors(void) +{ + uint8_t value = 0; + this->send(66, this->_data, 0, true); + if (this->recv(66, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + + + diff --git a/src/tinymovr/homing.cpp b/src/tinymovr/homing.cpp index 697b292..15e444c 100644 --- a/src/tinymovr/homing.cpp +++ b/src/tinymovr/homing.cpp @@ -11,8 +11,8 @@ float Homing_::get_velocity(void) { float value = 0; - this->send(68, this->_data, 0, true); - if (this->recv(68, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(86, this->_data, 0, true); + if (this->recv(86, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -22,14 +22,14 @@ float Homing_::get_velocity(void) void Homing_::set_velocity(float value) { write_le(value, this->_data); - this->send(68, this->_data, sizeof(float), false); + this->send(86, this->_data, sizeof(float), false); } float Homing_::get_max_homing_t(void) { float value = 0; - this->send(69, this->_data, 0, true); - if (this->recv(69, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(87, this->_data, 0, true); + if (this->recv(87, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -39,14 +39,14 @@ float Homing_::get_max_homing_t(void) void Homing_::set_max_homing_t(float value) { write_le(value, this->_data); - this->send(69, this->_data, sizeof(float), false); + this->send(87, this->_data, sizeof(float), false); } float Homing_::get_retract_dist(void) { float value = 0; - this->send(70, this->_data, 0, true); - if (this->recv(70, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(88, this->_data, 0, true); + if (this->recv(88, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -56,14 +56,14 @@ float Homing_::get_retract_dist(void) void Homing_::set_retract_dist(float value) { write_le(value, this->_data); - this->send(70, this->_data, sizeof(float), false); + this->send(88, this->_data, sizeof(float), false); } uint8_t Homing_::get_warnings(void) { uint8_t value = 0; - this->send(71, this->_data, 0, true); - if (this->recv(71, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(89, this->_data, 0, true); + if (this->recv(89, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -73,7 +73,7 @@ uint8_t Homing_::get_warnings(void) void Homing_::home() { - this->send(75, this->_data, 0, true); + this->send(93, this->_data, 0, true); } diff --git a/src/tinymovr/motor.cpp b/src/tinymovr/motor.cpp index 2eb11bc..d746f5c 100644 --- a/src/tinymovr/motor.cpp +++ b/src/tinymovr/motor.cpp @@ -11,8 +11,8 @@ float Motor_::get_R(void) { float value = 0; - this->send(44, this->_data, 0, true); - if (this->recv(44, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(48, this->_data, 0, true); + if (this->recv(48, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -22,14 +22,14 @@ float Motor_::get_R(void) void Motor_::set_R(float value) { write_le(value, this->_data); - this->send(44, this->_data, sizeof(float), false); + this->send(48, this->_data, sizeof(float), false); } float Motor_::get_L(void) { float value = 0; - this->send(45, this->_data, 0, true); - if (this->recv(45, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(49, this->_data, 0, true); + if (this->recv(49, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -39,14 +39,14 @@ float Motor_::get_L(void) void Motor_::set_L(float value) { write_le(value, this->_data); - this->send(45, this->_data, sizeof(float), false); + this->send(49, this->_data, sizeof(float), false); } uint8_t Motor_::get_pole_pairs(void) { uint8_t value = 0; - this->send(46, this->_data, 0, true); - if (this->recv(46, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(50, this->_data, 0, true); + if (this->recv(50, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -56,14 +56,14 @@ uint8_t Motor_::get_pole_pairs(void) void Motor_::set_pole_pairs(uint8_t value) { write_le(value, this->_data); - this->send(46, this->_data, sizeof(uint8_t), false); + this->send(50, this->_data, sizeof(uint8_t), false); } uint8_t Motor_::get_type(void) { uint8_t value = 0; - this->send(47, this->_data, 0, true); - if (this->recv(47, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(51, this->_data, 0, true); + if (this->recv(51, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -73,48 +73,14 @@ uint8_t Motor_::get_type(void) void Motor_::set_type(uint8_t value) { write_le(value, this->_data); - this->send(47, this->_data, sizeof(uint8_t), false); -} - -float Motor_::get_offset(void) -{ - float value = 0; - this->send(48, this->_data, 0, true); - if (this->recv(48, this->_data, &(this->_dlc), this->delay_us_value)) - { - read_le(&value, this->_data); - } - return value; -} - -void Motor_::set_offset(float value) -{ - write_le(value, this->_data); - this->send(48, this->_data, sizeof(float), false); -} - -int8_t Motor_::get_direction(void) -{ - int8_t value = 0; - this->send(49, this->_data, 0, true); - if (this->recv(49, this->_data, &(this->_dlc), this->delay_us_value)) - { - read_le(&value, this->_data); - } - return value; -} - -void Motor_::set_direction(int8_t value) -{ - write_le(value, this->_data); - this->send(49, this->_data, sizeof(int8_t), false); + this->send(51, this->_data, sizeof(uint8_t), false); } bool Motor_::get_calibrated(void) { bool value = 0; - this->send(50, this->_data, 0, true); - if (this->recv(50, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(52, this->_data, 0, true); + if (this->recv(52, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -124,8 +90,8 @@ bool Motor_::get_calibrated(void) float Motor_::get_I_cal(void) { float value = 0; - this->send(51, this->_data, 0, true); - if (this->recv(51, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(53, this->_data, 0, true); + if (this->recv(53, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -135,14 +101,14 @@ float Motor_::get_I_cal(void) void Motor_::set_I_cal(float value) { write_le(value, this->_data); - this->send(51, this->_data, sizeof(float), false); + this->send(53, this->_data, sizeof(float), false); } uint8_t Motor_::get_errors(void) { uint8_t value = 0; - this->send(52, this->_data, 0, true); - if (this->recv(52, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(54, this->_data, 0, true); + if (this->recv(54, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } diff --git a/src/tinymovr/onboard.cpp b/src/tinymovr/onboard.cpp new file mode 100644 index 0000000..6d5f545 --- /dev/null +++ b/src/tinymovr/onboard.cpp @@ -0,0 +1,34 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#include + +bool Onboard_::get_calibrated(void) +{ + bool value = 0; + this->send(59, this->_data, 0, true); + if (this->recv(59, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +uint8_t Onboard_::get_errors(void) +{ + uint8_t value = 0; + this->send(60, this->_data, 0, true); + if (this->recv(60, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + + + diff --git a/src/tinymovr/position.cpp b/src/tinymovr/position.cpp index 6848657..3ced45e 100644 --- a/src/tinymovr/position.cpp +++ b/src/tinymovr/position.cpp @@ -11,8 +11,8 @@ float Position_::get_setpoint(void) { float value = 0; - this->send(19, this->_data, 0, true); - if (this->recv(19, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(22, this->_data, 0, true); + if (this->recv(22, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -22,14 +22,14 @@ float Position_::get_setpoint(void) void Position_::set_setpoint(float value) { write_le(value, this->_data); - this->send(19, this->_data, sizeof(float), false); + this->send(22, this->_data, sizeof(float), false); } float Position_::get_p_gain(void) { float value = 0; - this->send(20, this->_data, 0, true); - if (this->recv(20, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(23, this->_data, 0, true); + if (this->recv(23, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -39,7 +39,7 @@ float Position_::get_p_gain(void) void Position_::set_p_gain(float value) { write_le(value, this->_data); - this->send(20, this->_data, sizeof(float), false); + this->send(23, this->_data, sizeof(float), false); } diff --git a/src/tinymovr/position_sensor.cpp b/src/tinymovr/position_sensor.cpp new file mode 100644 index 0000000..bc20b1f --- /dev/null +++ b/src/tinymovr/position_sensor.cpp @@ -0,0 +1,79 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#include + +uint8_t Position_sensor_::get_connection(void) +{ + uint8_t value = 0; + this->send(67, this->_data, 0, true); + if (this->recv(67, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +void Position_sensor_::set_connection(uint8_t value) +{ + write_le(value, this->_data); + this->send(67, this->_data, sizeof(uint8_t), false); +} + +float Position_sensor_::get_bandwidth(void) +{ + float value = 0; + this->send(68, this->_data, 0, true); + if (this->recv(68, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +void Position_sensor_::set_bandwidth(float value) +{ + write_le(value, this->_data); + this->send(68, this->_data, sizeof(float), false); +} + +int32_t Position_sensor_::get_raw_angle(void) +{ + int32_t value = 0; + this->send(69, this->_data, 0, true); + if (this->recv(69, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +float Position_sensor_::get_position_estimate(void) +{ + float value = 0; + this->send(70, this->_data, 0, true); + if (this->recv(70, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +float Position_sensor_::get_velocity_estimate(void) +{ + float value = 0; + this->send(71, this->_data, 0, true); + if (this->recv(71, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + + + diff --git a/src/tinymovr/scheduler.cpp b/src/tinymovr/scheduler.cpp index de9bd30..a02f68a 100644 --- a/src/tinymovr/scheduler.cpp +++ b/src/tinymovr/scheduler.cpp @@ -8,11 +8,22 @@ #include -uint8_t Scheduler_::get_errors(void) +uint32_t Scheduler_::get_load(void) +{ + uint32_t value = 0; + this->send(16, this->_data, 0, true); + if (this->recv(16, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +uint8_t Scheduler_::get_warnings(void) { uint8_t value = 0; - this->send(14, this->_data, 0, true); - if (this->recv(14, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(17, this->_data, 0, true); + if (this->recv(17, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } diff --git a/src/tinymovr/select.cpp b/src/tinymovr/select.cpp new file mode 100644 index 0000000..4be081f --- /dev/null +++ b/src/tinymovr/select.cpp @@ -0,0 +1,12 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#include + + + diff --git a/src/tinymovr/sensors.cpp b/src/tinymovr/sensors.cpp new file mode 100644 index 0000000..58113ac --- /dev/null +++ b/src/tinymovr/sensors.cpp @@ -0,0 +1,12 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#include + + + diff --git a/src/tinymovr/setup.cpp b/src/tinymovr/setup.cpp new file mode 100644 index 0000000..779c548 --- /dev/null +++ b/src/tinymovr/setup.cpp @@ -0,0 +1,12 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#include + + + diff --git a/src/tinymovr/stall_detect.cpp b/src/tinymovr/stall_detect.cpp index b3a5d93..b5dcbf3 100644 --- a/src/tinymovr/stall_detect.cpp +++ b/src/tinymovr/stall_detect.cpp @@ -11,8 +11,8 @@ float Stall_detect_::get_velocity(void) { float value = 0; - this->send(72, this->_data, 0, true); - if (this->recv(72, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(90, this->_data, 0, true); + if (this->recv(90, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -22,14 +22,14 @@ float Stall_detect_::get_velocity(void) void Stall_detect_::set_velocity(float value) { write_le(value, this->_data); - this->send(72, this->_data, sizeof(float), false); + this->send(90, this->_data, sizeof(float), false); } float Stall_detect_::get_delta_pos(void) { float value = 0; - this->send(73, this->_data, 0, true); - if (this->recv(73, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(91, this->_data, 0, true); + if (this->recv(91, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -39,14 +39,14 @@ float Stall_detect_::get_delta_pos(void) void Stall_detect_::set_delta_pos(float value) { write_le(value, this->_data); - this->send(73, this->_data, sizeof(float), false); + this->send(91, this->_data, sizeof(float), false); } float Stall_detect_::get_t(void) { float value = 0; - this->send(74, this->_data, 0, true); - if (this->recv(74, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(92, this->_data, 0, true); + if (this->recv(92, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -56,7 +56,7 @@ float Stall_detect_::get_t(void) void Stall_detect_::set_t(float value) { write_le(value, this->_data); - this->send(74, this->_data, sizeof(float), false); + this->send(92, this->_data, sizeof(float), false); } diff --git a/src/tinymovr/tinymovr.cpp b/src/tinymovr/tinymovr.cpp index f4e977b..df88ebf 100644 --- a/src/tinymovr/tinymovr.cpp +++ b/src/tinymovr/tinymovr.cpp @@ -105,24 +105,44 @@ uint8_t Tinymovr::get_errors(void) } return value; } +uint8_t Tinymovr::get_warnings(void) +{ + uint8_t value = 0; + this->send(10, this->_data, 0, true); + if (this->recv(10, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} void Tinymovr::save_config() { - this->send(10, this->_data, 0, true); + this->send(11, this->_data, 0, true); } void Tinymovr::erase_config() { - this->send(11, this->_data, 0, true); + this->send(12, this->_data, 0, true); } void Tinymovr::reset() { - this->send(12, this->_data, 0, true); + this->send(13, this->_data, 0, true); } void Tinymovr::enter_dfu() { - this->send(13, this->_data, 0, true); + this->send(14, this->_data, 0, true); +} +uint32_t Tinymovr::get_config_size(void) +{ + uint32_t value = 0; + this->send(15, this->_data, 0, true); + if (this->recv(15, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; } diff --git a/src/tinymovr/traj_planner.cpp b/src/tinymovr/traj_planner.cpp index 058ec08..45fd78a 100644 --- a/src/tinymovr/traj_planner.cpp +++ b/src/tinymovr/traj_planner.cpp @@ -11,8 +11,8 @@ float Traj_planner_::get_max_accel(void) { float value = 0; - this->send(59, this->_data, 0, true); - if (this->recv(59, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(77, this->_data, 0, true); + if (this->recv(77, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -22,14 +22,14 @@ float Traj_planner_::get_max_accel(void) void Traj_planner_::set_max_accel(float value) { write_le(value, this->_data); - this->send(59, this->_data, sizeof(float), false); + this->send(77, this->_data, sizeof(float), false); } float Traj_planner_::get_max_decel(void) { float value = 0; - this->send(60, this->_data, 0, true); - if (this->recv(60, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(78, this->_data, 0, true); + if (this->recv(78, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -39,14 +39,14 @@ float Traj_planner_::get_max_decel(void) void Traj_planner_::set_max_decel(float value) { write_le(value, this->_data); - this->send(60, this->_data, sizeof(float), false); + this->send(78, this->_data, sizeof(float), false); } float Traj_planner_::get_max_vel(void) { float value = 0; - this->send(61, this->_data, 0, true); - if (this->recv(61, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(79, this->_data, 0, true); + if (this->recv(79, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -56,14 +56,14 @@ float Traj_planner_::get_max_vel(void) void Traj_planner_::set_max_vel(float value) { write_le(value, this->_data); - this->send(61, this->_data, sizeof(float), false); + this->send(79, this->_data, sizeof(float), false); } float Traj_planner_::get_t_accel(void) { float value = 0; - this->send(62, this->_data, 0, true); - if (this->recv(62, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(80, this->_data, 0, true); + if (this->recv(80, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -73,14 +73,14 @@ float Traj_planner_::get_t_accel(void) void Traj_planner_::set_t_accel(float value) { write_le(value, this->_data); - this->send(62, this->_data, sizeof(float), false); + this->send(80, this->_data, sizeof(float), false); } float Traj_planner_::get_t_decel(void) { float value = 0; - this->send(63, this->_data, 0, true); - if (this->recv(63, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(81, this->_data, 0, true); + if (this->recv(81, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -90,14 +90,14 @@ float Traj_planner_::get_t_decel(void) void Traj_planner_::set_t_decel(float value) { write_le(value, this->_data); - this->send(63, this->_data, sizeof(float), false); + this->send(81, this->_data, sizeof(float), false); } float Traj_planner_::get_t_total(void) { float value = 0; - this->send(64, this->_data, 0, true); - if (this->recv(64, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(82, this->_data, 0, true); + if (this->recv(82, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -107,7 +107,7 @@ float Traj_planner_::get_t_total(void) void Traj_planner_::set_t_total(float value) { write_le(value, this->_data); - this->send(64, this->_data, sizeof(float), false); + this->send(82, this->_data, sizeof(float), false); } @@ -117,7 +117,7 @@ void Traj_planner_::move_to(float pos_setpoint) write_le(pos_setpoint, this->_data + data_len); data_len += sizeof(pos_setpoint); - this->send(65, this->_data, data_len, false); + this->send(83, this->_data, data_len, false); } void Traj_planner_::move_to_tlimit(float pos_setpoint) @@ -126,13 +126,13 @@ void Traj_planner_::move_to_tlimit(float pos_setpoint) write_le(pos_setpoint, this->_data + data_len); data_len += sizeof(pos_setpoint); - this->send(66, this->_data, data_len, false); + this->send(84, this->_data, data_len, false); } uint8_t Traj_planner_::get_errors(void) { uint8_t value = 0; - this->send(67, this->_data, 0, true); - if (this->recv(67, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(85, this->_data, 0, true); + if (this->recv(85, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } diff --git a/src/tinymovr/user_frame.cpp b/src/tinymovr/user_frame.cpp new file mode 100644 index 0000000..e3c7f61 --- /dev/null +++ b/src/tinymovr/user_frame.cpp @@ -0,0 +1,68 @@ +/* +* This file was automatically generated using Avlos. +* https://github.com/tinymovr/avlos +* +* Any changes to this file will be overwritten when +* content is regenerated. +*/ + +#include + +float User_frame_::get_position_estimate(void) +{ + float value = 0; + this->send(55, this->_data, 0, true); + if (this->recv(55, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +float User_frame_::get_velocity_estimate(void) +{ + float value = 0; + this->send(56, this->_data, 0, true); + if (this->recv(56, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +float User_frame_::get_offset(void) +{ + float value = 0; + this->send(57, this->_data, 0, true); + if (this->recv(57, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +void User_frame_::set_offset(float value) +{ + write_le(value, this->_data); + this->send(57, this->_data, sizeof(float), false); +} + +float User_frame_::get_multiplier(void) +{ + float value = 0; + this->send(58, this->_data, 0, true); + if (this->recv(58, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} + +void User_frame_::set_multiplier(float value) +{ + write_le(value, this->_data); + this->send(58, this->_data, sizeof(float), false); +} + + + diff --git a/src/tinymovr/velocity.cpp b/src/tinymovr/velocity.cpp index 318995e..a0bccb8 100644 --- a/src/tinymovr/velocity.cpp +++ b/src/tinymovr/velocity.cpp @@ -11,8 +11,8 @@ float Velocity_::get_setpoint(void) { float value = 0; - this->send(21, this->_data, 0, true); - if (this->recv(21, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(24, this->_data, 0, true); + if (this->recv(24, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -22,14 +22,14 @@ float Velocity_::get_setpoint(void) void Velocity_::set_setpoint(float value) { write_le(value, this->_data); - this->send(21, this->_data, sizeof(float), false); + this->send(24, this->_data, sizeof(float), false); } float Velocity_::get_limit(void) { float value = 0; - this->send(22, this->_data, 0, true); - if (this->recv(22, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(25, this->_data, 0, true); + if (this->recv(25, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -39,14 +39,14 @@ float Velocity_::get_limit(void) void Velocity_::set_limit(float value) { write_le(value, this->_data); - this->send(22, this->_data, sizeof(float), false); + this->send(25, this->_data, sizeof(float), false); } float Velocity_::get_p_gain(void) { float value = 0; - this->send(23, this->_data, 0, true); - if (this->recv(23, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(26, this->_data, 0, true); + if (this->recv(26, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -56,14 +56,14 @@ float Velocity_::get_p_gain(void) void Velocity_::set_p_gain(float value) { write_le(value, this->_data); - this->send(23, this->_data, sizeof(float), false); + this->send(26, this->_data, sizeof(float), false); } float Velocity_::get_i_gain(void) { float value = 0; - this->send(24, this->_data, 0, true); - if (this->recv(24, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(27, this->_data, 0, true); + if (this->recv(27, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -73,14 +73,14 @@ float Velocity_::get_i_gain(void) void Velocity_::set_i_gain(float value) { write_le(value, this->_data); - this->send(24, this->_data, sizeof(float), false); + this->send(27, this->_data, sizeof(float), false); } float Velocity_::get_deadband(void) { float value = 0; - this->send(25, this->_data, 0, true); - if (this->recv(25, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(28, this->_data, 0, true); + if (this->recv(28, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -90,14 +90,14 @@ float Velocity_::get_deadband(void) void Velocity_::set_deadband(float value) { write_le(value, this->_data); - this->send(25, this->_data, sizeof(float), false); + this->send(28, this->_data, sizeof(float), false); } float Velocity_::get_increment(void) { float value = 0; - this->send(26, this->_data, 0, true); - if (this->recv(26, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(29, this->_data, 0, true); + if (this->recv(29, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -107,7 +107,7 @@ float Velocity_::get_increment(void) void Velocity_::set_increment(float value) { write_le(value, this->_data); - this->send(26, this->_data, sizeof(float), false); + this->send(29, this->_data, sizeof(float), false); } diff --git a/src/tinymovr/voltage.cpp b/src/tinymovr/voltage.cpp index 754640b..c41fe38 100644 --- a/src/tinymovr/voltage.cpp +++ b/src/tinymovr/voltage.cpp @@ -11,8 +11,8 @@ float Voltage_::get_Vq_setpoint(void) { float value = 0; - this->send(35, this->_data, 0, true); - if (this->recv(35, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(38, this->_data, 0, true); + if (this->recv(38, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } diff --git a/src/tinymovr/watchdog.cpp b/src/tinymovr/watchdog.cpp index 35548b2..13ce273 100644 --- a/src/tinymovr/watchdog.cpp +++ b/src/tinymovr/watchdog.cpp @@ -11,8 +11,8 @@ bool Watchdog_::get_enabled(void) { bool value = 0; - this->send(76, this->_data, 0, true); - if (this->recv(76, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(94, this->_data, 0, true); + if (this->recv(94, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -22,14 +22,14 @@ bool Watchdog_::get_enabled(void) void Watchdog_::set_enabled(bool value) { write_le(value, this->_data); - this->send(76, this->_data, sizeof(bool), false); + this->send(94, this->_data, sizeof(bool), false); } bool Watchdog_::get_triggered(void) { bool value = 0; - this->send(77, this->_data, 0, true); - if (this->recv(77, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(95, this->_data, 0, true); + if (this->recv(95, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -39,8 +39,8 @@ bool Watchdog_::get_triggered(void) float Watchdog_::get_timeout(void) { float value = 0; - this->send(78, this->_data, 0, true); - if (this->recv(78, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(96, this->_data, 0, true); + if (this->recv(96, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -50,7 +50,7 @@ float Watchdog_::get_timeout(void) void Watchdog_::set_timeout(float value) { write_le(value, this->_data); - this->send(78, this->_data, sizeof(float), false); + this->send(96, this->_data, sizeof(float), false); } From 16047591e07ccbec393bc9218fc13d36d7b9ae12 Mon Sep 17 00:00:00 2001 From: Yannis Chatzikonstantinou Date: Wed, 24 Apr 2024 01:52:10 +0300 Subject: [PATCH 2/5] add gitignore --- .gitignore | 1 + 1 file changed, 1 insertion(+) create mode 100644 .gitignore diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..7a7e85b --- /dev/null +++ b/.gitignore @@ -0,0 +1 @@ +include/tinymovr/.DS_Store From 3c1ef04927825b60405ba003a74140b62c26c321 Mon Sep 17 00:00:00 2001 From: Yannis Chatzikonstantinou Date: Wed, 24 Apr 2024 01:52:29 +0300 Subject: [PATCH 3/5] update for spec 2.0.x --- CMakeLists.txt | 12 ++++- include/tinymovr/encoder.hpp | 28 ----------- src/tinymovr/encoder.cpp | 90 ------------------------------------ src/tm_joint_iface.cpp | 8 ++-- 4 files changed, 16 insertions(+), 122 deletions(-) delete mode 100644 include/tinymovr/encoder.hpp delete mode 100644 src/tinymovr/encoder.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 0d3fcb9..d076add 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -130,14 +130,24 @@ include_directories( set(TINYMOVR_SOURCES src/tinymovr/can.cpp src/tinymovr/comms.cpp + src/tinymovr/commutation_sensor.cpp src/tinymovr/controller.cpp src/tinymovr/current.cpp - src/tinymovr/encoder.cpp + src/tinymovr/external_spi.cpp + src/tinymovr/hall.cpp + src/tinymovr/homing.cpp src/tinymovr/motor.cpp + src/tinymovr/onboard.cpp + src/tinymovr/position_sensor.cpp src/tinymovr/position.cpp src/tinymovr/scheduler.cpp + src/tinymovr/select.cpp + src/tinymovr/sensors.cpp + src/tinymovr/setup.cpp + src/tinymovr/stall_detect.cpp src/tinymovr/tinymovr.cpp src/tinymovr/traj_planner.cpp + src/tinymovr/user_frame.cpp src/tinymovr/velocity.cpp src/tinymovr/voltage.cpp src/tinymovr/watchdog.cpp diff --git a/include/tinymovr/encoder.hpp b/include/tinymovr/encoder.hpp deleted file mode 100644 index d05d2e4..0000000 --- a/include/tinymovr/encoder.hpp +++ /dev/null @@ -1,28 +0,0 @@ -/* -* This file was automatically generated using Avlos. -* https://github.com/tinymovr/avlos -* -* Any changes to this file will be overwritten when -* content is regenerated. -*/ - -#pragma once - -#include - -class Encoder_ : Node -{ - public: - - Encoder_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value): - Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; - float get_position_estimate(void); - float get_velocity_estimate(void); - uint8_t get_type(void); - void set_type(uint8_t value); - float get_bandwidth(void); - void set_bandwidth(float value); - bool get_calibrated(void); - uint8_t get_errors(void); - -}; diff --git a/src/tinymovr/encoder.cpp b/src/tinymovr/encoder.cpp deleted file mode 100644 index 9622c48..0000000 --- a/src/tinymovr/encoder.cpp +++ /dev/null @@ -1,90 +0,0 @@ -/* -* This file was automatically generated using Avlos. -* https://github.com/tinymovr/avlos -* -* Any changes to this file will be overwritten when -* content is regenerated. -*/ - -#include - -float Encoder_::get_position_estimate(void) -{ - float value = 0; - this->send(53, this->_data, 0, true); - if (this->recv(53, this->_data, &(this->_dlc), this->delay_us_value)) - { - read_le(&value, this->_data); - } - return value; -} - -float Encoder_::get_velocity_estimate(void) -{ - float value = 0; - this->send(54, this->_data, 0, true); - if (this->recv(54, this->_data, &(this->_dlc), this->delay_us_value)) - { - read_le(&value, this->_data); - } - return value; -} - -uint8_t Encoder_::get_type(void) -{ - uint8_t value = 0; - this->send(55, this->_data, 0, true); - if (this->recv(55, this->_data, &(this->_dlc), this->delay_us_value)) - { - read_le(&value, this->_data); - } - return value; -} - -void Encoder_::set_type(uint8_t value) -{ - write_le(value, this->_data); - this->send(55, this->_data, sizeof(uint8_t), false); -} - -float Encoder_::get_bandwidth(void) -{ - float value = 0; - this->send(56, this->_data, 0, true); - if (this->recv(56, this->_data, &(this->_dlc), this->delay_us_value)) - { - read_le(&value, this->_data); - } - return value; -} - -void Encoder_::set_bandwidth(float value) -{ - write_le(value, this->_data); - this->send(56, this->_data, sizeof(float), false); -} - -bool Encoder_::get_calibrated(void) -{ - bool value = 0; - this->send(57, this->_data, 0, true); - if (this->recv(57, this->_data, &(this->_dlc), this->delay_us_value)) - { - read_le(&value, this->_data); - } - return value; -} - -uint8_t Encoder_::get_errors(void) -{ - uint8_t value = 0; - this->send(58, this->_data, 0, true); - if (this->recv(58, this->_data, &(this->_dlc), this->delay_us_value)) - { - read_le(&value, this->_data); - } - return value; -} - - - diff --git a/src/tm_joint_iface.cpp b/src/tm_joint_iface.cpp index ed0d5de..8a9e770 100644 --- a/src/tm_joint_iface.cpp +++ b/src/tm_joint_iface.cpp @@ -239,7 +239,9 @@ bool TinymovrJoint::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh) ROS_DEBUG("Asserting calibrated"); for (int i=0; i Date: Wed, 24 Apr 2024 01:56:57 +0300 Subject: [PATCH 4/5] add ignore --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 7a7e85b..2f9ab53 100644 --- a/.gitignore +++ b/.gitignore @@ -1 +1,2 @@ include/tinymovr/.DS_Store +src/tinymovr/.DS_Store From 52faccbe4fd8020ec1e28f94a6e6c22d2a8bdfa5 Mon Sep 17 00:00:00 2001 From: Yannis Chatzikonstantinou Date: Wed, 24 Apr 2024 02:08:20 +0300 Subject: [PATCH 5/5] fix calls to calibrated --- src/tm_joint_iface.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/tm_joint_iface.cpp b/src/tm_joint_iface.cpp index 8a9e770..98ad9be 100644 --- a/src/tm_joint_iface.cpp +++ b/src/tm_joint_iface.cpp @@ -239,9 +239,7 @@ bool TinymovrJoint::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh) ROS_DEBUG("Asserting calibrated"); for (int i=0; i