The robotic arm detects the plastic and metal bottles and place each material in the target position.
This arm can be employed in recycling plants, you put metals in one place and other materials in another.
You wanna know how? let's go through this case study:
This arm has four degrees of freedom (four rotational joints) each joint is driven by a DC motor and there is a linear resistor for every joint to determine the current position.
1 - DC MOTOR:
We used four DC MOTOR (12 volt) to move the joints.
2-Linear resistor:
There are four resistors (5.5 kOhm) installed on the axis of each motor responsible for determining the current position of each joint.
3-DevKit HG0B1CEU:
Short Description:
- utilizes the STM32G0B1CEU6 (Mcu) ARM Cortex-M0+ core, operating at speeds of up to 64 megahertz, featuring a wide range of communication interfaces: UART, SPI, I2C, USB, and more.
- incorporates a built-in DC-DC converter for efficient power generation.
- includes ADC and DAC units for high-precision analog-to-digital and digital-to-analog conversions.
- boasts low power consumption to optimize battery life.
3 - H-bridge(H18R1x) Module:
We can use the H18R1x module to control the motor (start, stop, forward and reverse direction, or speed control).H18R1xis a dual H-bridge motor driver module based on L298 and STM32G0 MCU.The H-bridge motor driver module enables motors to be driven in two directions (forward and reverse). With such a module, the motor can be made to rotate, and the polarity of the motor’s power supply can be reversed to change the direction of rotation. If necessary, the motor can also be braked.
4- STLINK(H40Rx):
The H40Rx is Hexabitz programming module that includes STLINK-V3MODS for stand-alone debugging and programming.
Used for programming (Upload / download.hex /.bin files) STM32 microcontrollers (Hexabitz modules and other MCUs),
5- Power Module (H03R00):
H03R00 is a compact DC-DC buck power supply with a 3.3V/1A DC output and 5-40V DC input. Its function is to feed the matrix of other modules.
6- Capacitive sensor:
This sensor detects the insulating material passing in front of it.
7- Inductive sensor:
This sensor determines the type of material if it is metal or otherwise.
8-Belt Conveyor:
Its function is to carry the materials to be sorted by the installed capacitive and inductive sensors and it is driven by H18R1x.
The dynamic model of arm:The dynamic model of arm characterizes the motion taking into account the forces and moments acting on the joints and the movement produced by the robot.
In order to control any system, mathematical equations must be found to describe the system.
The more accurate the mathematical equations, the more reliable, accurate and effective the controller will be!
We found the dynamic model of the arm using two methods:
1- Mathematical method.
2- Engineering method.
1-Mathematical model:
The mathematical model was obtained using the Euler-Lagrange method:
2- Engineering method:
The engineering model of the robot obtained after drawing the arm using SOLID WORK software and exported to Matlab software.
The system in the open loop:
System response in the open loop:
We notice that the system is stable in the open loop.
Control System:PID Controller:
the Proportional-Integral-Derivative (PID) controller. The PID controller is widely spread because it is very understandable and because it is quite effective somewhat. One attraction of the PID controller is that all engineers understand conceptually differentiation and integration, so they can implement the control system even without a deep understanding of control theory. Further, even though the compensator is simple, it is quite sophisticated in that it captures the history of the system (through integration) and anticipates the future behavior of the system (through differentiation). We will discuss the effect of each of the PID parameters on the dynamics of a closed-loop system
PID controller is given by the equation:
Where e(t)=r(t)-y(t) is the error equation, Kp, TI and Td are the proportional gain, integral time constant and differential time constant respectively.
There are a number of methods for tuning a PID controller, some of which are based on time response (transient), the best known are Ziegler-Nichols, Cohen-Coon, trial-and-error method (manual calibration), and some are based on frequency analysis, and in this project we will use the manual calibration method
We have used the following table which made it easier for us to calibrate manually
For more information about PID controller, please visit:
We used an outer loop (PD controller) for position control and an inner loop (PI controller) for speed control
We have plugged the modules together (soldering) and put them into 3D shape, then assembled the elements on the board where the main Mcu (DevKit ) will process the data coming from the sensors and send control commands to H-bridge modules via the UART communication port. H-bridge modules drive arm motors to move to the desired position, we also added optocoupler to transmit the sensor signal to the Mcu.
Initially we will number modules 1 to 3 to create a file of static topology and upload code to the processors so that they can communicate with each other and know their neighbors (Bitz Operating System - BOS terms)
we will enter the topology settings for code generation using the STM32CubeIDE software tool in the topology file as follows:
#define __N 3 // Number of array modules
// Array modules
#define _mod1 1<<3
#define _mod2 2<<3
#define _mod3 3<<3
// Topology
static uint16_t array[__N ][7] ={
{_H18R1, 0, _mod2 | P2, 0, 0, 0, 0}, // Module 1
{_H18R1, 0, _mod1 | P2, _mod3 | P3, 0, 0, 0}, // Module 2
{_H18R1, 0, 0, _mod2 | P3, 0, 0, 0},
};
Now that we have numbered the array of modules, we will configure the serial ports in the same file (topology.h):
// Configurations for duplex serial ports
#if ( _module == 1 )
#define _H18R1 1
#define _P1pol_normal 1
#define _P2pol_normal 1
#define _P3pol_normal 1
#define _P4pol_normal 1
#define _P5pol_normal 1
#define _P6pol_normal 1
#endif
#if ( _module == 2 )
#define _H18R1 1
#define _P1pol_normal 1
#define _P2pol_reversed 1
#define _P3pol_reversed 1
#define _P4pol_normal 1
#define _P5pol_normal 1
#define _P6pol_normal 1
#endif
#if ( _module == 3 )
#define _H18R1 1
#define _P1pol_normal 1
#define _P2pol_normal 1
#define _P3pol_normal 1
#define _P4pol_normal 1
#define _P5pol_normal 1
#define _P6pol_normal 1
#endif
For more information on how to create a fixed topology, you can always visit
Make a Pre-built Array Topology File – Hexabitz
Secondly, we will define variables and constants in the main Mcu:
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __ROBOT_H
#define __ROBOT_H
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32g0xx_hal.h"
#define metal 1 // The material is metal
#define not_metal 2 // The material is not metal
#define pi 3.14
#define theta1_0 0 // 0 degree for base
#define theta1_90 1.57 // 90 degree for base
#define theta1_180 3.14 // 180 degree for base
#define theta2_down 1.48 // down for shoulder (pi/2)
#define theta2_up 2.155 // up for shoulder (3pi/4)
#define theta3_down 1.80 // down for shoulder
#define theta3_up 2.20 // up for shoulder
#define theta4_down 2.0 // down for shoulder
#define theta4_up 1.40 // up for shoulder
#define theta2_down2 1.15 // down for shoulder (pi/2)
#define theta4_up2 1.25 // up for shoulder
#define min_velocity_1 7 // 7 % PWM
#define min_velocity_2_up 10 // 10 % PWM
#define min_velocity_2_down 6 // 6 % PWM
#define min_velocity_3_up 10 // 10 % PWM
#define min_velocity_3_down 5 // 5 % PWM
#define min_velocity_4_up 6 // 6 % PWM
#define min_velocity_4_down 6 // 6 % PWM
#define done_classification 0 // fished the operation
#define arm_is_down 1 // Arm is down
#define arm_is_up 2 // Arm is down
#define catch 3 // end_effector is closed (catch)
// parameter for P controller
#define kp11 6.0 // kp for P controller motor1
#define kp12 6.0 // kp for P controller motor2
#define kp13 6.5 // kp for P controller motor3
#define kp14 6.0 // kp for P controller motor4
// parameter for PI controller
#define kp1 17.0 // kp for PI controller motor1
#define kp2 15.0 // kp for PI controller motor2
#define kp3 15.0 // kp for PI controller motor3
#define kp4 10.0 // kp for PI controller motor4
#define ki1 10.0 // ki for PI controller motor1
#define ki2 5.0 // ki for PI controller motor2
#define ki3 5.0 // ki for PI controller motor3
#define ki4 20.0 // ki for PI controller motor4 //25
float P(float error ,float KP);
float PI(float error, float KP, float KI, float Ts);
#ifdef __cplusplus
}
#endif
#endif /* ROBOT_H */
Thirdly, we will write a function to calculate the error equation for the P and PI controller in main.c file in the main Mcu as follows:
float P(float error , float KP)
{
float out_P;
out_P = KP*error ;
if(out_P > pi/2) // Max speed = pi/2 (rad/s)
out_P = pi/2;
else if(out_P < -pi/2)
out_P = -pi/2;
if(error < 0.05 && error > -0.05)
out_P = 0.0;
return out_P;
}
float PI(float error, float KP, float KI, float Ts)
{
static float error_previous,sum ;
float probortional, integral, out_PI ;
integral = KI*(error+error_previous)*Ts;
if(integral > 5.0)
integral = 5.0;
else if(integral < -5.0)
integral = -5.0;
probortional = KP*error;
out_PI = probortional + integral;
error_previous = error;
if(out_PI > 100.0)
out_PI = 100.0;
else if(out_PI < -100.0)
out_PI = -100.0;
return out_PI;
}
Now we will create the UART communication channel between the main Mcu and H18R1x module and write this part of the code in the main Mcu:
uint8_t index = 0;
uint8_t index_now = 0;
uint8_t DataRecieve[4];
uint8_t i = 0;
uint8_t j = 0;
uint8_t pwm1 = 0, pwm2 = 0, pwm3 = 0, pwm4 = 0;
/* User Task */
void UserTask(void *argument) {
while (1) {
index = MSG_RX_BUF_SIZE - (DMA1_Channel3->CNDTR);
if (index == index_now)
continue;
index_now = index - 10; // 10 is number of sent bytes
if (index_now < 0)
index_now = 0;
end_effector[0] = (char) (UARTRxBuf[2][index_now]);
index_now += 1;
conveyor[0] = (char) (UARTRxBuf[2][index_now]);
index_now += 1;
for (j = 0; j < 4; j++) {
direction[j] = (char) (UARTRxBuf[2][index_now]);
index_now += 1;
}
for (i = 0; i < 4; i++) {
DataRecieve[i] = (uint8_t)(UARTRxBuf[2][index_now]);
index_now += 1;
}
pwm1 = (uint8_t) DataRecieve[0];
pwm2 = (uint8_t) DataRecieve[1];
pwm3 = (uint8_t) DataRecieve[2];
pwm4 = (uint8_t) DataRecieve[3];
At the end, we will process the data received from the sensors and send the necessary data to the Modules in order to move the arm and this process will be carried out by the main Mcu:
char direction[4];
char end_effector[1];
char conveyor[1];
// MotorA1 ON / OFF
if (direction[0] == 's' || pwm1 < 2) {
Turn_OFF(MotorA);
} else if (direction[0] == 'f') {
Turn_PWM(forward, pwm1, MotorA);
} else if (direction[0] == 'b') {
Turn_PWM(backward, pwm1, MotorA);
}
// MotorB1 ON / OFF
if (direction[1] == 's' || pwm2 < 2) {
Turn_OFF(MotorB);
} else if (direction[1] == 'f') {
Turn_PWM(forward, pwm2, MotorB);
} else if (direction[1] == 'b') {
Turn_PWM(backward, pwm2, MotorB);
}
// MotorA2 ON / OFF
if (direction[2] == 's' || pwm3 < 2) {
messageParams[0] = 1; //MotorA Module_2
SendMessageToModule(2, CODE_H18R1_Turn_OFF, 1);
} else if (direction[2] == 'f') {
messageParams[0] = 1; // forward
messageParams[1] = pwm3; // Duty cycle
messageParams[2] = 1; //MotorA
SendMessageToModule(2, CODE_H18R1_Turn_PWM, 3);
} else if (direction[2] == 'b') {
messageParams[0] = 2; // backward
messageParams[1] = pwm3; // Duty cycle
messageParams[2] = 1; //MotorA
SendMessageToModule(2, CODE_H18R1_Turn_PWM, 3);
}
// MotorB2 ON / OFF
if (direction[3] == 's' || pwm4 < 2) {
messageParams[0] = 2; //MotorB Module_2
SendMessageToModule(2, CODE_H18R1_Turn_OFF, 1);
} else if (direction[3] == 'f') {
messageParams[0] = 1; // forward
messageParams[1] = pwm4; // Duty cycle
messageParams[2] = 2; //MotorB
SendMessageToModule(2, CODE_H18R1_Turn_PWM, 3);
} else if (direction[3] == 'b') {
messageParams[0] = 2; // backward
messageParams[1] = pwm4; // Duty cycle
messageParams[2] = 2; //MotorB
SendMessageToModule(2, CODE_H18R1_Turn_PWM, 3);
}
// End_effector (Module 3 , MotorA)
if (end_effector[0] == 'c') {
messageParams[0] = 1; // forward
messageParams[1] = 50; // Duty cycle
messageParams[2] = 1; //MotorA
SendMessageToModule(3, CODE_H18R1_Turn_PWM, 3);
} else if (end_effector[0] == 'o') {
messageParams[0] = 1; //MotorA Module_3
SendMessageToModule(3, CODE_H18R1_Turn_OFF, 1);
}
// Conveyor belt (Module 3 , MotorB)
if (conveyor[0] == 'n') {
messageParams[0] = 1; //forward
messageParams[1] = 2; //MotorB Module_3
SendMessageToModule(3, CODE_H18R1_Turn_ON, 2);
} else if (conveyor[0] == 's') {
messageParams[0] = 2; //MotorB Module_3
SendMessageToModule(3, CODE_H18R1_Turn_OFF, 1);
}
Delay_ms(10);
}
}
► ResultsHere are some live experiments of our project. Have fun looking at them! More interesting projects will be presented in Hexabitz Channel.
Comments
Please log in or sign up to comment.