Compare commits

...

10 Commits

Author SHA1 Message Date
82ebb95678 control on off 2020-08-29 18:41:28 -05:00
ecb494c4b1 ultimos cambios 2020-08-23 2020-08-23 20:11:08 -05:00
8a1f485d20 readme 20020 2020-08-23 17:46:38 -05:00
5d6fe0de20 readme 2020-08-23 2020-08-23 17:43:19 -05:00
94fd4b0606 cotrol on of 2020-08-23 14:44:44 -05:00
890a26ac06 limpieza 2020-08-23 14:34:25 -05:00
2b9e394318 commit 2019-01-26 2019-01-26 15:42:42 -05:00
69d9a4b1e6 pcb inicial 2019-01-13 18:45:54 -05:00
56581a0a5b inicial 2018-07-02 21:56:34 -05:00
5bb74adf96 Eliminar 'README.md' 2018-07-02 21:54:18 -05:00
30 changed files with 473 additions and 1 deletions

5
.gitignore vendored Normal file
View File

@@ -0,0 +1,5 @@
.pio
.vscode/.browse.c_cpp.db*
.vscode/c_cpp_properties.json
.vscode/launch.json
.vscode/ipch

67
.travis.yml Normal file
View File

@@ -0,0 +1,67 @@
# Continuous Integration (CI) is the practice, in software
# engineering, of merging all developer working copies with a shared mainline
# several times a day < https://docs.platformio.org/page/ci/index.html >
#
# Documentation:
#
# * Travis CI Embedded Builds with PlatformIO
# < https://docs.travis-ci.com/user/integration/platformio/ >
#
# * PlatformIO integration with Travis CI
# < https://docs.platformio.org/page/ci/travis.html >
#
# * User Guide for `platformio ci` command
# < https://docs.platformio.org/page/userguide/cmd_ci.html >
#
#
# Please choose one of the following templates (proposed below) and uncomment
# it (remove "# " before each line) or use own configuration according to the
# Travis CI documentation (see above).
#
#
# Template #1: General project. Test it using existing `platformio.ini`.
#
# language: python
# python:
# - "2.7"
#
# sudo: false
# cache:
# directories:
# - "~/.platformio"
#
# install:
# - pip install -U platformio
# - platformio update
#
# script:
# - platformio run
#
# Template #2: The project is intended to be used as a library with examples.
#
# language: python
# python:
# - "2.7"
#
# sudo: false
# cache:
# directories:
# - "~/.platformio"
#
# env:
# - PLATFORMIO_CI_SRC=path/to/test/file.c
# - PLATFORMIO_CI_SRC=examples/file.ino
# - PLATFORMIO_CI_SRC=path/to/test/directory
#
# install:
# - pip install -U platformio
# - platformio update
#
# script:
# - platformio ci --lib="." --board=ID_1 --board=ID_2 --board=ID_N

7
.vscode/extensions.json vendored Normal file
View File

@@ -0,0 +1,7 @@
{
// See http://go.microsoft.com/fwlink/?LinkId=827846
// for the documentation about the extensions.json format
"recommendations": [
"platformio.platformio-ide"
]
}

View File

