Perro-Bot

36523

Intro: Perro-Bot

the best friend of the electronic engineer, the dog-bot

the body of a quadruped robot with 3 degrees of freedom per leg, very cheap and simple, that will serve you as a platform for all kinds of projects that you sound, being able to control it remotely or totally autonomous

STEP 1:


this robot does from walking, sitting, standing, to running like crazy everywhere

Being able to open the legs, close them, move the hips, and the knees thanks to the most common servomotors that you can get from China

a 3D printed shell and leg segments made of balsa wood (so lightweight)

STEP 2:

controlled with the powerful stm32f401 microcontroller

to control the 12 servomotors whit PWMs at the same time, and to be able to produce the walking sequences of the dog-bot

STEP 3:

We start by looking at the images of the knee model to understand how the legs will move when stretched and flexed

and based on this experimental model we will design the final model, of which I attach the designs (use both solid works and freecad to design the mechanical parts)

STEP 4:

As you can see in the image, each leg consists of 3 servomotors, for its movements, M1: to open the robot's legs, M2: to move the hip, and M3: to move the knee (but the latter is placed by the hip same leg and connected with a tendon bar to reduce the load on the same leg by leverage)

STEP 5:

This robot is powered by 2 rechargeable 3.7V batteries in series which feed two voltage regulators to obtain fixed 5 volts with which the 12 servo motors and the microcontroller are distributed distributedly

STEP 6:

These are the connections that I used to control the 12 servomotors at 12 PWMs, as you can see in the photo the front legs are up and the back legs are down, the kicks on the right side are represented on the right side and the left ones are those of their respective side, and the pins of the microcontroller with which they are connected can be seen very clearly, example: right front leg of the M1 motor: it is connected to the PE9 pin of the STM32F401 microcontroller, and so on with the other pins

STEP 7:


The rigid segments of the legs (painted black) are made of balsa wood to be as light as possible, and as you can see in the video, the robot supports its own standing weight very well without any problem with only the force of its servomotors and the power source of the batteries that he carried with himself

STEP 8:


Now is the time to have fun, now you can implement different sequences of steps, walking, running, playing, jumping obstacles, both remotely and autonomously, it depends on what you decide to do with this fun robotic platform what is my Perro-Bot

In the firmware I support the sysctick, to generate the constant interruptions that help to form the sequences of each particular task that the robot is developing at a certain moment

Any questions, or help that you require, please let me know
and I will gladly help you, whether it be the code, mechanical design, electronics, etc.

3 Comments

an apology: I just realized that I did not upload the files correctly, if someone occupies them with pleasure ask me and I will send them to you
regards
sorry, the code:
/* Includes ------------------------------------------------------------------*/
#include "stm32f401_discovery.h"

/** @addtogroup STM32F401_Discovery_Peripheral_Examples
* @{
*/

/** @addtogroup TIM_PWM_Output
* @{
*/

/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define ADC1_DR_ADDRESS ((uint32_t)0x4001204C)

/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
__IO uint16_t ADC1ConvertedValue = 0;
__IO uint32_t ADC1ConvertedVoltage = 0;

/* Private function prototypes -----------------------------------------------*/
void ADC1_CH1_DMA_Config(void);

/* Private functions ---------------------------------------------------------*/

/**
* @brief Main program
* @param None
* @retval None
*/

#include <stdio.h>
#include "stm32f4xx.h"

volatile uint32_t msTicks; //counts 1ms timeTicks
uint8_t Com_Enable=0,Pasos=0;
uint32_t t,tiemp=0,ang=0;
uint32_t M1DaP, M1DdP, M2IdP, M2DdP, M3IdP, M3DdP, M3DaP, M2DaP, M1IdP, M1IaP, M2IaP, M3IaP;
uint32_t M1DaT1_1, M1DdT1_2, M2IdT1_3, M2DdT1_4, M3IdT3_1, M3DdT3_2, M3DaT3_3, M2DaT3_4, M1IdT4_1, M1IaT4_2, M2IaT4_3, M3IaT4_4;
void config_GPIO(void);
void Cp1(void);
void Cp2(void);
void Cp3(void);
void Cp4(void);
void Cp5(void);
void Cp6(void);
void Cp7(void);
void Cp8(void);
void Cp9(void);
void Cp10(void);
void Cp11(void);
void Cp12(void);

