No, it is not a typo. SMArt Solar Tracker aligns its solar panel with the sun using Shape Memory Alloys and Phototransistors to increase power output.

Enlarge

SMAs actuating
SMAs being actuated

University of Houston

We were motivated to build this device by two points: the solid-state nature of SMAs and benefits of active solar tracking.
Unlike motors, SMAs require little to no maintenance since they are solid state devices which allow them to operate in much harsher environments with less protection, making them ideal for military and space applications. Active solar tracking, although harder, is the only viable option when you can’t use a solar altitude/azimuth table either because you don’t know where you are or you don’t know what date/time it is. These advantages of a SMA actuated active solar tracker made a very compelling case for us to investigate it.

We developed two subsystems, namely the SMA actuation and the active solar tracking, and integrated them together on an Arduino Uno.

Enlarge

Solar Pyramid
Solar Pyramid with the resultant (red) and individual (yellow) light vectors

Active solar tracking is done by a small unit, we like to call the “solar pyramid”. This is a tiny 3D-printed pyramid with 3 phototransistors placed on it. Going through a bunch of circuitry and finally into the ADC of the Arduino, these phototransistors tell us intensity of the light they are receiving. These intensities are then used to construct 3 vectors (one for each phototransistor) whose magnitudes are equal to the corresponding intensity. Pyramid’s angle between faces and its base are used to calculate the azimuthal angle and polar angle of each one of these vectors. The result is 3 vectors representing light intensity incident on the 3 faces of the solar pyramid. These vectors are then summed together. This resultant vector is the perceived direction at which the brightest light source is coming from. In the case of a solar panel, this is the direction where the sun is.

Next up is physically actuating the panel. SMA are amazing devices that change shape and size as a function of temperature. Generally they are operated by passing through a current. We only had very simple, and rather cheap, linear string-like SMAs available to us which turned out to be okay. Our SMAs have a stroke of 3mm (the length it gets smaller by when the SMA is hot) and a load capacity of 15N, with more expensive spring-like SMAs, you can get more stroke and more load capacity. You could also get SMAs that go into different shapes rather than contract and expand linearly.

Our control system utilizes a PID loop which uses the resultant vector from the solar pyramid as its feedback. In a nutshell, our system is trying to minimize the polar angle because the polar angle is zero when sun light is incident at a right angle. (i.e. power output is maximized) This is done by changing the current flowing through the SMAs which cause the panel to rotate. A great advantage of using a closed loop system like ours is that you don’t need to worry too much about characterizing your SMAs which tend to have non-linear relationships between their lengths and current flowing through, and that you are always pointing towards the source in the sky that will produce the highest power output even when clouds are present. Both of which are issues that can not be overcome by using a standard solar altitude/azimuth table. Outputs of the PID loop control N-channel MOSFETs which are used to regulate current going through the SMAs.

Enlarge

smart-solar-tracker-cropped
SMArt Solar Tracker

Investigation of efficiency of this system deserves an entire article but to quickly summarize: the most power hungry component in this system, the SMAs, draw less than 1W at peak which is rather insignificant compared to the panel’s power output. On the flip side, motors consume much more power but also don’t need to be continuously powered. The actual efficiency of a SMA actuated system tends to be better at smaller scales for mobile applications such as spacecraft and military deployments whereas motors really shine at bigger scales for fixed applications such as power plants.

Below you can find a simplified version of our code that lacks the Integral and Derivative components of the PID loop for stability and ease of use.

float pt1_phi=60*3.14158/180;    //angles are in radians which is degrees * (pi/180)
float pt1_omega=0*3.14158/180;
float pt2_phi=60*3.14158/180;
float pt2_omega=120*3.14158/180;
float pt3_phi=60*3.14158/180;
float pt3_omega=240*3.14158/180;
float resultantSolar[3]={0,0,0};  //Magnitude, Omega and Phi of Resultant Solar Data

float phiTarget=0;    //Target is the angle we are trying to achieve
float omegaTarget=90; //Error is the starting error for that angle
float omegaError=0;   
float phiError=0;     

float phiGain=10;     //Conversion factor between angular difference and current output
float omegaGain=15;   //Conversion factor between angular difference and current output

int yaw1Output=0;     //Starting output in mA
int yaw2Output=0;     //Starting output in mA
int pitch1Output=0;   //Starting output in mA
int pitch2Output=0;   //Starting output in mA

int SMAyawMid=400;    //mA
int SMApitchMid=400;  //mA

int a0, a1, a2;

