Skip to content
Snippets Groups Projects
Commit dbc80937 authored by Mahmoud Wagih's avatar Mahmoud Wagih
Browse files

local files

parents
No related branches found
No related tags found
No related merge requests found
Showing with 877 additions and 0 deletions
/*
* Antenna measurement system. Arduino controller for Braccio robotic arm.
* 19th April 2021
* Thomas Moody
*/
#include <Braccio.h>
#include <Servo.h>
Servo base;
Servo shoulder;
Servo elbow;
Servo wrist_rot;
Servo wrist_ver;
Servo gripper;
const int buffer_size = 6;
byte input_buffer[buffer_size];
void setup() {
Serial.begin(9600);
Braccio.begin();
}
void loop() {
/*
Step Delay: a milliseconds delay between the movement of each servo. Allowed values from 10 to 30 msec.
M1=base degrees. Allowed values from 0 to 180 degrees
M2=shoulder degrees. Allowed values from 15 to 165 degrees
M3=elbow degrees. Allowed values from 0 to 180 degrees
M4=wrist vertical degrees. Allowed values from 0 to 180 degrees
M5=wrist rotation degrees. Allowed values from 0 to 180 degrees
M6=gripper degrees. Allowed values from 10 to 73 degrees. 10: the toungue is open, 73: the gripper is closed.
Shoulder (base azimuth);
(step delay, M1, M2, M3, M4, M5, M6);
*/
if(Serial.available()) {
Serial.readBytes(input_buffer, buffer_size);
Braccio.ServoMovement(10, input_buffer[0], input_buffer[1], input_buffer[2], input_buffer[3], input_buffer[4], input_buffer[5]);
Serial.write(input_buffer, buffer_size);
}
}
/*
Braccio.cpp - board library Version 2.0
Written by Andrea Martino and Angelo Ferrante
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "Braccio.h"
extern Servo base;
extern Servo shoulder;
extern Servo elbow;
extern Servo wrist_rot;
extern Servo wrist_ver;
extern Servo gripper;
extern int step_base = 0;
extern int step_shoulder = 45;
extern int step_elbow = 180;
extern int step_wrist_rot = 180;
extern int step_wrist_ver = 90;
extern int step_gripper = 10;
_Braccio Braccio;
//Initialize Braccio object
_Braccio::_Braccio() {
}
/**
* Braccio initialization and set intial position
* Modifing this function you can set up the initial position of all the
* servo motors of Braccio
* @param soft_start_level: default value is 0 (SOFT_START_DEFAULT)
* You should set begin(SOFT_START_DISABLED) if you are using the Arm Robot shield V1.6
* SOFT_START_DISABLED disable the Braccio movements
*/
unsigned int _Braccio::begin(int soft_start_level) {
//Calling Braccio.begin(SOFT_START_DISABLED) the Softstart is disabled and you can use the pin 12
if(soft_start_level!=SOFT_START_DISABLED){
pinMode(SOFT_START_CONTROL_PIN,OUTPUT);
digitalWrite(SOFT_START_CONTROL_PIN,LOW);
}
// initialization pin Servo motors
base.attach(11);
shoulder.attach(10);
elbow.attach(9);
wrist_rot.attach(6);
wrist_ver.attach(5);
gripper.attach(3);
//For each step motor this set up the initial degree
base.write(0);
shoulder.write(40);
elbow.write(180);
wrist_ver.write(170);
wrist_rot.write(0);
gripper.write(73);
//Previous step motor position
step_base = 0;
step_shoulder = 40;
step_elbow = 180;
step_wrist_ver = 170;
step_wrist_rot = 0;
step_gripper = 73;
if(soft_start_level!=SOFT_START_DISABLED)
_softStart(soft_start_level);
return 1;
}
/*
Software implementation of the PWM for the SOFT_START_CONTROL_PIN,HIGH
@param high_time: the time in the logic level high
@param low_time: the time in the logic level low
*/
void _Braccio::_softwarePWM(int high_time, int low_time){
digitalWrite(SOFT_START_CONTROL_PIN,HIGH);
delayMicroseconds(high_time);
digitalWrite(SOFT_START_CONTROL_PIN,LOW);
delayMicroseconds(low_time);
}
/*
* This function, used only with the Braccio Shield V4 and greater,
* turn ON the Braccio softly and save it from brokes.
* The SOFT_START_CONTROL_PIN is used as a software PWM
* @param soft_start_level: the minimum value is -70, default value is 0 (SOFT_START_DEFAULT)
*/
void _Braccio::_softStart(int soft_start_level){
long int tmp=millis();
while(millis()-tmp < LOW_LIMIT_TIMEOUT)
_softwarePWM(80+soft_start_level, 450 - soft_start_level); //the sum should be 530usec
while(millis()-tmp < HIGH_LIMIT_TIMEOUT)
_softwarePWM(75 + soft_start_level, 430 - soft_start_level); //the sum should be 505usec
digitalWrite(SOFT_START_CONTROL_PIN,HIGH);
}
/**
* This functions allow you to control all the servo motors
*
* @param stepDelay The delay between each servo movement
* @param vBase next base servo motor degree
* @param vShoulder next shoulder servo motor degree
* @param vElbow next elbow servo motor degree
* @param vWrist_ver next wrist rotation servo motor degree
* @param vWrist_rot next wrist vertical servo motor degree
* @param vgripper next gripper servo motor degree
*/
int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,int vWrist_ver, int vWrist_rot, int vgripper) {
// Check values, to avoid dangerous positions for the Braccio
if (stepDelay > 30) stepDelay = 30;
if (stepDelay < 10) stepDelay = 10;
if (vBase < 0) vBase=0;
if (vBase > 180) vBase=180;
if (vShoulder < 15) vShoulder=15;
if (vShoulder > 165) vShoulder=165;
if (vElbow < 0) vElbow=0;
if (vElbow > 180) vElbow=180;
if (vWrist_ver < 0) vWrist_ver=0;
if (vWrist_ver > 180) vWrist_ver=180;
if (vWrist_rot > 180) vWrist_rot=180;
if (vWrist_rot < 0) vWrist_rot=0;
if (vgripper < 10) vgripper = 10;
if (vgripper > 73) vgripper = 73;
int exit = 1;
//Until the all motors are in the desired position
while (exit)
{
//For each servo motor if next degree is not the same of the previuos than do the movement
if (vBase != step_base)
{
base.write(step_base);
//One step ahead
if (vBase > step_base) {
step_base++;
}
//One step beyond
if (vBase < step_base) {
step_base--;
}
}
if (vShoulder != step_shoulder)
{
shoulder.write(step_shoulder);
//One step ahead
if (vShoulder > step_shoulder) {
step_shoulder++;
}
//One step beyond
if (vShoulder < step_shoulder) {
step_shoulder--;
}
}
if (vElbow != step_elbow)
{
elbow.write(step_elbow);
//One step ahead
if (vElbow > step_elbow) {
step_elbow++;
}
//One step beyond
if (vElbow < step_elbow) {
step_elbow--;
}
}
if (vWrist_ver != step_wrist_rot)
{
wrist_rot.write(step_wrist_rot);
//One step ahead
if (vWrist_ver > step_wrist_rot) {
step_wrist_rot++;
}
//One step beyond
if (vWrist_ver < step_wrist_rot) {
step_wrist_rot--;
}
}
if (vWrist_rot != step_wrist_ver)
{
wrist_ver.write(step_wrist_ver);
//One step ahead
if (vWrist_rot > step_wrist_ver) {
step_wrist_ver++;
}
//One step beyond
if (vWrist_rot < step_wrist_ver) {
step_wrist_ver--;
}
}
if (vgripper != step_gripper)
{
gripper.write(step_gripper);
if (vgripper > step_gripper) {
step_gripper++;
}
//One step beyond
if (vgripper < step_gripper) {
step_gripper--;
}
}
//delay between each movement
delay(stepDelay);
//It checks if all the servo motors are in the desired position
if ((vBase == step_base) && (vShoulder == step_shoulder)
&& (vElbow == step_elbow) && (vWrist_ver == step_wrist_rot)
&& (vWrist_rot == step_wrist_ver) && (vgripper == step_gripper)) {
step_base = vBase;
step_shoulder = vShoulder;
step_elbow = vElbow;
step_wrist_rot = vWrist_ver;
step_wrist_ver = vWrist_rot;
step_gripper = vgripper;
exit = 0;
} else {
exit = 1;
}
}
}
/*
Braccio.h - board library Version 2.0
Written by Andrea Martino and Angelo Ferrante
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef BRACCIO_H_
#define BRACCIO_H_
#include <Arduino.h>
#include <Servo.h>
// You should set begin(SOFT_START_DISABLED) if you are using the Arm Robot shield V1.6
#define SOFT_START_DISABLED -999
//The default value for the soft start
#define SOFT_START_DEFAULT 0
//The software PWM is connected to PIN 12. You cannot use the pin 12 if you are using
//a Braccio shield V4 or newer
#define SOFT_START_CONTROL_PIN 12
//Low and High Limit Timeout for the Software PWM
#define LOW_LIMIT_TIMEOUT 2000
#define HIGH_LIMIT_TIMEOUT 6000
class _Braccio {
public:
_Braccio();
/**
* Braccio initializations and set intial position
* Modifing this function you can set up the initial position of all the
* servo motors of Braccio
*@param soft_start_level: the minimum value is -70, default value is 0 (SOFT_START_DEFAULT)
* You should set begin(SOFT_START_DISABLED) if you are using the Arm Robot shield V1.6
*/
unsigned int begin(int soft_start_level=SOFT_START_DEFAULT);
/**
* This function allow the user to control all the servo motors in the Braccio
*/
int ServoMovement(int delay, int Vbase,int Vshoulder, int Velbow, int Vwrist_ver, int Vwrist_rot, int Vgripper);
private:
/*
* This function, used only with the Braccio Shield V4 and greater,
* turn ON the Braccio softly and save Braccio from brokes.
* The SOFT_START_CONTROL_PIN is used as a software PWM
* @param soft_start_level: the minimum value is -70, , default value is 0 (SOFT_START_DEFAULT)
*/
void _softStart(int soft_start_level);
/*
* Software implementation of the PWM for the SOFT_START_CONTROL_PIN,HIGH
* @param high_time: the time in the logic level high
* @param low_time: the time in the logic level low
*/
void _softwarePWM(int high_time, int low_time);
};
extern _Braccio Braccio;
#endif // BRACCIO_H_
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Setup: %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
% Precondition: Installed R&S VISA 5.11.0 or later with R&S VISA.NET
clear;
close all;
clc;
try
assemblyCheck = NET.addAssembly('Ivi.Visa');
catch
error('Error loading .NET assembly Ivi.Visa');
end
resourceString1 = 'TCPIP::192.168.2.2::INSTR'; % Standard LAN connection (also called VXI-11)
scope = Ivi.Visa.GlobalResourceManager.Open(resourceString1); % Opening VISA session to the instrument
scope.Clear()
scope.RawIO.Write(['*IDN?' newline]); % LineFeed character at the end (newline character)
idnResponse = char(scope.RawIO.ReadString()); % Store *IDN? query response from VNA
s = serial('COM4','BaudRate',9600); % Serial settings - change COM port as required
fopen(s); % Open the serial session
pause(10); % Waiting for Braccio.begin() on Arduino to complete
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
deltaTheta = 5;
deltaPhi = 5;
deltaFreq = 100e6;
Theta = 0:deltaTheta:180;
Phi = (-90:deltaPhi:90)';
%
%%%%%%% Set your frequency range %%%%%%%%%%
%
Freq = 2.0e9:deltaFreq:4.0e9;
%Braccio Hemisphere 1 Co-Polarization
radData1_CoPol = zeros(length(Phi),length(Theta),length(Freq));
%Braccio Hemisphere 2 Co-Polarization
radData2_CoPol = zeros(length(Phi),length(Theta),length(Freq));
%Braccio Hemisphere 1 Cross Polarization
radData1_XPol = zeros(length(Phi),length(Theta),length(Freq));
%Braccio Hemisphere 2 Cross Polarization
radData2_XPol = zeros(length(Phi),length(Theta),length(Freq));
setup(scope,Freq); % Setup the VNA
pause(2);
%ensure Braccio is at starting point
move(s,1,1);
pause(2);
%Measure hemisphere 1
for i = 1:length(Phi)
for j = 1:length(Theta)
move(s, Phi(i), Theta(j));
radData1_CoPol(i,j,:) = measure(scope,10,length(Freq));
end
end
%reset theta and phi positions
i=1;
j=1;
%wait for user to flip the Braccio;
%%%% execute dbcont to move forward
%
keyboard
%ensure Braccio is at starting point
move(s,Phi(1),Theta(1));
%Measure hemisphere 2
for i = 1:length(Phi)
for j = 1:length(Theta)
move(s, Phi(i), Theta(j));
radData2_CoPol(i,j,:) = measure(scope,10,length(Freq));
end
end
%Save the first co-pol hemisphere
freq_observe = 3.0e9; % Set the frequency set you'd like to save to CSV
saveCSV(radData1_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem1CoPol_3000MHz_1metre',freq_observe);
freq_observe = 3.2e9; % Set the frequency set you'd like to save to CSV
saveCSV(radData1_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem1CoPol_3200MHz_1metre',freq_observe);
freq_observe = 3.4e9; % Set the frequency set you'd like to save to CSV
saveCSV(radData1_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem1CoPol_3400MHz_1metre',freq_observe);
freq_observe = 3.6e9; % Set the frequency set you'd like to save to CSV
saveCSV(radData1_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem1CoPol_3600MHz_1metre',freq_observe);
%Save the second c-pol hemisphere
freq_observe = 3.0e9; % Set the frequency set you'd like to save to CSV
saveCSV(radData2_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem2CoPol_3000MHz_1metre',freq_observe);
freq_observe = 3.2e9; % Set the frequency set you'd like to save to CSV
saveCSV(radData2_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem2CoPol_3200MHz_1metre',freq_observe);
freq_observe = 3.4e9; % Set the frequency set you'd like to save to CSV
saveCSV(radData2_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem2CoPol_3400MHz_1metre',freq_observe);
freq_observe = 3.6e9; % Set the frequency set you'd like to save to CSV
saveCSV(radData2_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem2CoPol_3600MHz_1metre',freq_observe);
%combine both at a single frequency
radData_full=cat(2,radData1_CoPol(:,:,17),radData2_CoPol(:,:,13));
%WIP
Phi2 = (-180:deltaPhi:180)';
Theta2 = 0:deltaTheta:365;
%plot hemisphere 1
figure(1); clf;
patternCustom(radData1_CoPol(:,:,13),Theta,Phi,'CoordinateSystem','rectangular','Slice','phi','SliceValue',0);
figure(2); clf;
patternCustom(radData1_CoPol(:,:,13),Theta,Phi);
figure(3); clf;
patternCustom(radData2_CoPol(:,:,13),Theta,Phi);
figure(4); clf;
patternCustom(radData_full(:,:74),Theta2,Phi)
%Directivity calculation for single frequency
radData_mag = 10.^(radData_full(:,:)/10);
total_RP = sum(radData_mag);
average_RP = mean(radData_mag);
Peak_RP = max(radData_mag);
Directivity_linear = Peak_RP/average_RP;
Directivity_dB = 10*log(Peak_RP/average_RP)
%%%%%%%%%%%%%%%%% End %%%%%%%%%%%%%%%%%%%
move(s,0,90);
fclose(s);
delete(s);
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Setup: %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
% Precondition: Installed R&S VISA 5.11.0 or later with R&S VISA.NET
clear;
close all;
clc;
try
assemblyCheck = NET.addAssembly('Ivi.Visa');
catch
error('Error loading .NET assembly Ivi.Visa');
end
resourceString1 = 'TCPIP::192.168.2.2::INSTR'; % Standard LAN connection (also called VXI-11)
scope = Ivi.Visa.GlobalResourceManager.Open(resourceString1); % Opening VISA session to the instrument
scope.Clear()
scope.RawIO.Write(['*IDN?' newline]); % LineFeed character at the end (newline character)
idnResponse = char(scope.RawIO.ReadString()); % Store *IDN? query response from VNA
s = serial('COM4','BaudRate',9600); % Serial settings - change COM port as required
fopen(s); % Open the serial session
pause(10); % Waiting for Braccio.begin() on Arduino to complete
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
deltaTheta = 5;
deltaPhi = 5;
deltaFreq = 100e6;
Theta = 0:deltaTheta:180;
Phi = (-90:deltaPhi:90)';
%
%%%%%%% Set your frequency range %%%%%%%%%%
%
Freq = 2.0e9:deltaFreq:4.0e9;
%
%%%%%% Set your frequency point of interest
%
freq_plot=4;
%Braccio Hemisphere 1 Co-Polarization
radData1_CoPol = zeros(length(Phi),length(Theta),length(Freq));
%Braccio Hemisphere 2 Co-Polarization
radData2_CoPol = zeros(length(Phi),length(Theta),length(Freq));
%Braccio Hemisphere 1 Cross Polarization
radData1_XPol = zeros(length(Phi),length(Theta),length(Freq));
%Braccio Hemisphere 2 Cross Polarization
radData2_XPol = zeros(length(Phi),length(Theta),length(Freq));
setup(scope,Freq); % Setup the VNA
pause(1);
%ensure Braccio is at starting point
move(s,-90,0);
pause(1);
%Measure hemisphere 1
for i = 1:length(Phi)
for j = 1:length(Theta)
move(s, Phi(i), Theta(j));
radData1_CoPol(i,j,:) = measure(scope,10,length(Freq));
end
end
%reset theta and phi positions
i=1;
j=1;
%wait for user to flip the Braccio;
%%%% execute dbcont to move forward
%
fprintf("######\n########\n Flip the Braccio To hemisphere 2\n########\n")
keyboard
pause(2);
%ensure Braccio is at starting point
move(s,Phi(1),Theta(1));
%Measure hemisphere 2
for i = 1:length(Phi)
for j = 1:length(Theta)
move(s, Phi(i), Theta(j));
radData2_CoPol(i,j,:) = measure(scope,10,length(Freq));
end
end
%
%%%% execute dbcont to move forward
%
fprintf("######\n########\nChange polarization of the source \n######\n########\n Flip the Braccio To hemisphere 1\n")
keyboard
pause(2);
%ensure Braccio is at starting point
move(s,Phi(1),Theta(1));
%reset theta and phi positions
i=1;
j=1;
%Measure hemisphere 1 X-Polarized
for i = 1:length(Phi)
for j = 1:length(Theta)
move(s, Phi(i), Theta(j));
radData1_XPol(i,j,:) = measure(scope,10,length(Freq));
end
end
%
%%%% execute dbcont to move forward
%
fprintf("\n######\n########\n Flip the Braccio To hemisphere 2\n########\n")
keyboard
pause(2);
%ensure Braccio is at starting point
move(s,Phi(1),Theta(1));
%reset theta and phi positions
i=1;
j=1;
%Measure hemisphere 2 X-Polarized
for i = 1:length(Phi)
for j = 1:length(Theta)
move(s, Phi(i), Theta(j));
radData2_XPol(i,j,:) = measure(scope,10,length(Freq));
end
end
%
%Save the data (frequency sweep for each hemisphere and polarization) in a .Dat file
%
save AgPU10000cyclesPatch_take2_2400MHz_Hem1_CoPol.dat radData1_CoPol
save AgPU10000cyclesPatch_take2_2400MHz_Hem2_CoPol.dat radData2_CoPol
save AgPU10000cyclesPatch_take2_2400MHz_Hem1_XPol.dat radData1_XPol
save AgPU10000cyclesPatch_take2_2400MHz_Hem2_XPol.dat radData2_XPol
%
%%%%% New angular ranges for 3D plots
%
Phi2 = (-180:deltaPhi:180)';
Theta2 = 0:deltaTheta:365;
%
%%%%%
%
%combine both hemispheres at a single frequency for each polarization
% in radDataN_CoPol(:,:,x) -> X denotes teh frequency point of interest
%
radData_full_CoPol=cat(2,radData1_CoPol(:,:,4),radData2_CoPol(:,:,4));
radData_full_XPol=cat(2,radData1_XPol(:,:,4),radData2_XPol(:,:,4));
%
%%%%%%
%
radData_full_CoPol_mag=10.^(radData_full_CoPol(:,:)./10);
radData_full_XPol_mag=10.^(radData_full_XPol(:,:)./10);
total_RP = sum(sum(radData_full_CoPol_mag)) + sum(sum(radData_full_CoPol_mag));
average_RP_CoPol = mean(mean(radData_full_CoPol_mag));
average_RP_XPol = mean(mean(radData_full_CoPol_mag));
Peak_RP_CoPol = max(max(radData_full_CoPol_mag));
Directivity_CoPol = Peak_RP_CoPol/average_RP_CoPol;
Directivity_CoPol_dB = 10*log(Directivity_CoPol/10)
%
%Normalize the patterns
%
max_value=max(max(radData_full_CoPol(:,:)));
Norm_radData_full_CoPol(:,:)=radData_full_CoPol(:,:)-max_value;
Norm_radData_full_XPol(:,:)=radData_full_XPol(:,:)-max_value;
%
%plot hemisphere 1
%
figure(1); clf;
patternCustom(radData1_CoPol(:,:,freq_plot),Theta,Phi,'CoordinateSystem','rectangular','Slice','phi','SliceValue',0);
figure(2); clf;
patternCustom(radData1_CoPol(:,:,freq_plot),Theta,Phi);
figure(3); clf;
patternCustom(radData2_CoPol(:,:,freq_plot),Theta,Phi);
figure(4); clf;
patternCustom(Norm_radData_full_CoPol(:,:),Theta2,Phi);
figure(5); clf;
patternCustom(Norm_radData_full_XPol(:,:),Theta2,Phi);
%Directivity calculation for single frequency
radData_mag = 10.^(radData_full_CoPol(:,:)/10);
total_RP = sum(radData_mag);
average_RP = mean(radData_mag);
Peak_RP = max(radData_mag);
Directivity_linear = Peak_RP/average_RP;
Directivity_dBi = 10*log(Peak_RP/average_RP)
%%%%%%%%%%%%%%%%% End %%%%%%%%%%%%%%%%%%%
move(s,0,90);
fclose(s);
delete(s);
% %Save the first co-pol hemisphere
% freq_observe = 3.0e9; % Set the frequency set you'd like to save to CSV
% saveCSV(radData1_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem1CoPol_3000MHz_1metre',freq_observe);
%
% freq_observe = 3.2e9; % Set the frequency set you'd like to save to CSV
% saveCSV(radData1_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem1CoPol_3200MHz_1metre',freq_observe);
%
% freq_observe = 3.4e9; % Set the frequency set you'd like to save to CSV
% saveCSV(radData1_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem1CoPol_3400MHz_1metre',freq_observe);
%
% freq_observe = 3.6e9; % Set the frequency set you'd like to save to CSV
% saveCSV(radData1_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem1CoPol_3600MHz_1metre',freq_observe);
%
%
% %Save the second c-pol hemisphere
% freq_observe = 3.0e9; % Set the frequency set you'd like to save to CSV
% saveCSV(radData2_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem2CoPol_3000MHz_1metre',freq_observe);
%
% freq_observe = 3.2e9; % Set the frequency set you'd like to save to CSV
% saveCSV(radData2_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem2CoPol_3200MHz_1metre',freq_observe);
%
% freq_observe = 3.4e9; % Set the frequency set you'd like to save to CSV
% saveCSV(radData2_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem2CoPol_3400MHz_1metre',freq_observe);
%
% freq_observe = 3.6e9; % Set the frequency set you'd like to save to CSV
% saveCSV(radData2_CoPol,Theta,Phi,Freq,'CarbonPatch1_Hem2CoPol_3600MHz_1metre',freq_observe);
File added
File added
function [read] = measure(scope,n_samples,size)
%MEASURE Request measurement sweep from VNA
commands = [
"INIT1:IMM"
"*WAI"
"CALC1:DATA? FDAT"
];
samples = zeros(n_samples,size); % Array for holding multiple identical sweeps for averaging
for x = 1:n_samples
for i = 1:length(commands)
scope.RawIO.Write([char(commands(i)) newline]);
end
a = char(scope.RawIO.ReadString());
samples(x,:) = sscanf(a, '%g,', [1, inf]).';
pause(0.01); % Delay between sweeps
end
read = mean(samples); % Mean of rows of 'samples' - leaves one row
end
function move(s, Phi, Theta)
%MOVE Sends command to move the Braccio arm to the requested position
% M1 M2 M3 M4 M5 M6
% Base Shldr Elbow WristV WristR Grip
% 0-180 15-165 0-180 0-180 0-180 10-73
if (Phi <= 90)&&(Phi >= -90)
mov = [Phi+90, 90, 180, Theta, 180, 10];
end
for i=1:size(mov,1) % Cycle through all position vectors in 'mov'
fwrite(s, mov(i,:)); % Send position vector via serial
disp(fread(s,6,'uint8')); % Read and display serial
end
end
deltaTheta = 20;
deltaPhi = 20;
Theta = 0:deltaTheta:180;
Phi = (-180:deltaPhi:180)';
Freq = 0.2e9:0.1e9:2e9;
radData = zeros(length(Phi),length(Theta),length(Freq));
for i = 1:length(Phi)
for j = 1:length(Theta)
% Move to correct position
radData(i,j,:) = i*j;
end
end
freq_observe = 300e6;
saveCSV(radData,Theta,Phi,Freq,'test',freq_observe);
figure(1); clf;
patternCustom(radData(:,:,3),Theta,Phi,'CoordinateSystem','rectangular','Slice','phi','SliceValue',-180);
function saveCSV(radData, Theta, Phi, Freq, fname, FreqSave)
%SAVECSV Saves the radData to a csv file
% radData(azimuth, elevation, frequency) = Magnitude
% Theta = 0 to 180 (elevation)
% Phi = -80 to 180 (azimuth)
% Freq = Start Frequency to Stop Frequency
% fname = Desired filename
% FreqSave = Single frequency within Freq to save data for
% Append requested frequency to file name:
if FreqSave > 1e9
append = '_' + string(FreqSave/1e9) + 'GHz';
else
append = '_' + string(FreqSave/1e6) + 'MHz';
end
% Search Freq vector for element number of requested frequency:
freq_index = find(Freq == FreqSave);
% Reshape data for csv file:
Elevation = repelem(Theta,length(Phi))';
Azimuth = repmat(Phi,[length(Theta) 1]);
Magnitude = reshape(radData(:,:,freq_index),[numel(radData(:,:,freq_index)) 1]);
T = table(Elevation,Azimuth,Magnitude);
writetable(T,strcat(fname,append+'.csv'));
end
function setup(scope, Freq)
%SETUP Setup of the VNA
setup_cmmds = [
"*RST"
"INIT1:CONT 0" % Single sweep = 0, Continuous = 1
"SYST:DISP:UPD ON"
"MEM:DEF 'Set1'"
"CALC1:PAR:SDEF 'Antenna','S21'"
"DISP:WIND1:STAT ON;:DISP:WIND1:TRAC2:FEED 'Antenna'"
"SENS1:SWE:POIN " % Max: 20,001 Min: 2
"INIT1:CONT 0" % Single sweep = 0, Continuous = 1
"SENS1:SWE:COUN 1" % Sweep count (set to 1)
"SENS1:SWE:TYPE LIN" % "LIN" or "LOG"
"SENS1:FREQ:STAR " % Start frequency
"SENS1:FREQ:STOP " % Stop frequency
"SOUR1:POW 10dBm" % Output power
"CALC1:PAR:SDEF 'Antenna','S21'"
"CALC1:FORM MLOG"
];
setup_cmmds(7) = setup_cmmds(7) + string(length(Freq)); % Set number of points
setup_cmmds(11) = setup_cmmds(11) + string(Freq(1)/1e9) + "GHz"; % Set start frequency
setup_cmmds(12) = setup_cmmds(12) + string(Freq(end)/1e9) + "GHz"; % Set end frequency
for i = 1:length(setup_cmmds)
scope.RawIO.Write([char(setup_cmmds(i)) newline]);
end
end
File added
File added
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment