Skip to content

Commit

Permalink
Merge pull request #13 from tinymovr/2_0_x
Browse files Browse the repository at this point in the history
Tinymovr version 2.0.x
  • Loading branch information
yconst committed Apr 22, 2024
2 parents 1d53af8 + 5eaacff commit 4b4ef1b
Show file tree
Hide file tree
Showing 39 changed files with 923 additions and 216 deletions.
8 changes: 4 additions & 4 deletions examples/arduino_mkr_wifi_1010/arduino_mkr_wifi_1010.ino
Original file line number Diff line number Diff line change
Expand Up @@ -159,14 +159,14 @@ void loop()
else if (receivedChar == '<')
{
Serial.println("Received L turn command");
float pos_estimate = tinymovr.encoder.get_position_estimate();
float pos_estimate = tinymovr.sensors.user_frame.get_position_estimate();
Serial.println(pos_estimate);
tinymovr.controller.position.set_setpoint(pos_estimate - 8192.0f);
}
else if (receivedChar == '>')
{
Serial.println("Received R turn command");
float pos_estimate = tinymovr.encoder.get_position_estimate();
float pos_estimate = tinymovr.sensors.user_frame.get_position_estimate();
Serial.println(pos_estimate);
tinymovr.controller.position.set_setpoint(pos_estimate + 8192.0f);
}
Expand All @@ -183,9 +183,9 @@ void loop()
Serial.print(tinymovr.controller.get_mode());
Serial.print("\n");
Serial.print("Position estimate: ");
Serial.print(tinymovr.encoder.get_position_estimate());
Serial.print(tinymovr.sensors.user_frame.get_position_estimate());
Serial.print(", Velocity estimate: ");
Serial.print(tinymovr.encoder.get_velocity_estimate());
Serial.print(tinymovr.sensors.user_frame.get_velocity_estimate());
Serial.print("\n");
Serial.print("Iq estimate: ");
Serial.print(tinymovr.controller.current.get_Iq_estimate());
Expand Down
8 changes: 4 additions & 4 deletions examples/esp32_mcp2551/esp32_mcp2551.ino
Original file line number Diff line number Diff line change
Expand Up @@ -159,14 +159,14 @@ void loop()
else if (receivedChar == '<')
{
Serial.println("Received L turn command");
float pos_estimate = tinymovr.encoder.get_position_estimate();
float pos_estimate = tinymovr.sensors.user_frame.get_position_estimate();
Serial.println(pos_estimate);
tinymovr.controller.position.set_setpoint(pos_estimate - 8192.0f);
}
else if (receivedChar == '>')
{
Serial.println("Received R turn command");
float pos_estimate = tinymovr.encoder.get_position_estimate();
float pos_estimate = tinymovr.sensors.user_frame.get_position_estimate();
Serial.println(pos_estimate);
tinymovr.controller.position.set_setpoint(pos_estimate + 8192.0f);
}
Expand All @@ -183,9 +183,9 @@ void loop()
Serial.print(tinymovr.controller.get_mode());
Serial.print("\n");
Serial.print("Position estimate: ");
Serial.print(tinymovr.encoder.get_position_estimate());
Serial.print(tinymovr.sensors.user_frame.get_position_estimate());
Serial.print(", Velocity estimate: ");
Serial.print(tinymovr.encoder.get_velocity_estimate());
Serial.print(tinymovr.sensors.user_frame.get_velocity_estimate());
Serial.print("\n");
Serial.print("Iq estimate: ");
Serial.print(tinymovr.controller.current.get_Iq_estimate());
Expand Down
4 changes: 2 additions & 2 deletions readme.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@ The library is hardware-agnostic so you can use any CAN 2.0-capable adapter. The

The library is object oriented and the main Tinymovr object is what you use to establish communication with the board. Endpoints that are read only implement `get_{endpoint_name}` style getters. Endpoints that are writeable implement both `get_{endpoint_name}` and `set_{endpoint_name}`.

float pos_estimate = tinymovr.encoder.get_position_estimate();
float vel_estimate = tinymovr.encoder.get_velocity_estimate();
float pos_estimate = tinymovr.sensors.user_frame.get_position_estimate();
float vel_estimate = tinymovr.sensors.user_frame.get_velocity_estimate();
tinymovr.controller.position.set_setpoint(10000);

Functions are called with their name and required parameters.
Expand Down
29 changes: 23 additions & 6 deletions src/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand All @@ -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);
}
Expand All @@ -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);
}


Expand Down
2 changes: 2 additions & 0 deletions src/can.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);

};
79 changes: 79 additions & 0 deletions src/commutation_sensor.cpp
Original file line number Diff line number Diff line change
@@ -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 <commutation_sensor.hpp>

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;
}



27 changes: 27 additions & 0 deletions src/commutation_sensor.hpp
Original file line number Diff line number Diff line change
@@ -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 <helpers.hpp>

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);

};
32 changes: 16 additions & 16 deletions src/controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand All @@ -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);
}
Expand All @@ -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);
}
Expand All @@ -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);
}
Expand All @@ -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)
Expand All @@ -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))
Expand Down
Loading

0 comments on commit 4b4ef1b

Please sign in to comment.