void config_GPIO(void)
{
GPIO_InitTypeDef GPIO_InitStructure;

/* GPIOD Periph clock enable */
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE);

/* Configure PB13 in output pushpull mode */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(GPIOB, &GPIO_InitStructure);

GPIO_ResetBits(GPIOB, GPIO_Pin_13);//Servos desenergizados
}

/*PWM ServoMotor: TIMx->CCRx = 275 1350 2350 2600
0 90 180
con 250 gira hacia manecillas reloj
con 2700 gira Anti-manecillas reloj*/
void OutPwm(void)
{
TIM1->CCR1 = M1DaT1_1; //M1 Derecho adelante
TIM1->CCR2 = M1DdT1_2; //M1 Derecho detras
TIM1->CCR3 = M2IdT1_3; //M2 Izquierdo detras
TIM1->CCR4 = M2DdT1_4; //M2 Derecho detras
TIM3->CCR1 = M3IdT3_1; //M3 Izquierdo detras
TIM3->CCR2 = M3DdT3_2; //M3 Derecho detras
TIM3->CCR3 = M3DaT3_3; //M3 Derecho adelante
TIM3->CCR4 = M2DaT3_4; //M2 Derecho adelante
TIM4->CCR1 = M1IdT4_1; //M1 Izquierdo detras
TIM4->CCR2 = M1IaT4_2; //M1 Izquierdo adelante
TIM4->CCR3 = M2IaT4_3; //M2 Izquierdo adelante
TIM4->CCR4 = M3IaT4_4; //M3 Izquierdo adelante
}

void Cont_ms()
{
Com_Enable=1;
if(Com_Enable)
{
if(M1DaT1_1<M1DaP){M1DaT1_1++;}
if(M1DaT1_1>M1DaP){M1DaT1_1--;}

if(M1DdT1_2<M1DdP){M1DdT1_2++;}
if(M1DdT1_2>M1DdP){M1DdT1_2--;}

if(M2IdT1_3<M2IdP){M2IdT1_3++;}
if(M2IdT1_3>M2IdP){M2IdT1_3--;}

if(M2DdT1_4<M2DdP){M2DdT1_4++;}
if(M2DdT1_4>M2DdP){M2DdT1_4--;}

if(M3IdT3_1<M3IdP){M3IdT3_1++;}
if(M3IdT3_1>M3IdP){M3IdT3_1--;}

if(M3DdT3_2<M3DdP){M3DdT3_2++;}
if(M3DdT3_2>M3DdP){M3DdT3_2--;}

if(M3DaT3_3<M3DaP){M3DaT3_3++;}
if(M3DaT3_3>M3DaP){M3DaT3_3--;}

if(M2DaT3_4<M2DaP){M2DaT3_4++;}
if(M2DaT3_4>M2DaP){M2DaT3_4--;}

if(M1IdT4_1<M1IdP){M1IdT4_1++;}
if(M1IdT4_1>M1IdP){M1IdT4_1--;}

if(M1IaT4_2<M1IaP){M1IaT4_2++;}
if(M1IaT4_2>M1IaP){M1IaT4_2--;}

if(M2IaT4_3<M2IaP){M2IaT4_3++;}
if(M2IaT4_3>M2IaP){M2IaT4_3--;}

if(M3IaT4_4<M3IaP){M3IaT4_4++;}
if(M3IaT4_4>M3IaP){M3IaT4_4--;}
}
}

