Skip to content

Commit 63dd89e

Browse files
committed
Adds a preliminary support for zephyr boards
1 parent 2832d5c commit 63dd89e

File tree

4 files changed

+201
-1
lines changed

4 files changed

+201
-1
lines changed

.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
.vscode/settings.json

src/Servo.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -79,8 +79,10 @@
7979
#include "xmc/ServoTimers.h"
8080
#elif defined(ARDUINO_ARCH_ESP32)
8181
#include "esp32/ServoTimers.h"
82+
#elif defined(ARDUINO_ARCH_ZEPHYR)
83+
#include "zephyr/ServoTimers.h"
8284
#else
83-
#error "This library only supports boards with an AVR, SAM, SAMD, NRF52, STM32F4, Renesas, XMC or ESP32 processor."
85+
#error "This library only supports boards with an AVR, SAM, SAMD, NRF52, STM32F4, Renesas, XMC, ESP32 or Zephyr core."
8486
#endif
8587

8688
#define Servo_VERSION 2 // software version of this library

src/zephyr/Servo.cpp

Lines changed: 191 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,191 @@
1+
#if defined(ARDUINO_ARCH_ZEPHYR)
2+
3+
#include <zephyr/kernel.h>
4+
#include <zephyr/drivers/gpio.h>
5+
#include <zephyr/device.h>
6+
#include <zephyr/drivers/counter.h>
7+
8+
#include <Arduino.h>
9+
#include <Servo.h>
10+
11+
12+
typedef struct {
13+
uint8_t pin;
14+
uint32_t position_tick;
15+
uint32_t timer_index;
16+
uint32_t min;
17+
uint32_t max;
18+
} servoTimer_t;
19+
20+
class ServoTimerHandler{
21+
22+
inline static uint32_t timer_servo;
23+
inline static uint32_t servo_timing_period;
24+
bool timer_is_started;
25+
26+
inline static servoTimer_t * servos[MAX_ZEPHYR_SERVOS] = {nullptr};
27+
uint8_t servoCount;
28+
29+
public:
30+
ServoTimerHandler(){
31+
timer_is_started = false;
32+
timer_servo = 0;
33+
servoCount = 0;
34+
}
35+
36+
int initTimer(){
37+
if (!timer_is_started){
38+
const struct device *const counter_dev = DEVICE_DT_GET(TIMER);
39+
counter_start(counter_dev);
40+
struct counter_top_cfg top_cfg;
41+
top_cfg.ticks = counter_us_to_ticks(counter_dev, servo_timer_base_us_tick);
42+
top_cfg.callback = this->servo_timer_update;
43+
top_cfg.user_data = &top_cfg;
44+
top_cfg.flags = 0;
45+
46+
int err = counter_set_top_value(counter_dev, &top_cfg);
47+
if (err){
48+
return 0;
49+
}
50+
else{
51+
timer_is_started = true;
52+
return 1;
53+
}
54+
}
55+
return -1;
56+
}
57+
58+
static void servo_timer_update(const struct device *counter_dev, void *user_data){
59+
for (uint8_t i = 0; i < MAX_ZEPHYR_SERVOS; i++){
60+
if (servos[i]!=nullptr){
61+
if (timer_servo>servos[i]->position_tick){
62+
digitalWrite(servos[i]->pin, LOW);
63+
}
64+
else{
65+
digitalWrite(servos[i]->pin, HIGH);
66+
}
67+
}
68+
}
69+
if (timer_servo>servo_timer_end_tick){
70+
timer_servo = 0;
71+
}
72+
timer_servo++;
73+
}
74+
75+
int addServo(servoTimer_t * s){
76+
if (servoCount<MAX_ZEPHYR_SERVOS){
77+
for (uint8_t i = 0; i<MAX_ZEPHYR_SERVOS; i++){
78+
if (servos[i]!=nullptr && servos[i]->pin==s->pin){
79+
return i;
80+
}
81+
}
82+
for (uint8_t i = 0; i<MAX_ZEPHYR_SERVOS; i++){
83+
if (servos[i]==nullptr){
84+
servos[i]=s;
85+
servoCount++;
86+
return i;
87+
}
88+
}
89+
}
90+
else{
91+
return -1;
92+
}
93+
return -2;
94+
}
95+
96+
int removeServo(int index){
97+
if (index<MAX_ZEPHYR_SERVOS){
98+
delete servos[index];
99+
servos[index]=nullptr;
100+
servoCount--;
101+
return index;
102+
}
103+
else{
104+
return -1;
105+
}
106+
}
107+
108+
void writeMicroseconds(int index, int value){
109+
if (servos[index]!=nullptr){
110+
servos[index]->position_tick = value/servo_timer_base_us_tick;
111+
}
112+
}
113+
114+
uint32_t getMin(int index){
115+
if (servos[index]!=nullptr){
116+
return servos[index]->min;
117+
}
118+
return MIN_PULSE_WIDTH;
119+
}
120+
121+
uint32_t getMax(int index){
122+
if (servos[index]!=nullptr){
123+
return servos[index]->max;
124+
}
125+
return MAX_PULSE_WIDTH;
126+
}
127+
128+
uint32_t readMicroseconds(int index){
129+
if (servos[index]!=nullptr){
130+
return servos[index]->position_tick*servo_timer_base_us_tick;
131+
}
132+
return 0;
133+
}
134+
};
135+
136+
static ServoTimerHandler servo_handle;
137+
138+
139+
Servo::Servo(){
140+
servo_handle.initTimer();
141+
servoIndex = 255;
142+
}
143+
144+
uint8_t Servo::attach(int pin){
145+
return this->attach(pin, MIN_PULSE_WIDTH , MAX_PULSE_WIDTH );
146+
}
147+
148+
uint8_t Servo::attach(int pin, int min, int max){
149+
pinMode(pin, OUTPUT);
150+
servoTimer_t * tmp_servo = new servoTimer_t();
151+
tmp_servo->pin = pin;
152+
tmp_servo->min = min;
153+
tmp_servo->max = max;
154+
servoIndex = servo_handle.addServo(tmp_servo);
155+
this->min = servo_handle.getMin(servoIndex)/4;
156+
this->max = servo_handle.getMax(servoIndex)/4;
157+
return 0;
158+
}
159+
160+
161+
void Servo::detach(){
162+
servo_handle.removeServo(servoIndex);
163+
servoIndex = 255;
164+
}
165+
166+
void Servo::write(int value){
167+
servo_handle.writeMicroseconds(servoIndex, map(value, 0, 180, servo_handle.getMin(servoIndex), servo_handle.getMax(servoIndex)));
168+
}
169+
170+
void Servo::writeMicroseconds(int value){
171+
servo_handle.writeMicroseconds(servoIndex, value);
172+
}
173+
174+
int Servo::read(){
175+
return map(servo_handle.readMicroseconds(servoIndex), servo_handle.getMin(servoIndex), servo_handle.getMax(servoIndex), 0, 180);
176+
}
177+
178+
int Servo::readMicroseconds(){
179+
return servo_handle.readMicroseconds(servoIndex);
180+
}
181+
182+
bool Servo::attached(){
183+
if (servoIndex==255){
184+
return false;
185+
}
186+
else{
187+
return true;
188+
}
189+
}
190+
191+
#endif

src/zephyr/ServoTimers.h

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
#define MAX_ZEPHYR_SERVOS 16
2+
3+
#define TIMER DT_NODELABEL(counter_servo)
4+
5+
const uint32_t servo_timer_base_us_tick = 4;
6+
const uint32_t servo_timer_end_tick = 20000/servo_timer_base_us_tick;

0 commit comments

Comments
 (0)