Skip to content

Commit

Permalink
[Drivers]Add some drivers.It need implement in the future.
Browse files Browse the repository at this point in the history
  • Loading branch information
Linjieqiang committed Dec 25, 2017
1 parent e4b169a commit 27f5dd4
Show file tree
Hide file tree
Showing 8 changed files with 90 additions and 82 deletions.
4 changes: 3 additions & 1 deletion make/source.mk
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,16 @@ COMMON_SRC = \
drivers/drv_system.c \
drivers/drv_uart.c \
drivers/drv_watchdog.c \
drivers/multi_timer.c \
drivers/drv_scheduler.c \
drivers/drv_ws2812.c \
motor/motor_adc.c \
motor/motor_comparator.c \
motor/motor_pwm.c \
motor/motor_rtctl.c \
motor/motor_rtctl_test.c \
motor/motor_signal.c \
motor/motor_telemetry.c \
motor/motor_beeper.c \
motor/motor_timer.c

VPATH := $(VPATH):$(SRC_DIR)
Expand Down
126 changes: 63 additions & 63 deletions src/main/drivers/multi_timer.c → src/main/drivers/drv_scheduler.c
Original file line number Diff line number Diff line change
@@ -1,63 +1,63 @@
#include "include.h"

static struct Timer* head_handle = NULL;

static volatile uint32_t _timer_ticks = 0;

void timer_init(struct Timer* handle, void(*timeout_cb)(), uint32_t timeout, uint32_t repeat)
{
// memset(handle, sizeof(struct Timer), 0);
handle->timeout_cb = timeout_cb;
handle->timeout = _timer_ticks + timeout;
handle->repeat = repeat;
}

int timer_start(struct Timer* handle)
{
struct Timer* target = head_handle;
while(target) {
if(target == handle) {
return -1;
}
target = target->next;
}
handle->next = head_handle;
head_handle = handle;

return 0;
}

void timer_stop(struct Timer* handle)
{
struct Timer** curr;

for(curr = &head_handle; *curr; ) {
struct Timer* entry = *curr;
if (entry == handle) {
*curr = entry->next;
} else {
curr = &entry->next;
}
}
}

void timer_loop(void)
{
struct Timer* target;

for(target = head_handle; target; target = target->next) {
if(_timer_ticks >= target->timeout) {
if(target->repeat == 0) {
timer_stop(target);
} else {
target->timeout = _timer_ticks + target->repeat;
}
target->timeout_cb();
}
}
}

void timer_ticks(void)
{
_timer_ticks++;
}
#include "include.h"

static struct Timer* head_handle = NULL;

static volatile uint32_t _timer_ticks = 0;

void timer_init(struct Timer* handle, void(*timeout_cb)(), uint32_t timeout, uint32_t repeat)
{
// memset(handle, sizeof(struct Timer), 0);
handle->timeout_cb = timeout_cb;
handle->timeout = _timer_ticks + timeout;
handle->repeat = repeat;
}

int timer_start(struct Timer* handle)
{
struct Timer* target = head_handle;
while(target) {
if(target == handle) {
return -1;
}
target = target->next;
}
handle->next = head_handle;
head_handle = handle;

return 0;
}

void timer_stop(struct Timer* handle)
{
struct Timer** curr;

for(curr = &head_handle; *curr; ) {
struct Timer* entry = *curr;
if (entry == handle) {
*curr = entry->next;
} else {
curr = &entry->next;
}
}
}

void timer_loop(void)
{
struct Timer* target;

for(target = head_handle; target; target = target->next) {
if(_timer_ticks >= target->timeout) {
if(target->repeat == 0) {
timer_stop(target);
} else {
target->timeout = _timer_ticks + target->repeat;
}
target->timeout_cb();
}
}
}

void timer_ticks(void)
{
_timer_ticks++;
}
32 changes: 16 additions & 16 deletions src/main/drivers/multi_timer.h → src/main/drivers/drv_scheduler.h
Original file line number Diff line number Diff line change
@@ -1,16 +1,16 @@
#pragma once

#include "stdint.h"

typedef struct Timer {
uint32_t timeout;
uint32_t repeat;
void (*timeout_cb)(void);
struct Timer* next;
} Timer;

void timer_init(struct Timer* handle, void(*timeout_cb)(), uint32_t timeout, uint32_t repeat);
int timer_start(struct Timer* handle);
void timer_stop(struct Timer* handle);
void timer_ticks(void);
void timer_loop(void);
#pragma once

#include "stdint.h"

typedef struct Timer {
uint32_t timeout;
uint32_t repeat;
void (*timeout_cb)(void);
struct Timer* next;
} Timer;

void timer_init(struct Timer* handle, void(*timeout_cb)(), uint32_t timeout, uint32_t repeat);
int timer_start(struct Timer* handle);
void timer_stop(struct Timer* handle);
void timer_ticks(void);
void timer_loop(void);
1 change: 1 addition & 0 deletions src/main/drivers/drv_ws2812.c
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
#include "include.h"
1 change: 1 addition & 0 deletions src/main/drivers/drv_ws2812.h
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
#pragma once
6 changes: 4 additions & 2 deletions src/main/include.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,11 +45,12 @@

#include "irq.h"

#include "drivers/multi_timer.h"
#include "drivers/drv_scheduler.h"
#include "drivers/drv_system.h"
#include "drivers/drv_uart.h"
#include "drivers/drv_led.h"
#include "drivers/drv_watchdog.h"
#include "drivers/drv_ws2812.h"

#include "motor/motor_adc.h"
#include "motor/motor_comparator.h"
Expand All @@ -59,10 +60,11 @@
#include "motor/motor_timer.h"
#include "motor/motor_rtctl.h"
#include "motor/motor_rtctl_test.h"
#include "motor/motor_beeper.h"

#include "control/rpmctl.h"
#include "control/control.h"

#include "config/config.h"
#include "config/config_master.h"
#include "config/config_eeprom.h"
#include "config/config_eeprom.h"
1 change: 1 addition & 0 deletions src/main/motor/motor_beeper.c
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
#include "include.h"
1 change: 1 addition & 0 deletions src/main/motor/motor_beeper.h
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
#pragma once

0 comments on commit 27f5dd4

Please sign in to comment.