void Parado()
{
M1DaP = 1350; //M1 Derecho adelante
M1DdP = 1350; //M1 Derecho detras
M2IdP = 1600; //M2 Izquierdo detras
M2DdP = 1000; //M2 Derecho detras
M3IdP = 1000; //M3 Izquierdo detras
M3DdP = 1800; //M3 Derecho detras
M3DaP = 1800; //M3 Derecho adelante
M2DaP = 1350; //M2 Derecho adelante
M1IdP = 1350; //M1 Izquierdo detras
M1IaP = 1350; //M1 Izquierdo adelante
M2IaP = 1350; //M2 Izquierdo adelante
M3IaP = 1000; //M3 Izquierdo adelante
}

void Sentado()
{
M1DaP = 1350; //M1 Derecho adelante
M1DdP = 1350; //M1 Derecho detras
M2IdP = 2200; //M2 Izquierdo detras
M2DdP = 500; //M2 Derecho detras
M3IdP = 2000; //M3 Izquierdo detras
M3DdP = 500; //M3 Derecho detras
M3DaP = 700; //M3 Derecho adelante
M2DaP = 500; //M2 Derecho adelante
M1IdP = 1350; //M1 Izquierdo detras
M1IaP = 1350; //M1 Izquierdo adelante
M2IaP = 2200; //M2 Izquierdo adelante
M3IaP = 2000; //M3 Izquierdo adelante
}

void Jaltras()
{
TIM1->CCR1 = 1350;//M1 Derecho adelante
M1DaP = 1350; //M1 Derecho adelante
TIM1->CCR2 = 1350;//M1 Derecho detras
M1DdP = 1350; //M1 Derecho detras
TIM1->CCR3 = 1900;//M2 Izquierdo detras
M2IdP = 1900; //M2 Izquierdo detras
TIM1->CCR4 = 750; //M2 Derecho detras
M2DdP = 750; //M2 Derecho detras
TIM3->CCR1 = 1000;//M3 Izquierdo detras
M3IdP = 1000; //M3 Izquierdo detras
TIM3->CCR2 = 1800;//M3 Derecho detras
M3DdP = 1800; //M3 Derecho detras
TIM3->CCR3 = 1800;//M3 Derecho adelante
M3DaP = 1800; //M3 Derecho adelante
TIM3->CCR4 = 925; //M2 Derecho adelante
M2DaP = 925; //M2 Derecho adelante
TIM4->CCR1 = 1350;//M1 Izquierdo detras
M1IdP = 1350; //M1 Izquierdo detras
TIM4->CCR2 = 1350;//M1 Izquierdo adelante
M1IaP = 1350; //M1 Izquierdo adelante
TIM4->CCR3 = 1775;//M2 Izquierdo adelante
M2IaP = 1775; //M2 Izquierdo adelante
TIM4->CCR4 = 1000;//M3 Izquierdo adelante
M3IaP = 1000; //M3 Izquierdo adelante
}

void Cp1()
{
M3DaT3_3=700;
M3DaP=700;
}

void Cp2()
{
M2DaT3_4=1600;
M2DaP=1600;
}

void Cp3()
{
M3DaT3_3=1800;
M3DaP=1800;
}

void Cp4()
{
M3IdT3_1=2000;
M3IdP=2000;
}

void Cp5()
{
M2IdT1_3=1100;
M2IdP=1100;
}

void Cp6()
{
M3IdT3_1=1000;
M3IdP=1000;
}

void Cp7()
{
M3IaT4_4=2000;
M3IaP=2000;
}

void Cp8()
{
M2IaT4_3=1100;
M2IaP=1100;
}

void Cp9()
{
M3IaT4_4=1000;
M3IaP=1000;
}

void Cp10()
{
M3DdT3_2=500;
M3DdP=500;
}

void Cp11()
{
M2DdT1_4=1600;
M2DdP=1600;
}

void Cp12()
{
M3DdT3_2=1800;
M3DdP=1800;
}

void Camina()
{
Parado();
/*switch(Pasos)
{
case 0:
Parado();
break;

case 1:
Cp1();
break;

case 2:
Cp2();
break;

case 3:
Cp3();
break;

case 4:
Cp4();
break;

case 5:
Cp5();
break;

case 6:
Cp6();
break;

case 7:
Cp7();
break;

case 8:
Cp8();
break;

case 9:
Cp9();
break;

case 10:
Cp10();
break;

case 11:
Cp11();
break;

case 12:
Cp12();
break;

case 13:
Jaltras();
break;
}
Pasos++;
if(Pasos==14){Pasos=0;}*/
}


