Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Support Tinymovr 2.0.0a1 #4

Merged
merged 5 commits into from
Apr 24, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
include/tinymovr/.DS_Store
src/tinymovr/.DS_Store
12 changes: 11 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 2 additions & 0 deletions include/tinymovr/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);

};
27 changes: 27 additions & 0 deletions include/tinymovr/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);

};
26 changes: 26 additions & 0 deletions include/tinymovr/external_spi.hpp
Original file line number Diff line number Diff line change
@@ -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 <helpers.hpp>

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

};
22 changes: 22 additions & 0 deletions include/tinymovr/hall.hpp
Original file line number Diff line number Diff line change
@@ -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 <helpers.hpp>

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

};
8 changes: 4 additions & 4 deletions include/tinymovr/helpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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)
{
Expand Down
4 changes: 0 additions & 4 deletions include/tinymovr/motor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
22 changes: 22 additions & 0 deletions include/tinymovr/onboard.hpp
Original file line number Diff line number Diff line change
@@ -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 <helpers.hpp>

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

};
Original file line number Diff line number Diff line change
Expand Up @@ -10,19 +10,18 @@

#include <helpers.hpp>

class Encoder_ : Node
class Position_sensor_ : 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):
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) {};
float get_position_estimate(void);
float get_velocity_estimate(void);
uint8_t get_type(void);
void set_type(uint8_t value);
uint8_t get_connection(void);
void set_connection(uint8_t value);
float get_bandwidth(void);
void set_bandwidth(float value);
bool get_calibrated(void);
uint8_t get_errors(void);
int32_t get_raw_angle(void);
float get_position_estimate(void);
float get_velocity_estimate(void);

};
3 changes: 2 additions & 1 deletion include/tinymovr/scheduler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);

};
26 changes: 26 additions & 0 deletions include/tinymovr/select.hpp
Original file line number Diff line number Diff line change
@@ -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 <helpers.hpp>
#include <position_sensor.hpp>
#include <commutation_sensor.hpp>

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;

};
29 changes: 29 additions & 0 deletions include/tinymovr/sensors.hpp
Original file line number Diff line number Diff line change
@@ -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 <helpers.hpp>
#include <user_frame.hpp>
#include <setup.hpp>
#include <select.hpp>

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;

};
29 changes: 29 additions & 0 deletions include/tinymovr/setup.hpp
Original file line number Diff line number Diff line change
@@ -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 <helpers.hpp>
#include <onboard.hpp>
#include <external_spi.hpp>
#include <hall.hpp>

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;

};
Loading
Loading