Updated test code
This commit is contained in:
parent
c351e9cfca
commit
f81661b800
178
zuno/zuno.ino
178
zuno/zuno.ino
@ -5,9 +5,9 @@
|
|||||||
#define SERVO_PIN 12
|
#define SERVO_PIN 12
|
||||||
const int SERVO_ENABLE_PIN = 9;
|
const int SERVO_ENABLE_PIN = 9;
|
||||||
|
|
||||||
const int SENSOR_LOCK_PIN = 0;
|
const int SENSOR_LOCK_PIN = 2;
|
||||||
const int SENSOR_HANDLE_PIN = 1;
|
const int SENSOR_HANDLE_PIN = 1;
|
||||||
const int SENSOR_DISABLE_PIN = 2;
|
const int SENSOR_DISABLE_PIN = 0;
|
||||||
const int SENSOR_CLOSE_PIN = 10;
|
const int SENSOR_CLOSE_PIN = 10;
|
||||||
|
|
||||||
const int BTN_LOCK_PIN = 3;
|
const int BTN_LOCK_PIN = 3;
|
||||||
@ -20,10 +20,11 @@ const int LED_UNLOCK_PIN = 6;
|
|||||||
#define SERVO_UNLOCK 2
|
#define SERVO_UNLOCK 2
|
||||||
#define SERVO_CENTER 3
|
#define SERVO_CENTER 3
|
||||||
|
|
||||||
#define SOURCE_EXTERNAL 0;
|
#define SOURCE_EXTERNAL 0
|
||||||
#define SOURCE_RFID 1;
|
#define SOURCE_RFID 1
|
||||||
#define SOURCE_ZWAVE 2;
|
#define SOURCE_ZWAVE 2
|
||||||
#define SOURCE_BUTTONS 3;
|
#define SOURCE_BUTTONS 3
|
||||||
|
#define SOURCE_SYSTEM 4
|
||||||
|
|
||||||
// Last saved LED value
|
// Last saved LED value
|
||||||
byte currentLEDValue = 0;
|
byte currentLEDValue = 0;
|
||||||
@ -59,13 +60,13 @@ int btn_unlock_prev_state = HIGH;
|
|||||||
int btn_unlock_current_state = LOW;
|
int btn_unlock_current_state = LOW;
|
||||||
int btn_unlock_debounce = 0;
|
int btn_unlock_debounce = 0;
|
||||||
|
|
||||||
int heartbeat = 0;
|
int activity_flash = 0;
|
||||||
int servo_status = 0;
|
int servo_status = 0;
|
||||||
int lock_status = 0;
|
int lock_status = 0;
|
||||||
int source_status = 0;
|
int source_status = 0;
|
||||||
|
|
||||||
unsigned long current_timestamp = 0;
|
unsigned long current_timestamp = 0;
|
||||||
unsigned long heartbeat_timestamp = 0;
|
unsigned long activity_timestamp = 0;
|
||||||
unsigned long servo_timestamp = 0;
|
unsigned long servo_timestamp = 0;
|
||||||
|
|
||||||
ServoController servo(12);
|
ServoController servo(12);
|
||||||
@ -74,29 +75,30 @@ ServoController servo(12);
|
|||||||
ZUNO_SETUP_CHANNELS(ZUNO_SWITCH_MULTILEVEL(getter, setter));
|
ZUNO_SETUP_CHANNELS(ZUNO_SWITCH_MULTILEVEL(getter, setter));
|
||||||
ZUNO_SETUP_DEBUG_MODE(DEBUG_ON);
|
ZUNO_SETUP_DEBUG_MODE(DEBUG_ON);
|
||||||
|
|
||||||
void set_servo(int mode){
|
void set_servo(int mode, int source){
|
||||||
if (mode == SERVO_LOCK){
|
if (sensor_handle == true && sensor_disable == false && sensor_close == true){
|
||||||
servo.setValue(40);
|
if (mode == SERVO_LOCK){
|
||||||
lock_status = SERVO_LOCK;
|
servo.setValue(160+2);
|
||||||
|
lock_status = SERVO_LOCK;
|
||||||
|
}
|
||||||
|
else if (mode == SERVO_UNLOCK){
|
||||||
|
servo.setValue(20+2);
|
||||||
|
lock_status = SERVO_UNLOCK;
|
||||||
|
}
|
||||||
|
else if (mode == SERVO_CENTER){
|
||||||
|
servo.setValue(90+2);
|
||||||
|
}
|
||||||
|
if (mode == SERVO_DISABLE){
|
||||||
|
digitalWrite(SERVO_ENABLE_PIN, LOW);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
servo.begin();
|
||||||
|
digitalWrite(SERVO_ENABLE_PIN, HIGH);
|
||||||
|
servo_timestamp = current_timestamp + 700;
|
||||||
|
}
|
||||||
|
servo_status = mode;
|
||||||
|
source_status = source;
|
||||||
}
|
}
|
||||||
else if (mode == SERVO_UNLOCK){
|
|
||||||
servo.setValue(140);
|
|
||||||
lock_status = SERVO_UNLOCK;
|
|
||||||
}
|
|
||||||
else if (mode == SERVO_CENTER){
|
|
||||||
servo.setValue(90);
|
|
||||||
}
|
|
||||||
if (mode == SERVO_DISABLE){
|
|
||||||
//servo.end();
|
|
||||||
digitalWrite(SERVO_ENABLE_PIN, LOW);
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
servo.begin();
|
|
||||||
digitalWrite(SERVO_ENABLE_PIN, HIGH);
|
|
||||||
servo_timestamp = current_timestamp + 500;
|
|
||||||
}
|
|
||||||
servo_status = mode;
|
|
||||||
source_status = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void update_buttons(){
|
void update_buttons(){
|
||||||
@ -112,6 +114,9 @@ void update_buttons(){
|
|||||||
if (sensor_lock_current_state != sensor_lock_prev_state) {
|
if (sensor_lock_current_state != sensor_lock_prev_state) {
|
||||||
if (++sensor_lock_debounce == SIGNAL_DEBOUNCE_CONSTANT) {
|
if (++sensor_lock_debounce == SIGNAL_DEBOUNCE_CONSTANT) {
|
||||||
if (sensor_lock_current_state == LOW) {
|
if (sensor_lock_current_state == LOW) {
|
||||||
|
sensor_lock = false;
|
||||||
|
}
|
||||||
|
else{
|
||||||
sensor_lock = true;
|
sensor_lock = true;
|
||||||
}
|
}
|
||||||
sensor_lock_prev_state = sensor_lock_current_state;
|
sensor_lock_prev_state = sensor_lock_current_state;
|
||||||
@ -125,6 +130,9 @@ void update_buttons(){
|
|||||||
if (sensor_handle_current_state == LOW) {
|
if (sensor_handle_current_state == LOW) {
|
||||||
sensor_handle = true;
|
sensor_handle = true;
|
||||||
}
|
}
|
||||||
|
else{
|
||||||
|
sensor_handle = false;
|
||||||
|
}
|
||||||
sensor_handle_prev_state = sensor_handle_current_state;
|
sensor_handle_prev_state = sensor_handle_current_state;
|
||||||
sensor_handle_debounce = 0;
|
sensor_handle_debounce = 0;
|
||||||
}
|
}
|
||||||
@ -134,6 +142,9 @@ void update_buttons(){
|
|||||||
if (sensor_disable_current_state != sensor_disable_prev_state) {
|
if (sensor_disable_current_state != sensor_disable_prev_state) {
|
||||||
if (++sensor_disable_debounce == SIGNAL_DEBOUNCE_CONSTANT) {
|
if (++sensor_disable_debounce == SIGNAL_DEBOUNCE_CONSTANT) {
|
||||||
if (sensor_disable_current_state == LOW) {
|
if (sensor_disable_current_state == LOW) {
|
||||||
|
sensor_disable = false;
|
||||||
|
}
|
||||||
|
else{
|
||||||
sensor_disable = true;
|
sensor_disable = true;
|
||||||
}
|
}
|
||||||
sensor_disable_prev_state = sensor_disable_current_state;
|
sensor_disable_prev_state = sensor_disable_current_state;
|
||||||
@ -145,6 +156,9 @@ void update_buttons(){
|
|||||||
if (sensor_close_current_state != sensor_close_prev_state) {
|
if (sensor_close_current_state != sensor_close_prev_state) {
|
||||||
if (++sensor_close_debounce == SIGNAL_DEBOUNCE_CONSTANT) {
|
if (++sensor_close_debounce == SIGNAL_DEBOUNCE_CONSTANT) {
|
||||||
if (sensor_close_current_state == LOW) {
|
if (sensor_close_current_state == LOW) {
|
||||||
|
sensor_close = false;
|
||||||
|
}
|
||||||
|
else{
|
||||||
sensor_close = true;
|
sensor_close = true;
|
||||||
}
|
}
|
||||||
sensor_close_prev_state = sensor_close_current_state;
|
sensor_close_prev_state = sensor_close_current_state;
|
||||||
@ -185,6 +199,13 @@ void update_buttons(){
|
|||||||
void setup() {
|
void setup() {
|
||||||
RFID.begin(9600);
|
RFID.begin(9600);
|
||||||
|
|
||||||
|
pinMode(SENSOR_LOCK_PIN, INPUT_PULLUP);
|
||||||
|
pinMode(SENSOR_HANDLE_PIN, INPUT_PULLUP);
|
||||||
|
pinMode(SENSOR_DISABLE_PIN, INPUT_PULLUP);
|
||||||
|
pinMode(SENSOR_CLOSE_PIN, INPUT_PULLUP);
|
||||||
|
pinMode(BTN_LOCK_PIN, INPUT_PULLUP);
|
||||||
|
pinMode(BTN_UNLOCK_PIN, INPUT_PULLUP);
|
||||||
|
|
||||||
pinMode(LED_UNLOCK_PIN, OUTPUT); // setup pin as output
|
pinMode(LED_UNLOCK_PIN, OUTPUT); // setup pin as output
|
||||||
digitalWrite(LED_UNLOCK_PIN, LOW);
|
digitalWrite(LED_UNLOCK_PIN, LOW);
|
||||||
pinMode(LED_LOCK_PIN, OUTPUT); // setup pin as output
|
pinMode(LED_LOCK_PIN, OUTPUT); // setup pin as output
|
||||||
@ -193,22 +214,24 @@ void setup() {
|
|||||||
pinMode(SERVO_ENABLE_PIN, OUTPUT); // setup pin as output
|
pinMode(SERVO_ENABLE_PIN, OUTPUT); // setup pin as output
|
||||||
digitalWrite(SERVO_ENABLE_PIN, LOW);
|
digitalWrite(SERVO_ENABLE_PIN, LOW);
|
||||||
|
|
||||||
set_servo(SERVO_CENTER);
|
set_servo(SERVO_CENTER, SOURCE_SYSTEM);
|
||||||
}
|
}
|
||||||
|
|
||||||
// the loop routine runs over and over again forever:
|
// the loop routine runs over and over again forever:
|
||||||
void loop() {
|
void loop() {
|
||||||
current_timestamp = millis();
|
current_timestamp = millis();
|
||||||
|
|
||||||
update_buttons();
|
update_buttons();
|
||||||
|
|
||||||
if (btn_lock == true && servo_status == SERVO_DISABLE){
|
|
||||||
set_servo(SERVO_LOCK);
|
// Check button status
|
||||||
|
if (btn_lock == true){
|
||||||
|
set_servo(SERVO_LOCK, SOURCE_BUTTONS);
|
||||||
btn_lock = false;
|
btn_lock = false;
|
||||||
btn_unlock = false;
|
btn_unlock = false;
|
||||||
}
|
}
|
||||||
else if (btn_unlock == true && servo_status == SERVO_DISABLE){
|
else if (btn_unlock == true){
|
||||||
set_servo(SERVO_UNLOCK);
|
set_servo(SERVO_UNLOCK, SOURCE_BUTTONS);
|
||||||
btn_unlock = false;
|
btn_unlock = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -216,23 +239,84 @@ void loop() {
|
|||||||
if (servo_status > SERVO_DISABLE) {
|
if (servo_status > SERVO_DISABLE) {
|
||||||
if (current_timestamp >= servo_timestamp) {
|
if (current_timestamp >= servo_timestamp) {
|
||||||
if (servo_status < SERVO_CENTER) {
|
if (servo_status < SERVO_CENTER) {
|
||||||
set_servo(SERVO_CENTER);
|
set_servo(SERVO_CENTER, source_status);
|
||||||
}else{
|
}else{
|
||||||
set_servo(SERVO_DISABLE);
|
set_servo(SERVO_DISABLE, source_status);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Heartbeat
|
|
||||||
if (current_timestamp >= heartbeat_timestamp) {
|
// LED display
|
||||||
if (heartbeat == 1) {
|
if (servo_status == SERVO_LOCK){
|
||||||
heartbeat = 0;
|
if (current_timestamp >= activity_timestamp) {
|
||||||
digitalWrite(LED_LOCK_PIN, HIGH);
|
if (activity_flash == 0){
|
||||||
} else {
|
digitalWrite(LED_LOCK_PIN, HIGH);
|
||||||
heartbeat = 1;
|
digitalWrite(LED_UNLOCK_PIN, LOW);
|
||||||
digitalWrite(LED_LOCK_PIN, LOW);
|
activity_flash = 1;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
digitalWrite(LED_LOCK_PIN, LOW);
|
||||||
|
digitalWrite(LED_UNLOCK_PIN, LOW);
|
||||||
|
activity_flash = 0;
|
||||||
|
}
|
||||||
|
activity_timestamp = current_timestamp + 50;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (servo_status == SERVO_UNLOCK){
|
||||||
|
if (current_timestamp >= activity_timestamp) {
|
||||||
|
if (activity_flash == 0){
|
||||||
|
digitalWrite(LED_LOCK_PIN, LOW);
|
||||||
|
digitalWrite(LED_UNLOCK_PIN, HIGH);
|
||||||
|
activity_flash = 1;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
digitalWrite(LED_LOCK_PIN, LOW);
|
||||||
|
digitalWrite(LED_UNLOCK_PIN, LOW);
|
||||||
|
activity_flash = 0;
|
||||||
|
}
|
||||||
|
activity_timestamp = current_timestamp + 50;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (servo_status == SERVO_DISABLE){
|
||||||
|
if (sensor_close == false || sensor_handle == false){
|
||||||
|
if (current_timestamp >= activity_timestamp) {
|
||||||
|
if (activity_flash == 0){
|
||||||
|
digitalWrite(LED_LOCK_PIN, LOW);
|
||||||
|
digitalWrite(LED_UNLOCK_PIN, HIGH);
|
||||||
|
activity_flash = 1;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
digitalWrite(LED_LOCK_PIN, LOW);
|
||||||
|
digitalWrite(LED_UNLOCK_PIN, LOW);
|
||||||
|
activity_flash = 0;
|
||||||
|
}
|
||||||
|
activity_timestamp = current_timestamp + 500;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (sensor_disable == true){
|
||||||
|
if (current_timestamp >= activity_timestamp) {
|
||||||
|
if (activity_flash == 0){
|
||||||
|
digitalWrite(LED_LOCK_PIN, HIGH);
|
||||||
|
digitalWrite(LED_UNLOCK_PIN, LOW);
|
||||||
|
activity_flash = 1;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
digitalWrite(LED_LOCK_PIN, LOW);
|
||||||
|
digitalWrite(LED_UNLOCK_PIN, LOW);
|
||||||
|
activity_flash = 0;
|
||||||
|
}
|
||||||
|
activity_timestamp = current_timestamp + 500;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (sensor_lock == true){
|
||||||
|
digitalWrite(LED_LOCK_PIN, HIGH);
|
||||||
|
digitalWrite(LED_UNLOCK_PIN, LOW);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
digitalWrite(LED_LOCK_PIN, LOW);
|
||||||
|
digitalWrite(LED_UNLOCK_PIN, HIGH);
|
||||||
}
|
}
|
||||||
heartbeat_timestamp = current_timestamp + 500;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user