// Delays number of Systicks (happens every 1 ms)
/*static void Delay(__IO uint32_t dlyTicks){
uint32_t curTicks = msTicks;
while ((msTicks - curTicks) < dlyTicks);
}*/

void setSysTick(void){
// ---------- SysTick timer (1ms) -------- //
if (SysTick_Config(SystemCoreClock / 1000)) {
// Capture error
while (1){};
}
}

void config_USART(void)
{
// Structures for configuration
GPIO_InitTypeDef GPIO_InitStructure;
USART_InitTypeDef USART_InitStructure;
NVIC_InitTypeDef NVIC_InitStruct;

// UArt Clock Enable
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);

// GPIOB Clock Enable
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOD, ENABLE);

// Initalize PD6
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5 | GPIO_Pin_6;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz; // GPIO_High_Speed
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; // Weak Pull-up for safety during startup
GPIO_Init(GPIOD, &GPIO_InitStructure);

GPIO_PinAFConfig(GPIOD, GPIO_PinSource5, GPIO_AF_USART2);
GPIO_PinAFConfig(GPIOD, GPIO_PinSource6, GPIO_AF_USART2);

// Usart Configuration
USART_InitStructure.USART_BaudRate = 9600;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_InitStructure.USART_Parity = USART_Parity_No;
USART_InitStructure.USART_StopBits = USART_StopBits_1;
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
USART_Init(USART2, &USART_InitStructure);
USART_Cmd(USART2, ENABLE);

//Enable RX interrupt
USART_ITConfig(USART2, USART_IT_RXNE, ENABLE);

/**
* Set Channel to USART1
* Set Channel Cmd to enable. That will enable USART2 channel in NVIC
* Set Both priorities to 0. This means high priority
*
* Initialize NVIC
*/
NVIC_InitStruct.NVIC_IRQChannel = USART2_IRQn;
NVIC_InitStruct.NVIC_IRQChannelCmd = ENABLE;
NVIC_InitStruct.NVIC_IRQChannelPreemptionPriority = 0;
NVIC_InitStruct.NVIC_IRQChannelSubPriority = 0;
NVIC_Init(&NVIC_InitStruct);
}

void config_PWM(void)
{
// Structures for configuration
GPIO_InitTypeDef GPIO_InitStructure;
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_OCInitTypeDef TIM_OCInitStructure;

// TIM Clock Enable
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE);

// GPIOB Clock Enable
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE);
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOD, ENABLE);
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOE, ENABLE);

// Initalize PE (TIM1)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9 | GPIO_Pin_11 | GPIO_Pin_13 | GPIO_Pin_14;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz; // GPIO_High_Speed
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; // Weak Pull-up for safety during startup
GPIO_Init(GPIOE, &GPIO_InitStructure);

// Initalize PB (TIM3)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_4 | GPIO_Pin_5;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz; // GPIO_High_Speed
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; // Weak Pull-up for safety during startup
GPIO_Init(GPIOB, &GPIO_InitStructure);

// Initalize PD (TIM4)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12 | GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz; // GPIO_High_Speed
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; // Weak Pull-up for safety during startup
GPIO_Init(GPIOD, &GPIO_InitStructure);

// Assign Alternate Functions to pins
GPIO_PinAFConfig(GPIOE, GPIO_PinSource9 , GPIO_AF_TIM1);
GPIO_PinAFConfig(GPIOE, GPIO_PinSource11, GPIO_AF_TIM1);
GPIO_PinAFConfig(GPIOE, GPIO_PinSource13, GPIO_AF_TIM1);
GPIO_PinAFConfig(GPIOE, GPIO_PinSource14, GPIO_AF_TIM1);

