Compare commits
8 Commits
Author | SHA1 | Date | |
---|---|---|---|
265c3b3b39 | |||
6a1786ec9a | |||
e3843db340 | |||
da2a06b23a | |||
1d1874872b | |||
2d32523317 | |||
adc6134d8b | |||
d2dec55110 |
27
.github/workflows/test_build.yml
vendored
27
.github/workflows/test_build.yml
vendored
@ -1,35 +1,22 @@
|
||||
on:
|
||||
push:
|
||||
branches: [ master ]
|
||||
branches:
|
||||
- main
|
||||
- develop
|
||||
pull_request:
|
||||
branches: [ master ]
|
||||
branches:
|
||||
- main
|
||||
- develop
|
||||
|
||||
jobs:
|
||||
test:
|
||||
|
||||
runs-on: ubuntu-latest
|
||||
|
||||
steps:
|
||||
- name: Checkout project
|
||||
uses: actions/checkout@v3
|
||||
|
||||
# - name: Cache pip
|
||||
# uses: actions/cache@v3
|
||||
# with:
|
||||
# path: ~/.cache/pip
|
||||
# key: ${{ runner.os }}-pip-${{ hashFiles('**/requirements.txt') }}
|
||||
# restore-keys: |
|
||||
# ${{ runner.os }}-pip-
|
||||
|
||||
# # this cache the platformio binaries and not the .pio folder
|
||||
# - name: Cache PlatformIO
|
||||
# uses: actions/cache@v3
|
||||
# with:
|
||||
# path: ~/.platformio
|
||||
# key: ${{ runner.os }}-${{ hashFiles('**/lockfiles') }}
|
||||
|
||||
- name: Set up Python
|
||||
uses: https://github.com/actions/setup-python@v3
|
||||
uses: actions/setup-python@v3
|
||||
|
||||
- name: Install PlatformIO
|
||||
run: pip install platformio
|
||||
|
@ -22,7 +22,7 @@ build_flags =
|
||||
-D STEPER_ACC=200
|
||||
;-D STEPER_PAS=755.906 ; = 65mm
|
||||
-D STEPER_PAS=58 ; = 5mm
|
||||
-D STEPER_SPEED=2700 ;1000 ; 2500
|
||||
-D STEPER_SPEED=2000 ;1000 ; 2500
|
||||
-D GRBL_UPDATE=165 ;update time in ms
|
||||
;;;;;;;;;;;;;;;;;;;;;;
|
||||
;;; App config ;;;
|
||||
@ -40,4 +40,4 @@ build_flags =
|
||||
|
||||
|
||||
|
||||
-D CONVOYER_LEN=80 ;mm
|
||||
-D CONVOYER_LEN=70 ; 80 ;mm
|
||||
|
23
docs/Schématics/Algo.puml
Normal file
23
docs/Schématics/Algo.puml
Normal file
@ -0,0 +1,23 @@
|
||||
@startuml algo
|
||||
|
||||
!pragma useVerticalIf on
|
||||
|
||||
start
|
||||
|
||||
:teste périphérique;
|
||||
|
||||
:gestion bourrage colis;
|
||||
|
||||
if (NFC détecter) then (oui)
|
||||
:j'affiche le tag lu;
|
||||
:je récupère le produit sur Dolibarr;
|
||||
:gestion erreur;
|
||||
:je crée un mouvement de stock Dolibarr;
|
||||
:gestion erreur;
|
||||
:je bouge l'aiguillage de destination;
|
||||
:j'avance de la longueur du tapis;
|
||||
else (non)
|
||||
:avance tapis;
|
||||
endif
|
||||
stop
|
||||
@enduml
|
@ -8,18 +8,6 @@ class Dolibarr {
|
||||
+ String createStockMovement(String tagID, String warehouseId)
|
||||
}
|
||||
|
||||
package "Managers" {
|
||||
abstract AManager {
|
||||
# ILCDScreen lcd
|
||||
# IServoMotor servo
|
||||
# IGRBL grbl
|
||||
# INFCReader nfc
|
||||
}
|
||||
|
||||
class WarehouseManager
|
||||
|
||||
WarehouseManager .|> AManager
|
||||
}
|
||||
|
||||
package "Components" {
|
||||
package "NFCReader" {
|
||||
@ -66,12 +54,11 @@ class Program {
|
||||
+ void loop
|
||||
}
|
||||
|
||||
AManager <-- IServoMotor
|
||||
AManager <-- IGRBL
|
||||
AManager <-- ILCDScreen
|
||||
AManager <-- INFCReader
|
||||
Program <-- IServoMotor
|
||||
Program <-- IGRBL
|
||||
Program <-- ILCDScreen
|
||||
Program <-- INFCReader
|
||||
|
||||
Program <-- WarehouseManager
|
||||
Program <-- Dolibarr
|
||||
Dolibarr --> Program
|
||||
|
||||
@enduml
|
||||
|
@ -22,6 +22,7 @@ public:
|
||||
void checkNfc();
|
||||
void checkServo();
|
||||
void checkWifi();
|
||||
void moveStepper();
|
||||
private:
|
||||
DolibarrClient *client;
|
||||
ServoMotorComponent *servo;
|
||||
|
@ -4,6 +4,8 @@
|
||||
#include <iostream>
|
||||
#include "M5LCD.h"
|
||||
|
||||
HTTPClient *client = new HTTPClient();
|
||||
|
||||
DolibarrClient::DolibarrClient(struct DolibarrConfig dolibarr_config) : dolibarr(dolibarr_config) {
|
||||
#if defined(DEBUG)
|
||||
Serial.println(" --- Dolibarr configuration --- ");
|
||||
@ -14,7 +16,6 @@ DolibarrClient::DolibarrClient(struct DolibarrConfig dolibarr_config) : dolibarr
|
||||
}
|
||||
|
||||
HTTPClient *DolibarrClient::build_url(const String& url) const {
|
||||
auto *client = new HTTPClient();
|
||||
String clientUrl = this->dolibarr.url + url;
|
||||
client->begin(clientUrl);
|
||||
client->addHeader("Content-Type", "application/json");
|
||||
@ -25,40 +26,12 @@ HTTPClient *DolibarrClient::build_url(const String& url) const {
|
||||
return client;
|
||||
}
|
||||
|
||||
|
||||
int DolibarrClient::login() const {
|
||||
HTTPClient *client = this->build_url(API_LOGIN_URL);
|
||||
int httpResponseCode = client->GET();
|
||||
if (httpResponseCode > 0) {
|
||||
DynamicJsonDocument doc(384);
|
||||
DeserializationError error = deserializeJson(doc, client->getString().c_str());
|
||||
if (error) {
|
||||
Serial.println("ERROR: ");
|
||||
Serial.println(error.c_str());
|
||||
delete client;
|
||||
return -1;
|
||||
}
|
||||
delete client;
|
||||
return 0;
|
||||
}
|
||||
delete client;
|
||||
return -1;
|
||||
}
|
||||
|
||||
String replace_id(const char *str, const char *id) {
|
||||
String url(str);
|
||||
url.replace("{id}", id);
|
||||
return url;
|
||||
}
|
||||
|
||||
std::vector<models::Product> *DolibarrClient::list_products() const {
|
||||
HTTPClient *client = this->build_url(API_LIST_PRODUCT_URL);
|
||||
if (client->GET() == HTTP_CODE_OK) {
|
||||
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
models::Product DolibarrClient::get_product_by_factory_id(const char* factory_id) const {
|
||||
HTTPClient *client = this->build_url(replace_id("/products?sortorder=ASC&limit=1&sqlfilters=(t.accountancy_code_sell:like:'{id}')", factory_id).c_str());
|
||||
if (client->GET() == HTTP_CODE_OK) {
|
||||
@ -67,7 +40,6 @@ models::Product DolibarrClient::get_product_by_factory_id(const char* factory_id
|
||||
if (error) {
|
||||
Serial.println("ERROR: ");
|
||||
Serial.println(error.c_str());
|
||||
delete client;
|
||||
return {};
|
||||
}
|
||||
for (auto obj : doc.as<JsonArray>()) {
|
||||
@ -80,13 +52,10 @@ models::Product DolibarrClient::get_product_by_factory_id(const char* factory_id
|
||||
product.accountancy_code_sell = obj["accountancy_code_sell"].as<std::string>();
|
||||
product.accountancy_code_sell_export = obj["accountancy_code_sell_export"].as<std::string>();
|
||||
product.fk_default_warehouse = obj["fk_default_warehouse"].as<std::string>();
|
||||
delete client;
|
||||
return product;
|
||||
}
|
||||
delete client;
|
||||
return {};
|
||||
}
|
||||
delete client;
|
||||
return {};
|
||||
}
|
||||
|
||||
@ -96,7 +65,6 @@ models::Product *DolibarrClient::get_product_by_id(const char* id_product) const
|
||||
DynamicJsonDocument doc(6144);
|
||||
DeserializationError error = deserializeJson(doc, client->getString().c_str());
|
||||
if (error) {
|
||||
delete client;
|
||||
return nullptr;
|
||||
}
|
||||
auto *product = new models::Product();
|
||||
@ -107,10 +75,8 @@ models::Product *DolibarrClient::get_product_by_id(const char* id_product) const
|
||||
product->label = doc["label"].as<std::string>();
|
||||
product->accountancy_code_sell = doc["accountancy_code_sell"].as<std::string>();
|
||||
product->accountancy_code_sell_export = doc["accountancy_code_sell_export"].as<std::string>();
|
||||
delete client;
|
||||
return product;
|
||||
}
|
||||
delete client;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
@ -122,7 +88,6 @@ std::vector<models::Warehouse> *DolibarrClient::list_warehouse() const {
|
||||
if (error) {
|
||||
Serial.println("ERROR: ");
|
||||
Serial.println(error.c_str());
|
||||
delete client;
|
||||
return nullptr;
|
||||
}
|
||||
auto *warehouses = new std::vector<models::Warehouse>();
|
||||
@ -132,10 +97,8 @@ std::vector<models::Warehouse> *DolibarrClient::list_warehouse() const {
|
||||
warehouse.label = obj["label"].as<std::string>();
|
||||
warehouses->push_back(warehouse);
|
||||
}
|
||||
delete client;
|
||||
return warehouses;
|
||||
}
|
||||
delete client;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
@ -151,7 +114,6 @@ int DolibarrClient::create_movement(models::CreateProductStock stock) const {
|
||||
serializeJson(doc, result);
|
||||
Serial.println(result.c_str());
|
||||
if (client->POST(result.c_str()) == HTTP_CODE_OK) {
|
||||
delete client;
|
||||
return 0;
|
||||
}
|
||||
return -1;
|
||||
|
@ -20,9 +20,7 @@ class DolibarrClient {
|
||||
public:
|
||||
DolibarrClient(DolibarrConfig dolibarr_config);
|
||||
~DolibarrClient() = default;
|
||||
int login() const;
|
||||
std::vector<models::Warehouse> *list_warehouse() const;
|
||||
std::vector<models::Product> *list_products() const;
|
||||
models::Product *get_product_by_id(const char* id_product) const;
|
||||
models::Product get_product_by_factory_id(const char* uuid) const;
|
||||
int create_movement(models::CreateProductStock stock) const;
|
||||
|
@ -4,7 +4,7 @@
|
||||
* M5LCD classe
|
||||
*/
|
||||
|
||||
M5LCD::M5LCD() : _current_page(0), _logs() , _debug_loc_y(0), _components_status({COMPONENT_KO, COMPONENT_KO, COMPONENT_KO, COMPONENT_KO, COMPONENT_KO}) {
|
||||
M5LCD::M5LCD() : _current_page(0), _logs() , _debug_loc_y(0), _components_status({COMPONENT_KO, COMPONENT_KO, COMPONENT_KO, COMPONENT_KO, COMPONENT_OK}) {
|
||||
this->_product_id = std::string("");
|
||||
this->_product_label = std::string("");
|
||||
this->_last_nfc = std::string("");
|
||||
@ -173,6 +173,7 @@ void M5LCD::set_dolibarr_status(AvailableComponentsStatus status) {
|
||||
|
||||
void M5LCD::update_dashboard() const {
|
||||
if (this->_current_page == DASHBOARD_SCREEN) {
|
||||
M5.Lcd.clear();
|
||||
this->show_dashboard();
|
||||
}
|
||||
}
|
||||
|
@ -77,7 +77,7 @@ Program::Program() {
|
||||
lcdScreen = new M5LCD();
|
||||
lcdScreen->add_log("Initialize M5LCD component....");
|
||||
this->nfcReader = new NfcReader(NFC_ADDR);
|
||||
this->servo = new ServoMotorComponent(2, 1, 1);
|
||||
this->servo = new ServoMotorComponent(2, 1, 1.5);
|
||||
this->servo->setDesiredPosition(Position::MIDDLE);
|
||||
this->grbl = new GRBL(STEPMOTOR_I2C_ADDR);
|
||||
this->outputReader = new BigNfcReader();
|
||||
@ -164,8 +164,8 @@ void Program::loop() {
|
||||
}
|
||||
this->grbl->mouveForward(CONVOYER_LEN);
|
||||
} else {
|
||||
if((this->grbl->isIddle() || (maintenant - this->grblUpdateTime >= GRBL_UPDATE)) && lcdScreen->get_components().grbl == COMPONENT_OK){
|
||||
this->grblUpdateTime = maintenant;
|
||||
if((this->grbl->isIddle()) && lcdScreen->get_components().grbl == COMPONENT_OK){
|
||||
//this->grblUpdateTime = maintenant;
|
||||
this->grbl->mouveForward(5);
|
||||
}
|
||||
}
|
||||
|
Loading…
x
Reference in New Issue
Block a user