@@ -1,2 +1,52 @@
# balancing_robot # Robot balancing ESP32
Robot balanceador basado en la tarjeta de desarrollo ESP32 MH-ET live y el módulo MPU6050 y los drivers DRV8825
- ESP32 MH-ET LIVE
- 2 motores nema 17
- 2 driver motores
- MPU6050
- bateria LiPo
![](imagenes/balancing.jpg)
## Diseño 3d
Los diseños estan realizados en FreeCad e impresas en PLA rojo y los neumáticos en TPU
![](imagenes/3d_balancing.png)
Mejoras:
+ mejorar acceso a los controles de los motores
+ mejorar conector modulo MPU6050
+ bajar motores o llantas de mayor tamaño
+ re-diseñar espacio para la batería
## ToDo
+ [x] Control On Off
+ [ ] Control Proporcional
+ [ ] Control PI
+ [ ] Control PID
+ [ ] Control Jostick Web
+ [ ] OTA y Telnet
## Referencias
[https://github.com/tockn/MPU6050_tockn](https://github.com/tockn/MPU6050_tockn)
[http://www.brokking.net/yabr_main.html](http://www.brokking.net/yabr_main.html)
[http://axelsdiy.brinkeby.se/?page_id=1141](http://axelsdiy.brinkeby.se/?page_id=1141)
[https://robologs.net/2014/10/15/tutorial-de-arduino-y-mpu-6050/](https://robologs.net/2014/10/15/tutorial-de-arduino-y-mpu-6050/)
[https://www.luisllamas.es/medir-la-inclinacion-imu-arduino-filtro-complementario/](https://www.luisllamas.es/medir-la-inclinacion-imu-arduino-filtro-complementario/)

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@@ -0,0 +1,39 @@
<!DOCTYPE html>
<html>
<head>
<meta charset="utf-8">
<meta http-equiv="X-UA-Compatible" content="IE=edge">
<title>A2P assembly hierarchy visualization</title>
</head>
<body>
<div class="mermaid">
graph TD
parte_inferior_001 -- plane --> lateral_balancing_002
parte_inferior_001 -- pointIdentity --> lateral_balancing_002
lateral_balancing_001(lateral_balancing_001<br>*FIXED*) -- plane --> parte_inferior_001
lateral_balancing_001(lateral_balancing_001<br>*FIXED*) -- pointIdentity --> parte_inferior_001
lateral_balancing_001(lateral_balancing_001<br>*FIXED*) -- plane --> motores_001
lateral_balancing_001(lateral_balancing_001<br>*FIXED*) -- plane --> parte_inferior_003
lateral_balancing_001(lateral_balancing_001<br>*FIXED*) -- pointIdentity --> parte_inferior_003
lateral_balancing_001(lateral_balancing_001<br>*FIXED*) -- axisParallel --> motores_001
lateral_balancing_002 -- plane --> control_motors_001
lateral_balancing_002 -- pointIdentity --> control_motors_001
lateral_balancing_002 -- plane --> motores_002
lateral_balancing_002 -- pointIdentity --> motores_002
lateral_balancing_002 -- axisParallel --> motores_002
lateral_balancing_002 -- plane --> parte_inferior_002
lateral_balancing_002 -- pointIdentity --> parte_inferior_002
lateral_balancing_002 -- pointIdentity --> parte_inferior_002
control_motors_001
motores_001 -- pointIdentity --> ruedas_002
motores_002 -- pointIdentity --> ruedas_001
ruedas_001
ruedas_002
parte_inferior_002
parte_inferior_003
</div>
<script src="https://unpkg.com/mermaid@7.1.2/dist/mermaid.js"></script>
<script>
mermaid.initialize({startOnLoad: true});
</script>
</body></html>

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

BIN
documentos/drv8825.pdf Normal file

Binary file not shown.

BIN
imagenes/3d_balancing.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 23 KiB

BIN
imagenes/balancing.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 114 KiB

39
include/README Normal file
View File

@@ -0,0 +1,39 @@
This directory is intended for project header files.
A header file is a file containing C declarations and macro definitions
to be shared between several project source files. You request the use of a
header file in your project source file (C, C++, etc) located in `src` folder
by including it, with the C preprocessing directive `#include'.
```src/main.c
#include "header.h"
int main (void)
{
...
}
```
Including a header file produces the same results as copying the header file
into each source file that needs it. Such copying would be time-consuming
and error-prone. With a header file, the related declarations appear
in only one place. If they need to be changed, they can be changed in one
place, and programs that include the header file will automatically use the
new version when next recompiled. The header file eliminates the labor of
finding and changing all the copies as well as the risk that a failure to
find one copy will result in inconsistencies within a program.
In C, the usual convention is to give header files names that end with `.h'.
It is most portable to use only letters, digits, dashes, and underscores in
header file names, and at most one dot.
Read more about using header files in official GCC documentation:
* Include Syntax
* Include Operation
* Once-Only Headers
* Computed Includes
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html

46
lib/README Normal file
View File

@@ -0,0 +1,46 @@
This directory is intended for project specific (private) libraries.
PlatformIO will compile them to static libraries and link into executable file.
The source code of each library should be placed in a an own separate directory
("lib/your_library_name/[here are source files]").
For example, see a structure of the following two libraries `Foo` and `Bar`:
|--lib
| |
| |--Bar
| | |--docs
| | |--examples
| | |--src
| | |- Bar.c
| | |- Bar.h
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
| |
| |--Foo
| | |- Foo.c
| | |- Foo.h
| |
| |- README --> THIS FILE
|
|- platformio.ini
|--src
|- main.c
and a contents of `src/main.c`:
```
#include <Foo.h>
#include <Bar.h>
int main (void)
{
...
}
```
PlatformIO Library Dependency Finder will find automatically dependent
libraries scanning project source files.
More information about PlatformIO Library Dependency Finder
- https://docs.platformio.org/page/librarymanager/ldf.html

15
platformio.ini Normal file
View File

@@ -0,0 +1,15 @@
; PlatformIO Project Configuration File
;
; Build options: build flags, source filter
; Upload options: custom upload port, speed and extra flags
; Library options: dependencies, extra library storages
; Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html
[env:mhetesp32devkit]
platform = espressif32
board = mhetesp32devkit
framework = arduino
monitor_speed = 115200

193
src/main.cpp Normal file
View File

@@ -0,0 +1,193 @@
#include <Arduino.h>
#include <Wire.h>
#include <MPU6050_tockn.h>
//TaskHandle_t TareaProcesador1;
//void loop1(void *pvParameters);
/*
=========================================
definiciones de los motores paso a paso
=========================================
*/
#define STEP_1 13
#define DIR_1 25
#define STEP_2 33
#define DIR_2 14
#define max_speed 100
void IRAM_ATTR onTimer(); //declaración callback interrupciones tick Motores
void motores_calc();
void control_on_off(float angulo);
hw_timer_t *timer_motores = NULL; //timer para controlar tick de los motores paso a paso
portMUX_TYPE timerMux = portMUX_INITIALIZER_UNLOCKED;
volatile int tick_motores;
volatile int left_motor, throttle_left_motor, throttle_counter_left_motor, throttle_left_motor_memory;
volatile int right_motor, throttle_right_motor, throttle_counter_right_motor, throttle_right_motor_memory;
volatile float setPoint = 0.0;
volatile int dir = 0;
bool FWD = HIGH;
bool BWD = LOW;
//==========================================
/*
============================================
Definiciones MPU6050
============================================
*/
MPU6050 mpu6050(Wire);
float ay;
long timer = 0;
//==========================================
void setup()
{
//Configuracion motores
pinMode(23, OUTPUT);
pinMode(STEP_1, OUTPUT);
pinMode(STEP_2, OUTPUT);
pinMode(DIR_1, OUTPUT);
pinMode(DIR_2, OUTPUT);
digitalWrite(DIR_1, LOW);
digitalWrite(DIR_2, LOW);
timer_motores = timerBegin(0, 80, true);
timerAttachInterrupt(timer_motores, &onTimer, true);
timerAlarmWrite(timer_motores, 50, true);
//I2C
Wire.begin();
Serial.begin(115200);
Wire.begin();
// xTaskCreatePinnedToCore(loop1, "Tarea1", 10000, NULL, 1, &TareaProcesador1, 0);
delay(1000); // Pause for 1 seconds
//Configuracion MPU6050
mpu6050.begin();
mpu6050.calcGyroOffsets(false);
delay(2000);
//Calculamos el setPoint inicial
Serial.print("\n[");
for (int i = 0; i < 100; i++)
{
mpu6050.update();
setPoint += mpu6050.getAngleY();
//Serial.print(setPoint),Serial.print(",");
delay(100);
}
Serial.print("]");
setPoint = setPoint / 100;
Serial.print("\nSetpoint:"), Serial.println(setPoint);
Serial.print("Core: "), Serial.println(xPortGetCoreID());
timerAlarmEnable(timer_motores);
}
void loop()
{
if (millis() - timer > 4)
{
mpu6050.update();
ay = mpu6050.getAngleY();
if (ay > 30 || ay < -30)
{
throttle_left_motor = 0;
throttle_right_motor = 0;
}
else
{
control_on_off(ay);
}
//Serial.println(ay);*/
timer = millis();
}
if (tick_motores > 0)
{
motores_calc();
}
}
/*
=============================
Funciones Motores paso a paso
==============================
*/
//Interrupcion Tick Motores paso a paso
void IRAM_ATTR onTimer()
{
portENTER_CRITICAL_ISR(&timerMux);
tick_motores++;
portEXIT_CRITICAL_ISR(&timerMux);
}
void motores_calc()
{
portENTER_CRITICAL(&timerMux);
tick_motores--;
portEXIT_CRITICAL(&timerMux);
throttle_counter_left_motor++; //Increase the throttle_counter_left_motor variable by 1 every time this routine is executed
if (throttle_counter_left_motor > throttle_left_motor_memory)
{ //If the number of loops is larger then the throttle_left_motor_memory variable
throttle_counter_left_motor = 0; //Reset the throttle_counter_left_motor variable
throttle_left_motor_memory = throttle_left_motor; //Load the next throttle_left_motor variable
if (throttle_left_motor_memory < 0)
{ //If the throttle_left_motor_memory is negative
digitalWrite(DIR_1, BWD); //Set output 3 low to reverse the direction of the stepper controller
throttle_left_motor_memory *= -1; //Invert the throttle_left_motor_memory variable
}
else
digitalWrite(DIR_1, FWD); //Set output 3 high for a forward direction of the stepper motor
}
else if (throttle_counter_left_motor == 1)
digitalWrite(STEP_1, HIGH); //Set output 2 high to create a pulse for the stepper controller
else if (throttle_counter_left_motor == 2)
digitalWrite(STEP_1, LOW); //Set output 2 low because the pulse only has to last for 20us
//right motor pulse calculations
throttle_counter_right_motor++; //Increase the throttle_counter_right_motor variable by 1 every time the routine is executed
if (throttle_counter_right_motor > throttle_right_motor_memory)
{ //If the number of loops is larger then the throttle_right_motor_memory variable
throttle_counter_right_motor = 0; //Reset the throttle_counter_right_motor variable
throttle_right_motor_memory = throttle_right_motor; //Load the next throttle_right_motor variable
if (throttle_right_motor_memory < 0)
{ //If the throttle_right_motor_memory is negative
digitalWrite(DIR_2, BWD); //Set output 5 low to reverse the direction of the stepper controller
throttle_right_motor_memory *= -1; //Invert the throttle_right_motor_memory variable
}
else
digitalWrite(DIR_2, FWD);
; //Set output 5 high for a forward direction of the stepper motor
}
else if (throttle_counter_right_motor == 1)
digitalWrite(STEP_2, HIGH); //Set output 4 high to create a pulse for the stepper controller
else if (throttle_counter_right_motor == 2)
digitalWrite(STEP_2, LOW);
}
void control_on_off(float angulo)
{
float error = angulo - setPoint;
if (error > 4)
{
dir = -1;
}
else if (error < -4)
{
dir = 1;
}
else
{
dir = 0;
}
throttle_left_motor = max_speed * dir;
throttle_right_motor = max_speed * dir;
}
/*void loop1(void *pvParameters){
for(;;){
Serial.print("Core: "),Serial.println(xPortGetCoreID());
}
}*/

11
test/README Normal file
View File

@@ -0,0 +1,11 @@
This directory is intended for PIO Unit Testing and project tests.
Unit Testing is a software testing method by which individual units of
source code, sets of one or more MCU program modules together with associated
control data, usage procedures, and operating procedures, are tested to
determine whether they are fit for use. Unit testing finds problems early
in the development cycle.
More information about PIO Unit Testing:
- https://docs.platformio.org/page/plus/unit-testing.html