GPIO_PinAFConfig(GPIOB, GPIO_PinSource0, GPIO_AF_TIM3);
GPIO_PinAFConfig(GPIOB, GPIO_PinSource1, GPIO_AF_TIM3);
GPIO_PinAFConfig(GPIOB, GPIO_PinSource4, GPIO_AF_TIM3);
GPIO_PinAFConfig(GPIOB, GPIO_PinSource5, GPIO_AF_TIM3);

GPIO_PinAFConfig(GPIOD, GPIO_PinSource12, GPIO_AF_TIM4);
GPIO_PinAFConfig(GPIOD, GPIO_PinSource13, GPIO_AF_TIM4);
GPIO_PinAFConfig(GPIOD, GPIO_PinSource14, GPIO_AF_TIM4);
GPIO_PinAFConfig(GPIOD, GPIO_PinSource15, GPIO_AF_TIM4);


/* Setup TIM / PWM values
Servo Requirements: (May be different for your servo)
- 50Hz (== 20ms) PWM signal
- 1.0 - 2.0 ms Duty Cycle

1. Determine Required Timer_Freq.
TIM_Period = (Timer_Freq. / PWM_Freq) - 1

- We need a period of 20ms (or 20000µs) and our PWM_Freq = 50Hz (i.e. 1/20ms)
- See NOTES, for why we use µs
TIM_Period = 20000 - 1 = 19999 (since its 0 offset)

Timer_Freq = (TIM_Period + 1) * PWM_Freq.
Timer_Freq = (19999 + 1) * 50
Timer_Freq = 1000000 = 1MHz

2. Determine Pre-Scaler
APB1 clock frequency:
- SYS_CLK/4 when prescaler == 1 (i.e. 168MHz / 4 = 42MHz)
- SYS_CLK/2 when prescaler != 1 (i.e. 168MHz / 2 = 84MHz)

Prescaler = APB1_Freq / Timer_Freq
Prescaler = 84 MHz / 1 MHz
Prescaler = 84

For our example, we can prescale the TIM clock by 84, which gives us a Timer_Freq of 1MHz
Timer_Freq = 84 MHz / 84 = 1 MHz
So the TIMx_CNT register will increase by 1 000 000 ticks every second. When TIMx_CNT is increased by 1 that is 1 µs. So if we want a duty cycle of 1.5ms (1500 µs) then we can set our CCRx register to 1500.

NOTES:
- TIMx_CNT Register is 16 bits, i.e. we can count from 0 to (2^16)-1 = 65535
- If the period, TIMx_ARR, is greater than the max TIMx_CNT value (65535), then we need to choose a larger prescaler value in order to slow down the count.
- We use the µs for a more precise adjustment of the duty cycle

*/
uint16_t PrescalerValue = (uint16_t) 84;

// Time Base Configuration
TIM_TimeBaseStructure.TIM_Period = 19999;
TIM_TimeBaseStructure.TIM_Prescaler = PrescalerValue;
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;

TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
TIM_TimeBaseInit(TIM4, &TIM_TimeBaseStructure);

TIM_CtrlPWMOutputs(TIM1, ENABLE);

// Common TIM Settings
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_Pulse = 0; // Initial duty cycle
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;

