From ed248fab84c038c212b87ec1b87c3b75655454fb Mon Sep 17 00:00:00 2001 From: Yannis Chatzikonstantinou Date: Sun, 10 Sep 2023 01:52:23 +0300 Subject: [PATCH] version 1.6.0 --- src/can.cpp | 12 +++++----- src/controller.cpp | 32 +++++++++++++------------- src/current.cpp | 42 +++++++++++++++++----------------- src/encoder.cpp | 28 +++++++++++------------ src/homing.cpp | 24 ++++++++++---------- src/motor.cpp | 50 ++++++++++++++++++++-------------------- src/position.cpp | 12 +++++----- src/scheduler.cpp | 26 ++------------------- src/scheduler.hpp | 2 -- src/stall_detect.cpp | 18 +++++++-------- src/tinymovr.cpp | 54 ++++++++++++++++++++++++++++++++------------ src/tinymovr.hpp | 24 ++++++++++++++++++-- src/traj_planner.cpp | 44 ++++++++++++++++++------------------ src/velocity.cpp | 36 ++++++++++++++--------------- src/voltage.cpp | 4 ++-- src/watchdog.cpp | 16 ++++++------- 16 files changed, 222 insertions(+), 202 deletions(-) diff --git a/src/can.cpp b/src/can.cpp index 29761c0..33b1da0 100644 --- a/src/can.cpp +++ b/src/can.cpp @@ -11,8 +11,8 @@ uint32_t Can_::get_rate(void) { uint32_t value = 0; - this->send(41, this->_data, 0, true); - if (this->recv(41, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(42, this->_data, 0, true); + if (this->recv(42, 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(41, this->_data, sizeof(uint32_t), false); + this->send(42, this->_data, sizeof(uint32_t), false); } uint32_t Can_::get_id(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(43, this->_data, 0, true); + if (this->recv(43, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -39,7 +39,7 @@ uint32_t Can_::get_id(void) void Can_::set_id(uint32_t value) { write_le(value, this->_data); - this->send(42, this->_data, sizeof(uint32_t), false); + this->send(43, this->_data, sizeof(uint32_t), false); } diff --git a/src/controller.cpp b/src/controller.cpp index 779b750..9bd6447 100644 --- a/src/controller.cpp +++ b/src/controller.cpp @@ -11,8 +11,8 @@ uint8_t Controller_::get_state(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(15, this->_data, 0, true); + if (this->recv(15, 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(14, this->_data, sizeof(uint8_t), false); + this->send(15, this->_data, sizeof(uint8_t), false); } uint8_t Controller_::get_mode(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(16, this->_data, 0, true); + if (this->recv(16, 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(15, this->_data, sizeof(uint8_t), false); + this->send(16, this->_data, sizeof(uint8_t), false); } uint8_t Controller_::get_warnings(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(17, this->_data, 0, true); + if (this->recv(17, 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(17, this->_data, 0, true); - if (this->recv(17, 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); } @@ -67,27 +67,27 @@ uint8_t Controller_::get_errors(void) void Controller_::calibrate() { - this->send(35, this->_data, 0, true); + this->send(36, this->_data, 0, true); } void Controller_::idle() { - this->send(36, this->_data, 0, true); + this->send(37, this->_data, 0, true); } void Controller_::position_mode() { - this->send(37, this->_data, 0, true); + this->send(38, this->_data, 0, true); } void Controller_::velocity_mode() { - this->send(38, this->_data, 0, true); + this->send(39, this->_data, 0, true); } void Controller_::current_mode() { - this->send(39, this->_data, 0, true); + this->send(40, 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(40, this->_data, data_len, false); + this->send(41, 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/current.cpp b/src/current.cpp index 19257d9..c7873f8 100644 --- a/src/current.cpp +++ b/src/current.cpp @@ -11,8 +11,8 @@ float Current_::get_Iq_setpoint(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(27, this->_data, 0, true); + if (this->recv(27, 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(26, this->_data, sizeof(float), false); + this->send(27, this->_data, sizeof(float), false); } float Current_::get_Id_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(28, this->_data, 0, true); + if (this->recv(28, 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(28, this->_data, 0, true); - if (this->recv(28, 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); } @@ -50,14 +50,14 @@ float Current_::get_Iq_limit(void) void Current_::set_Iq_limit(float value) { write_le(value, this->_data); - this->send(28, this->_data, sizeof(float), false); + this->send(29, this->_data, sizeof(float), false); } float Current_::get_Iq_estimate(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(30, this->_data, 0, true); + if (this->recv(30, 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(30, this->_data, 0, true); - if (this->recv(30, 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); } @@ -78,14 +78,14 @@ float Current_::get_bandwidth(void) void Current_::set_bandwidth(float value) { write_le(value, this->_data); - this->send(30, this->_data, sizeof(float), false); + this->send(31, this->_data, sizeof(float), false); } float Current_::get_Iq_p_gain(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(32, this->_data, 0, true); + if (this->recv(32, 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(32, this->_data, 0, true); - if (this->recv(32, 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); } @@ -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(32, this->_data, sizeof(float), false); + this->send(33, this->_data, sizeof(float), false); } float Current_::get_max_Ibrake(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(34, this->_data, 0, true); + if (this->recv(34, 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(33, this->_data, sizeof(float), false); + this->send(34, this->_data, sizeof(float), false); } diff --git a/src/encoder.cpp b/src/encoder.cpp index d969497..9622c48 100644 --- a/src/encoder.cpp +++ b/src/encoder.cpp @@ -11,8 +11,8 @@ float Encoder_::get_position_estimate(void) { float value = 0; - this->send(52, this->_data, 0, true); - if (this->recv(52, 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); } @@ -22,8 +22,8 @@ float Encoder_::get_position_estimate(void) float Encoder_::get_velocity_estimate(void) { float value = 0; - this->send(53, this->_data, 0, true); - if (this->recv(53, 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); } @@ -33,8 +33,8 @@ float Encoder_::get_velocity_estimate(void) uint8_t Encoder_::get_type(void) { uint8_t value = 0; - this->send(54, this->_data, 0, true); - if (this->recv(54, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(55, this->_data, 0, true); + if (this->recv(55, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -44,14 +44,14 @@ uint8_t Encoder_::get_type(void) void Encoder_::set_type(uint8_t value) { write_le(value, this->_data); - this->send(54, this->_data, sizeof(uint8_t), false); + this->send(55, this->_data, sizeof(uint8_t), false); } float Encoder_::get_bandwidth(void) { float value = 0; - this->send(55, this->_data, 0, true); - if (this->recv(55, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(56, this->_data, 0, true); + if (this->recv(56, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -61,14 +61,14 @@ float Encoder_::get_bandwidth(void) void Encoder_::set_bandwidth(float value) { write_le(value, this->_data); - this->send(55, this->_data, sizeof(float), false); + this->send(56, this->_data, sizeof(float), false); } bool Encoder_::get_calibrated(void) { bool value = 0; - this->send(56, this->_data, 0, true); - if (this->recv(56, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(57, this->_data, 0, true); + if (this->recv(57, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -78,8 +78,8 @@ bool Encoder_::get_calibrated(void) uint8_t Encoder_::get_errors(void) { uint8_t value = 0; - this->send(57, this->_data, 0, true); - if (this->recv(57, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(58, this->_data, 0, true); + if (this->recv(58, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } diff --git a/src/homing.cpp b/src/homing.cpp index 7a245aa..697b292 100644 --- a/src/homing.cpp +++ b/src/homing.cpp @@ -11,8 +11,8 @@ float Homing_::get_velocity(void) { float value = 0; - this->send(67, this->_data, 0, true); - if (this->recv(67, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(68, this->_data, 0, true); + if (this->recv(68, 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(67, this->_data, sizeof(float), false); + this->send(68, this->_data, sizeof(float), false); } float Homing_::get_max_homing_t(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(69, this->_data, 0, true); + if (this->recv(69, 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(68, this->_data, sizeof(float), false); + this->send(69, this->_data, sizeof(float), false); } float Homing_::get_retract_dist(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(70, this->_data, 0, true); + if (this->recv(70, 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(69, this->_data, sizeof(float), false); + this->send(70, this->_data, sizeof(float), false); } uint8_t Homing_::get_warnings(void) { uint8_t value = 0; - this->send(70, this->_data, 0, true); - if (this->recv(70, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(71, this->_data, 0, true); + if (this->recv(71, 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(74, this->_data, 0, true); + this->send(75, this->_data, 0, true); } diff --git a/src/motor.cpp b/src/motor.cpp index 31d58d4..2eb11bc 100644 --- a/src/motor.cpp +++ b/src/motor.cpp @@ -11,8 +11,8 @@ float Motor_::get_R(void) { float value = 0; - this->send(43, this->_data, 0, true); - if (this->recv(43, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(44, this->_data, 0, true); + if (this->recv(44, 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(43, this->_data, sizeof(float), false); + this->send(44, this->_data, sizeof(float), false); } float Motor_::get_L(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(45, this->_data, 0, true); + if (this->recv(45, 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(44, this->_data, sizeof(float), false); + this->send(45, this->_data, sizeof(float), false); } uint8_t Motor_::get_pole_pairs(void) { uint8_t value = 0; - this->send(45, this->_data, 0, true); - if (this->recv(45, 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); } @@ -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(45, this->_data, sizeof(uint8_t), false); + this->send(46, this->_data, sizeof(uint8_t), false); } uint8_t Motor_::get_type(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(47, this->_data, 0, true); + if (this->recv(47, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } @@ -73,14 +73,14 @@ uint8_t Motor_::get_type(void) void Motor_::set_type(uint8_t value) { write_le(value, this->_data); - this->send(46, this->_data, sizeof(uint8_t), false); + this->send(47, this->_data, sizeof(uint8_t), false); } float Motor_::get_offset(void) { float value = 0; - this->send(47, this->_data, 0, true); - if (this->recv(47, 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); } @@ -90,14 +90,14 @@ float Motor_::get_offset(void) void Motor_::set_offset(float value) { write_le(value, this->_data); - this->send(47, this->_data, sizeof(float), false); + this->send(48, this->_data, sizeof(float), false); } int8_t Motor_::get_direction(void) { int8_t value = 0; - this->send(48, this->_data, 0, true); - if (this->recv(48, 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); } @@ -107,14 +107,14 @@ int8_t Motor_::get_direction(void) void Motor_::set_direction(int8_t value) { write_le(value, this->_data); - this->send(48, this->_data, sizeof(int8_t), false); + this->send(49, this->_data, sizeof(int8_t), false); } bool Motor_::get_calibrated(void) { bool value = 0; - this->send(49, this->_data, 0, true); - if (this->recv(49, 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); } @@ -124,8 +124,8 @@ bool Motor_::get_calibrated(void) float Motor_::get_I_cal(void) { float value = 0; - this->send(50, this->_data, 0, true); - if (this->recv(50, 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); } @@ -135,14 +135,14 @@ float Motor_::get_I_cal(void) void Motor_::set_I_cal(float value) { write_le(value, this->_data); - this->send(50, this->_data, sizeof(float), false); + this->send(51, this->_data, sizeof(float), false); } uint8_t Motor_::get_errors(void) { uint8_t value = 0; - this->send(51, this->_data, 0, true); - if (this->recv(51, 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); } diff --git a/src/position.cpp b/src/position.cpp index 30f8257..6848657 100644 --- a/src/position.cpp +++ b/src/position.cpp @@ -11,8 +11,8 @@ float Position_::get_setpoint(void) { float value = 0; - this->send(18, this->_data, 0, true); - if (this->recv(18, 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); } @@ -22,14 +22,14 @@ float Position_::get_setpoint(void) void Position_::set_setpoint(float value) { write_le(value, this->_data); - this->send(18, this->_data, sizeof(float), false); + this->send(19, this->_data, sizeof(float), false); } float Position_::get_p_gain(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(20, this->_data, 0, true); + if (this->recv(20, 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(19, this->_data, sizeof(float), false); + this->send(20, this->_data, sizeof(float), false); } diff --git a/src/scheduler.cpp b/src/scheduler.cpp index 37c4b5c..de9bd30 100644 --- a/src/scheduler.cpp +++ b/src/scheduler.cpp @@ -8,33 +8,11 @@ #include -uint32_t Scheduler_::get_total(void) -{ - uint32_t value = 0; - this->send(11, this->_data, 0, true); - if (this->recv(11, this->_data, &(this->_dlc), this->delay_us_value)) - { - read_le(&value, this->_data); - } - return value; -} - -uint32_t Scheduler_::get_busy(void) -{ - uint32_t value = 0; - this->send(12, this->_data, 0, true); - if (this->recv(12, this->_data, &(this->_dlc), this->delay_us_value)) - { - read_le(&value, this->_data); - } - return value; -} - uint8_t Scheduler_::get_errors(void) { uint8_t value = 0; - this->send(13, this->_data, 0, true); - if (this->recv(13, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(14, this->_data, 0, true); + if (this->recv(14, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } diff --git a/src/scheduler.hpp b/src/scheduler.hpp index c2a496a..2fe9bbc 100644 --- a/src/scheduler.hpp +++ b/src/scheduler.hpp @@ -16,8 +16,6 @@ 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) {}; - uint32_t get_total(void); - uint32_t get_busy(void); uint8_t get_errors(void); }; diff --git a/src/stall_detect.cpp b/src/stall_detect.cpp index a602173..b3a5d93 100644 --- a/src/stall_detect.cpp +++ b/src/stall_detect.cpp @@ -11,8 +11,8 @@ float Stall_detect_::get_velocity(void) { float value = 0; - this->send(71, this->_data, 0, true); - if (this->recv(71, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(72, this->_data, 0, true); + if (this->recv(72, 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(71, this->_data, sizeof(float), false); + this->send(72, this->_data, sizeof(float), false); } float Stall_detect_::get_delta_pos(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(73, this->_data, 0, true); + if (this->recv(73, 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(72, this->_data, sizeof(float), false); + this->send(73, this->_data, sizeof(float), false); } float Stall_detect_::get_t(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(74, this->_data, 0, true); + if (this->recv(74, 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(73, this->_data, sizeof(float), false); + this->send(74, this->_data, sizeof(float), false); } diff --git a/src/tinymovr.cpp b/src/tinymovr.cpp index 118d7e5..f4e977b 100644 --- a/src/tinymovr.cpp +++ b/src/tinymovr.cpp @@ -26,19 +26,18 @@ uint32_t Tinymovr::get_uid(void) } return value; } -float Tinymovr::get_Vbus(void) +void Tinymovr::get_fw_version(char out_value[]) { - float value = 0; this->send(2, this->_data, 0, true); + this->_dlc = 0; if (this->recv(2, this->_data, &(this->_dlc), this->delay_us_value)) { - read_le(&value, this->_data); + memcpy(out_value, this->_data, this->_dlc); } - return value; } -float Tinymovr::get_Ibus(void) +uint32_t Tinymovr::get_hw_revision(void) { - float value = 0; + uint32_t value = 0; this->send(3, this->_data, 0, true); if (this->recv(3, this->_data, &(this->_dlc), this->delay_us_value)) { @@ -46,7 +45,7 @@ float Tinymovr::get_Ibus(void) } return value; } -float Tinymovr::get_power(void) +float Tinymovr::get_Vbus(void) { float value = 0; this->send(4, this->_data, 0, true); @@ -56,7 +55,7 @@ float Tinymovr::get_power(void) } return value; } -float Tinymovr::get_temp(void) +float Tinymovr::get_Ibus(void) { float value = 0; this->send(5, this->_data, 0, true); @@ -66,9 +65,9 @@ float Tinymovr::get_temp(void) } return value; } -bool Tinymovr::get_calibrated(void) +float Tinymovr::get_power(void) { - bool value = 0; + float value = 0; this->send(6, this->_data, 0, true); if (this->recv(6, this->_data, &(this->_dlc), this->delay_us_value)) { @@ -76,9 +75,9 @@ bool Tinymovr::get_calibrated(void) } return value; } -uint8_t Tinymovr::get_errors(void) +float Tinymovr::get_temp(void) { - uint8_t value = 0; + float value = 0; this->send(7, this->_data, 0, true); if (this->recv(7, this->_data, &(this->_dlc), this->delay_us_value)) { @@ -86,19 +85,44 @@ uint8_t Tinymovr::get_errors(void) } return value; } +bool Tinymovr::get_calibrated(void) +{ + bool value = 0; + this->send(8, this->_data, 0, true); + if (this->recv(8, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} +uint8_t Tinymovr::get_errors(void) +{ + uint8_t value = 0; + this->send(9, this->_data, 0, true); + if (this->recv(9, this->_data, &(this->_dlc), this->delay_us_value)) + { + read_le(&value, this->_data); + } + return value; +} void Tinymovr::save_config() { - this->send(8, this->_data, 0, true); + this->send(10, this->_data, 0, true); } void Tinymovr::erase_config() { - this->send(9, this->_data, 0, true); + this->send(11, this->_data, 0, true); } void Tinymovr::reset() { - this->send(10, this->_data, 0, true); + this->send(12, this->_data, 0, true); +} + +void Tinymovr::enter_dfu() +{ + this->send(13, this->_data, 0, true); } diff --git a/src/tinymovr.hpp b/src/tinymovr.hpp index e67ee03..400e186 100644 --- a/src/tinymovr.hpp +++ b/src/tinymovr.hpp @@ -18,13 +18,18 @@ #include #include -static uint32_t avlos_proto_hash = 3667602695; +static uint32_t avlos_proto_hash = 4118115615; enum errors_flags { ERRORS_NONE = 0, ERRORS_UNDERVOLTAGE = (1 << 0), - ERRORS_DRIVER_FAULT = (1 << 1) + 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) }; enum scheduler_errors_flags @@ -75,6 +80,18 @@ enum homing_warnings_flags HOMING_WARNINGS_HOMING_TIMEOUT = (1 << 0) }; +enum motor_type_options +{ + MOTOR_TYPE_HIGH_CURRENT = 0, + MOTOR_TYPE_GIMBAL = 1 +}; + +enum encoder_type_options +{ + ENCODER_TYPE_INTERNAL = 0, + ENCODER_TYPE_HALL = 1 +}; + class Tinymovr : Node { public: @@ -91,6 +108,8 @@ class Tinymovr : Node , watchdog(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {}; uint32_t get_protocol_hash(void); uint32_t get_uid(void); + void get_fw_version(char out_value[]); + uint32_t get_hw_revision(void); float get_Vbus(void); float get_Ibus(void); float get_power(void); @@ -100,6 +119,7 @@ class Tinymovr : Node void save_config(); void erase_config(); void reset(); + void enter_dfu(); Scheduler_ scheduler; Controller_ controller; Comms_ comms; diff --git a/src/traj_planner.cpp b/src/traj_planner.cpp index 44d06e1..058ec08 100644 --- a/src/traj_planner.cpp +++ b/src/traj_planner.cpp @@ -11,8 +11,8 @@ float Traj_planner_::get_max_accel(void) { float value = 0; - this->send(58, this->_data, 0, true); - if (this->recv(58, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(59, this->_data, 0, true); + if (this->recv(59, 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(58, this->_data, sizeof(float), false); + this->send(59, this->_data, sizeof(float), false); } float Traj_planner_::get_max_decel(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(60, this->_data, 0, true); + if (this->recv(60, 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(59, this->_data, sizeof(float), false); + this->send(60, this->_data, sizeof(float), false); } float Traj_planner_::get_max_vel(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(61, this->_data, 0, true); + if (this->recv(61, 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(60, this->_data, sizeof(float), false); + this->send(61, this->_data, sizeof(float), false); } float Traj_planner_::get_t_accel(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(62, this->_data, 0, true); + if (this->recv(62, 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(61, this->_data, sizeof(float), false); + this->send(62, this->_data, sizeof(float), false); } float Traj_planner_::get_t_decel(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(63, this->_data, 0, true); + if (this->recv(63, 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(62, this->_data, sizeof(float), false); + this->send(63, this->_data, sizeof(float), false); } float Traj_planner_::get_t_total(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(64, this->_data, 0, true); + if (this->recv(64, 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(63, this->_data, sizeof(float), false); + this->send(64, 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(64, this->_data, data_len, false); + this->send(65, 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(65, this->_data, data_len, false); + this->send(66, this->_data, data_len, false); } uint8_t Traj_planner_::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)) + this->send(67, this->_data, 0, true); + if (this->recv(67, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } diff --git a/src/velocity.cpp b/src/velocity.cpp index 56b5480..318995e 100644 --- a/src/velocity.cpp +++ b/src/velocity.cpp @@ -11,8 +11,8 @@ float Velocity_::get_setpoint(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(21, this->_data, 0, true); + if (this->recv(21, 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(20, this->_data, sizeof(float), false); + this->send(21, this->_data, sizeof(float), false); } float Velocity_::get_limit(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(22, this->_data, 0, true); + if (this->recv(22, 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(21, this->_data, sizeof(float), false); + this->send(22, this->_data, sizeof(float), false); } float Velocity_::get_p_gain(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(23, this->_data, 0, true); + if (this->recv(23, 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(22, this->_data, sizeof(float), false); + this->send(23, this->_data, sizeof(float), false); } float Velocity_::get_i_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(24, this->_data, 0, true); + if (this->recv(24, 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(23, this->_data, sizeof(float), false); + this->send(24, this->_data, sizeof(float), false); } float Velocity_::get_deadband(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(25, this->_data, 0, true); + if (this->recv(25, 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(24, this->_data, sizeof(float), false); + this->send(25, this->_data, sizeof(float), false); } float Velocity_::get_increment(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(26, this->_data, 0, true); + if (this->recv(26, 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(25, this->_data, sizeof(float), false); + this->send(26, this->_data, sizeof(float), false); } diff --git a/src/voltage.cpp b/src/voltage.cpp index 83125fe..754640b 100644 --- a/src/voltage.cpp +++ b/src/voltage.cpp @@ -11,8 +11,8 @@ float Voltage_::get_Vq_setpoint(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(35, this->_data, 0, true); + if (this->recv(35, this->_data, &(this->_dlc), this->delay_us_value)) { read_le(&value, this->_data); } diff --git a/src/watchdog.cpp b/src/watchdog.cpp index 9e7401d..35548b2 100644 --- a/src/watchdog.cpp +++ b/src/watchdog.cpp @@ -11,8 +11,8 @@ bool Watchdog_::get_enabled(void) { bool value = 0; - this->send(75, this->_data, 0, true); - if (this->recv(75, this->_data, &(this->_dlc), this->delay_us_value)) + this->send(76, this->_data, 0, true); + if (this->recv(76, 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(75, this->_data, sizeof(bool), false); + this->send(76, this->_data, sizeof(bool), false); } bool Watchdog_::get_triggered(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(77, this->_data, 0, true); + if (this->recv(77, 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(77, this->_data, 0, true); - if (this->recv(77, 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); } @@ -50,7 +50,7 @@ float Watchdog_::get_timeout(void) void Watchdog_::set_timeout(float value) { write_le(value, this->_data); - this->send(77, this->_data, sizeof(float), false); + this->send(78, this->_data, sizeof(float), false); }