git repo: https://github.com/StanLinCat/matlab_robot_arm_control

Project Overview

This is a small MATLAB project implementing trajectory tracking control for a 2D two-link robotic arm. It employs the Slotine and Li adaptive control algorithm (Adaptive Control based on Slotine & Li’s method), enabling the end-effector to precisely follow a circular reference trajectory.

Key Features

  • Dynamic model of a two-link robotic arm built with realistic physical parameters (mass, inertia, gravity, etc.)
  • Designed circular desired trajectory (radius 0.2 m, centered at (0.8, 1))
  • Computed desired joint angles, angular velocities, and angular accelerations using inverse kinematics
  • Implemented Slotine and Li adaptive controller, including sliding surface, regressor matrix, and parameter adaptation law
  • Generated plots for trajectory error, joint angles, and control torques, along with a robotic arm motion animation

Here are some representative simulation results:

MATLAB simulation result plots

Key Code Snippets

1. Parameter Setup and Desired Trajectory (Main script excerpt)

m1 = 0.5; m2 = 0.5;     % Link masses (kg)
L1 = 0.75; L2 = 0.75;   % Link lengths (m)
g = 9.81;

% Circular desired trajectory (radius 0.2 m)
xd(i) = 0.8 + 0.2*cos(-pi/2 + pi/5*t(i));
yd(i) = 1 + 0.2*sin(-pi/2 + pi/5*t(i));

2. Inverse Kinematics for Desired Joint Angles (Main script)

q2d(i) = acos((xd(i)^2 + yd(i)^2 - L1^2 - L2^2)/(2*L1*L2));
q1d(i) = atan(yd(i)/xd(i)) - atan((L2*sin(q2d(i)))/(L1 + L2*cos(q2d(i))));

3. Core of Slotine and Li Controller (System subroutine)

% Sliding surface and auxiliary variables
s = e_d + Lambda*e;
v = qd_d - Lambda*e;
v_d = qd_dd - Lambda*e_d;

% Control torque
tao = Y*p_hat - kd*s;

% Parameter adaptation law
qp(7:12,1) = -inv(gamma)*Y'*s;  % Adaptive update of estimated dynamic parameters

4. Forward Kinematics of End-Effector (Used for plotting and animation)

x(i) = L1*cos(q1) + L2*cos(q1 + q2);
y(i) = L1*sin(q1) + L2*sin(q1 + q2);

Project File Structure

  • Main script: Parameter setup, ode45 integration, and result plotting
  • System subroutine (Slotine_and_Lisys.m): Dynamic equations and controller implementation
  • Animation script: Generates link motion animation and displays end-effector trajectory

This project is an excellent practical example for learning robot dynamics and adaptive control. The simulation results show that the end-effector trajectory closely matches the desired circular path, with smooth and stable control performance.

Failed controller

The system’s transient response was too abrupt, potentially causing an impact.

Updated:

Leave a comment