// T1 CH1
TIM_OC1Init(TIM1, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(TIM1, TIM_OCPreload_Enable);
// T1 CH2
TIM_OC2Init(TIM1, &TIM_OCInitStructure);
TIM_OC2PreloadConfig(TIM1, TIM_OCPreload_Enable);
// T1 CH3
TIM_OC3Init(TIM1, &TIM_OCInitStructure);
TIM_OC3PreloadConfig(TIM1, TIM_OCPreload_Enable);
// T1 CH4
TIM_OC4Init(TIM1, &TIM_OCInitStructure);
TIM_OC4PreloadConfig(TIM1, TIM_OCPreload_Enable);

// T3 CH1
TIM_OC1Init(TIM3, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable);
// T3 CH2
TIM_OC2Init(TIM3, &TIM_OCInitStructure);
TIM_OC2PreloadConfig(TIM3, TIM_OCPreload_Enable);
// T3 CH3
TIM_OC3Init(TIM3, &TIM_OCInitStructure);
TIM_OC3PreloadConfig(TIM3, TIM_OCPreload_Enable);
// T3 CH4
TIM_OC4Init(TIM3, &TIM_OCInitStructure);
TIM_OC4PreloadConfig(TIM3, TIM_OCPreload_Enable);

// T4 CH1
TIM_OC1Init(TIM4, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(TIM4, TIM_OCPreload_Enable);
// T4 CH2
TIM_OC2Init(TIM4, &TIM_OCInitStructure);
TIM_OC2PreloadConfig(TIM4, TIM_OCPreload_Enable);
// T4 CH3
TIM_OC3Init(TIM4, &TIM_OCInitStructure);
TIM_OC3PreloadConfig(TIM4, TIM_OCPreload_Enable);
// T4 CH4
TIM_OC4Init(TIM4, &TIM_OCInitStructure);
TIM_OC4PreloadConfig(TIM4, TIM_OCPreload_Enable);

TIM_ARRPreloadConfig(TIM1, ENABLE);
TIM_ARRPreloadConfig(TIM3, ENABLE);
TIM_ARRPreloadConfig(TIM4, ENABLE);

// Start timer
TIM_Cmd(TIM1, ENABLE);
TIM_Cmd(TIM3, ENABLE);
TIM_Cmd(TIM4, ENABLE);

// //Sentado
TIM1->CCR1 = 1350;//M1 Derecho adelante
M1DaP = 1350; //M1 Derecho adelante
TIM1->CCR2 = 1350;//M1 Derecho detras
M1DdP = 1350; //M1 Derecho detras
TIM1->CCR3 = 2200;//M2 Izquierdo detras
M2IdP = 2200; //M2 Izquierdo detras
TIM1->CCR4 = 500; //M2 Derecho detras
M2DdP = 500; //M2 Derecho detras
TIM3->CCR1 = 2000;//M3 Izquierdo detras
M3IdP = 2000; //M3 Izquierdo detras
TIM3->CCR2 = 500; //M3 Derecho detras
M3DdP = 500; //M3 Derecho detras
TIM3->CCR3 = 700; //M3 Derecho adelante
M3DaP = 700; //M3 Derecho adelante
TIM3->CCR4 = 500; //M2 Derecho adelante
M2DaP = 500; //M2 Derecho adelante
TIM4->CCR1 = 1350;//M1 Izquierdo detras
M1IdP = 1350; //M1 Izquierdo detras
TIM4->CCR2 = 1350;//M1 Izquierdo adelante
M1IaP = 1350; //M1 Izquierdo adelante
TIM4->CCR3 = 2200;//M2 Izquierdo adelante
M2IaP = 2200; //M2 Izquierdo adelante
TIM4->CCR4 = 2000;//M3 Izquierdo adelante
M3IaP = 2000; //M3 Izquierdo adelante
}


int main(void)
{
setSysTick();
SystemCoreClockUpdate();
SysTick_Config(SystemCoreClock);
config_GPIO();
//ADC1_CH1_DMA_Config();
//ADC_SoftwareStartConv(ADC1);
config_PWM();
Sentado();
config_USART();

/*PWM ServoMotor: TIMx->CCRx = 275 1350 2350 2600
0 90 180
con 250 gira hacia manecillas reloj
con 2700 gira Anti-manecillas reloj
*/
while (1)
{
// convert the ADC value (from 0 to 0xFFF) to a voltage value (from 0V to 3.0V)
//ADC1ConvertedVoltage = ADC1ConvertedValue *3000/0xFFF;
//ang=(ADC1ConvertedValue/2);
//TIM3->CCR4 = 1000;//ang;//PB1
//2600-ang;//PB0
// for(tiemp=275;tiemp<=2350;tiemp++)
// {
// TIM3->CCR4 = tiemp;
// for(t=0;t<=1000000000;t++){;}
// }
/*for(ang=500;ang<2600;ang++)
{
TIM3->CCR4 = ang;
TIM3->CCR3 = 500;
for(tiemp=0;tiemp<10000;tiemp++){;}
}
for(ang=500;ang<2600;ang++)
{
TIM3->CCR4 = 2600;
TIM3->CCR3 = ang;
for(tiemp=0;tiemp<10000;tiemp++){;}
}
for(ang=500;ang<2600;ang++)
{
TIM3->CCR4 = 2600-ang;
TIM3->CCR3 = 2600;
for(tiemp=0;tiemp<10000;tiemp++){;}
}
for(ang=500;ang<2600;ang++)
{
TIM3->CCR4 = 500;
TIM3->CCR3 = 2600-ang;
for(tiemp=0;tiemp<10000;tiemp++){;}
}

for(ang=500;ang<2600;ang++)
{
TIM3->CCR4 = ang;
TIM3->CCR3 = ang;
for(tiemp=0;tiemp<10000;tiemp++){;}
}
for(ang=500;ang<2600;ang++)
{
TIM3->CCR4 = 2600-ang;
TIM3->CCR3 = 2600-ang;
for(tiemp=0;tiemp<10000;tiemp++){;}
}*/

/*
TIM3->CCR4 = 500;//500
for(tiemp=0;tiemp<10000000;tiemp++){;}
TIM3->CCR4 = 1500;
for(tiemp=0;tiemp<10000000;tiemp++){;}
TIM3->CCR4 = 2600;
for(tiemp=0;tiemp<10000000;tiemp++){;}*/
}
//return 0;
}

void ADC1_CH1_DMA_Config(void)
{
ADC_InitTypeDef ADC_InitStructure;
ADC_CommonInitTypeDef ADC_CommonInitStructure;
DMA_InitTypeDef DMA_InitStructure;
GPIO_InitTypeDef GPIO_InitStructure;

/* Enable ADC3, DMA2 and GPIO clocks ****************************************/
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA2 | RCC_AHB1Periph_GPIOA, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);

/* DMA2 Stream0 channel0 configuration **************************************/
DMA_InitStructure.DMA_Channel = DMA_Channel_0;
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)ADC1_DR_ADDRESS;
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)&ADC1ConvertedValue;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
DMA_InitStructure.DMA_BufferSize = 1;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable;
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_HalfFull;
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
DMA_Init(DMA2_Stream0, &DMA_InitStructure);
DMA_Cmd(DMA2_Stream0, ENABLE);

/* Configure ADC1 Channel12 pin as analog input ******************************/
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ;
GPIO_Init(GPIOA, &GPIO_InitStructure);

/* ADC Common Init **********************************************************/
ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent;
ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div2;
ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled;
ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles;
ADC_CommonInit(&ADC_CommonInitStructure);

/* ADC1 Init ****************************************************************/
ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b;
ADC_InitStructure.ADC_ScanConvMode = DISABLE;
ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;
ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1;
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
ADC_InitStructure.ADC_NbrOfConversion = 1;
ADC_Init(ADC1, &ADC_InitStructure);

/* ADC1 regular channel12 configuration *************************************/
ADC_RegularChannelConfig(ADC1, ADC_Channel_1, 1, ADC_SampleTime_3Cycles);

/* Enable DMA request after last transfer (Single-ADC mode) */
ADC_DMARequestAfterLastTransferCmd(ADC1, ENABLE);

/* Enable ADC1 DMA */
ADC_DMACmd(ADC1, ENABLE);

/* Enable ADC1 */
ADC_Cmd(ADC1, ENABLE);
}



/**
* @brief Configure the TIM3 Ouput Channels.
* @param None
* @retval None
*/



#ifdef USE_FULL_ASSERT

/**
* @brief Reports the name of the source file and the source line number
* where the assert_param error has occurred.
* @param file: pointer to the source file name
* @param line: assert_param error line source number
* @retval None
*/
void assert_failed(uint8_t* file, uint32_t line)
{
/* User can add his own implementation to report the file name and line number,
ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */

while (1)
{}
}
#endif

/**
* @}
*/

/**
* @}
*/

/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/