void setup() {
//Some initial tasks that need to be done

  //Start up serial so we can see whats going on with the system
  Serial.begin(9600);
  
  //setup PWM pins which control the effective current passing through the SMAs
  pinMode(3, OUTPUT);
  pinMode(5, OUTPUT);
  pinMode(6, OUTPUT);
  pinMode(9, OUTPUT);

  //Read PTs (Phototransistors)
  a0=analogRead(0);
  a1=analogRead(1);
  a2=analogRead(2);
  //calculate resultant solar vector
  updateResultantSolar(analogRead(0), analogRead(1), analogRead(2), resultantSolar); 
}

void loop() {
//Loop for reading PTs and PID

  //Keep reading PTs at every cycle
  a0=analogRead(0);
  a1=analogRead(1);
  a2=analogRead(2);
  //calculate resultant solar vector at every cycle
  updateResultantSolar(a0, a1, a2, resultantSolar);

  //Calculate the required changed in Polar and Azimuth angles to reach the optimal state
  omegaError = omegaTarget - resultantSolar[1];
  phiError = phiTarget - resultantSolar[2];

  //Calculate Pitch and Yaw outputs as straying away from a Mid point (SMAyawMid and SMApitchMid)
  yaw1Output = SMAyawMid - round(omegaGain*omegaError);
  yaw2Output = SMAyawMid + round(omegaGain*omegaError);

  pitch1Output = SMApitchMid + round(phiGain*phiError);
  pitch2Output = SMApitchMid - round(phiGain*phiError);
  
//Ensure Pitch and Yaw outputs are between 0 and 255
  if(yaw1Output > 800){
    yaw1Output=800;
    yaw2Output=0;
  }
  if(yaw2Output > 800){
    yaw1Output=0;
    yaw2Output=800;
  }
  if(pitch1Output > 800){
    pitch1Output=800;
    pitch2Output=0;
  }
  if(pitch2Output > 800){
    pitch1Output=0;
    pitch2Output=800;
  }

  yaw1Output = map(yaw1Output, 0, 800, 0, 255);
  yaw2Output = map(yaw2Output, 0, 800, 0, 255);
  pitch1Output = map(pitch1Output, 0, 800, 0, 255);
  pitch2Output = map(pitch2Output, 0, 800, 0, 255);

  //print values for reference
  Serial.print("PT: ");
  Serial.print(a0);
  Serial.print(" ");
  Serial.print(a1);
  Serial.print(" ");
  Serial.println(a2);
  Serial.print("R: ");
  Serial.print(resultantSolar[0]);
  Serial.print(" ");
  Serial.print(resultantSolar[1]);
  Serial.print(" ");
  Serial.println(resultantSolar[2]);
  Serial.print("Error: yaw1output ");
  Serial.print(yaw1Output);
  Serial.print(" yaw2output ");
  Serial.print(yaw2Output);
  Serial.println(" ");
  Serial.print("Error: pitch1output ");
  Serial.print(pitch1Output);
  Serial.print(" pitch2output ");
  Serial.print(pitch2Output);
  Serial.println(" ");
  //actuate SMAs

  analogWrite(3,yaw1Output);
  analogWrite(5,yaw2Output);
  analogWrite(6,pitch1Output);
  analogWrite(9,pitch2Output);

  //No need to do faster
  delay(500);
}


void updateResultantSolar(int pt1, int pt2, int pt3, float *resultantSolar){
//Calculates the resultant light vector for given phototransistor intensities

  //For each PT, convert from Spherical to Cartesian
  double pt1x=pt1*sin(pt1_phi)*cos(pt1_omega);
  double pt1y=pt1*sin(pt1_phi)*sin(pt1_omega);
  double pt1z=pt1*cos(pt1_phi);
  double pt2x=pt2*sin(pt2_phi)*cos(pt2_omega);
  double pt2y=pt2*sin(pt2_phi)*sin(pt2_omega);
  double pt2z=pt2*cos(pt2_phi);
  double pt3x=pt3*sin(pt3_phi)*cos(pt3_omega);
  double pt3y=pt3*sin(pt3_phi)*sin(pt3_omega);
  double pt3z=pt3*cos(pt3_phi);
  //Sum up cartesian components of PTs
  double rx=pt1x+pt2x+pt3x;
  double ry=pt1y+pt2y+pt3y;
  double rz=pt1z+pt2z+pt3z;
  //Convert resultant Cartesian to Spherical
  resultantSolar[0]=sqrt(sq(rx)+sq(ry)+sq(rz));     //R Magnitude
  resultantSolar[1]=(180/3.1415)*atan2(ry,rx);                    //R Omega--yaw
  resultantSolar[2]=(180/3.1415)*atan2(sqrt(sq(rx)+sq(ry)),rz);   //R Phi--pitch
}

 Thank you Evan Lowell for your experience with SMAs and being an amazing partner on this project!