-
Notifications
You must be signed in to change notification settings - Fork 0
/
vesc.h
79 lines (57 loc) · 1.38 KB
/
vesc.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
// VESC communication library
// Ian Glen <ian@ianglen.me>
#ifndef VESC_H
#define VESC_H
#include <Arduino.h>
#include "vesc_datatypes.h"
// Telemetry data returned by VESC
typedef struct
{
uint8_t id;
float tempFET;
float tempMotor;
float avgMotorCurrent;
float avgInputCurrent;
float avgId;
float avgIq;
float dutyCycle;
float rpm;
float inputVoltage;
float ampHours;
float ampHoursCharged;
float wattHours;
float wattHoursCharged;
int32_t tachometer;
int32_t tachometerAbs;
vesc_fault_code_t fault;
float position;
float ntc1;
float ntc2;
float ntc3;
float avgVd;
float avgVq;
} vesc_values_t;
extern vesc_values_t vesc_values[2];
// register a vesc
size_t vesc_register(uint8_t id);
// vesc initialization
void vesc_init(void);
// request new values from a vesc
void vesc_update_values(uint8_t id);
// set motor duty
void vesc_set_duty(uint8_t id, float duty);
// set motor current
void vesc_set_current(uint8_t id, float current);
// set motor brake current
void vesc_set_current_brake(uint8_t id, float current);
// set motor rpm
void vesc_set_rpm(uint8_t id, float rpm);
// set motor position
void vesc_set_position(uint8_t id, float position);
// reboot vesc
void vesc_reboot(uint8_t id);
// send alive packet
void vesc_keep_alive(uint8_t id);
// get a description of a VESC fault code
//String getFaultMsg(uint8_t id, vesc_fault_code_t code);
#endif // VESC_H