Hexapod Robot: FPGA-Based Solution
2018-10-31 | By adam taylor
License: General Public License
Introduction
This project is going to show how we can build a walking hexapod robot which is controlled by a heterogeneous SoC that combines ARM processors with Programmable Logic.
Once completed the robot will have six legs, which must be controlled to ensure the robot can navigate in any direction.
Typically hexapod robots have differing degrees of freedom (DoF) per leg, the most common selections for hexapod walkers are 2 or 3 DoF.
This example will create a 2 DoF hexapod, meaning that each leg can can be moved up and down, as well as forward and backward. Exactly what we need to make it walk on a fairly flat surface. Each degree of freedom requires motor control. In this example, servos are used.
As the controller of the hexapod is based around a Cora Z7, which uses a Xilinx Zynq 7010, we will also use the Cora Z7 two Pmod interfaces to provide an understanding of the world and help the hexapod navigate in its environment.
To do this, we will be using the Pmod Sonar and the Pmod Nav.
Creating such a hexapod presents us with many challenges, including:
- Controlling multiple servos to enable walking
- Measuring distances and stopping movement when a object is too close
- Determining the next direction to explor
The Build
Completing the project requires several stages of build. The first is to assemble the mechanical body and legs of the hexapod in line with the guidelines for the hexapod body kit I purchased. These instructions can be found here (legs) and here (body) building the legs are very simple but a little time consuming.
One key thing to remember when you assemble the legs is to remember to mirror the legs for the right and left side.
Controlling Servos
Once we have the legs assembled, we need to be able to control them with the Cora Z7. Servos use PWM to drive to either extreme position or maintain their neutral position.
To maintain position, the desired servo position the PWM drive signal to the servo needs to be refreshed at 60 Hz.
Maintaining a neutral position requires the PWM signal must be high for 1.5 ms or 9% of the 60 Hz cycle.
If we want to move the servo to either extreme, we increase or decrease the PWM signal by 1 ms.
This means the PWM signal is valid between 0.5 ms and 2.5 ms or 3% to 15% of the 60 Hz cycle.
For this application, we are using the Cora Z7 which has a Zynq Z7010 fitted.
The Zynq 7010 has two Triple Timer Counters (TTC) within the PS, each of these TTC is capable of generating a PWM signal and driving a servo.
However, sadly this provides only 6 of the 12 servo drive signals we would need. If we used a Zynq MPSoC with four TTC this would provide sufficient drive capability directly.
Therefore, the simplest manner to drive the 12 servos for the hexapod is to use a shield designed for controlling up to 16 servos. The use of the shield means that we can use I2C from the Zynq to the shield to control each of the 16 PWM drive signals.
The shield I selected was the Adafruit 16 Channel PWM, which also requires assembly when it is received.
The shield requires two separate power supplies one for the servos and another for the logic.
To ensure the shield connectors align prior to soldering them, I connected them into an old Ardunio board and then placed the PWM shield on top.
This means that when you solder the shield pins in they are correctly spaced and interface with the Cora Z7 shield interface easily.
Once the shield has been assembled, the next stage is to mount it with the Cora Z7 and construct the body around the controller and the legs.
To test the Cora Z7 with the PWM Shield, a simple bare metal application was created in Vivado and SDK which was later expanded. This enabled me to demonstrate that the approach was valid and servos could be controlled correctly.
As the PWM can control up to 16 legs, the following mapping was used on the PWM shield connected to the leg joints:
- Channel 0 - Leg 0 up/down
- Channel 1 - Leg 1 up/down
- Channel 2 - Leg 2 up/down
- Channel 3 - Leg 3 up/down
- Channel 4 - Leg 4 up/down
- Channel 5 - Leg 5 up/down
- Channel 8 - Leg 0 forward/back
- Channel 9 - Leg 1 forward/back
- Channel 10 - Leg 2 forward/back
- Channel 11 - Leg 3 forward/back
- Channel 12 - Leg 4 forward/back
- Channel 13 - Leg 5 forward/back
This allocation of channels makes the SW we have to write later to control the servos a little easier.
Once we have the hexapod legs and body integrated with the Cora Z7 and the PWM shield, the next thing we need to do is create a Vivado project and SDK application.
Vivado Design
If this is your first time working with the Cora Z7, the first step is to install the board definition files, which enables Vivado to understand the configuration of Cora Z7. You can download the board definition files from here.
Our Vivado design needs to be able to interface with the I2C connections on the shield interface. While also interfacing to the Pmod Sonar and Pmod Nav, luckily for the Pmods we can use the Digilent IP repository.
The complete design uses the AXI I2C module in the PL along with the Pmod NAV and sonar IP. On the Cora Z7 Pmod, A is connected to the sonar and Pmod B is connected to the Nav.
Once we have the design built, we can start to create the SW application this is where the majority of the functionality of the hexapod is implemented.
SDK Software
The software for this application is complicated; therefore, the architecture was broken up into a number of functions which could be called as required with the necessary parameters.
Key functions are:
- set_freq() - this sets the frequency of the PCA9685 PWM - for this application it sets the refresh to 60 Hz.
- start_up() - checks each of the legs and all its joints movements in order. It only runs once following start up.
- write_leg() - command a defined leg up or down.
- centralise() - command a defined leg forward or backwards.
- straight() - makes the hexapod walk in straight line forward, uses write_leg() and centralise().
- reverse() - makes the hexapod walk in straight line backwards, uses write_leg() and centralise().
- left() - makes the hexapod turn to the left, uses write_leg() and centralise().
- right() - makes the hexapod turn to the right, uses write_leg() and centralise().
For the hexapod to pod to maneuver it uses an alternating tripod approach. This offers the most stable approach to walking.
This is shown in the diagram below where either the blue or the red legs move, leaving the hexapod supported by the remaining legs in a triangle.
Driving the PCA9685 IC on the PWM shield is straightforward, each PWM output has four registers. These define the time at which the PWM signal is turned on and the time at which it is turned off. As the timer have 12 bit granularity each on and off time has two 8-bit registers.
For this application, we can leave the on time as zero and set the off time at the desired value for the movement of the servo. These values are defined as constants and called up by the functions above as required.
void WriteLeg(int leg, position_t position )
//this positions a leg to either up or dwn
{
u8 SendBuffer [2];
u8 RecvBuffer [1];
if (position == down && (leg == 0 || leg == 2 || leg ==4)){
SendBuffer[0] = 0x06+(4*leg);
SendBuffer[1] = up_l_on;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
SendBuffer[0] = 0x07+(4*leg);
SendBuffer[1] = up_h_on;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
SendBuffer[0] = 0x08+(4*leg);
SendBuffer[1] = up_l_off;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
SendBuffer[0] = 0x09+(4*leg);
SendBuffer[1] = up_h_off;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
//printf("up even\r\n");
}
else
if (position == down && (leg == 1 || leg == 3 || leg == 5)){
SendBuffer[0] = 0x06+(4*leg);
SendBuffer[1] = down_l_on;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
SendBuffer[0] = 0x07+(4*leg);
SendBuffer[1] = down_h_on;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
SendBuffer[0] = 0x08+(4*leg);
SendBuffer[1] = down_l_off;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
SendBuffer[0] = 0x09+(4*leg);
SendBuffer[1] = down_h_off;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
//printf("up even\r\n");
}
else
if (position == up && (leg == 0 || leg == 2 || leg ==4)){
SendBuffer[0] = 0x06+(4*leg);
SendBuffer[1] = down_l_on;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
SendBuffer[0] = 0x07+(4*leg);
SendBuffer[1] = down_h_on;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
SendBuffer[0] = 0x08+(4*leg);
SendBuffer[1] = down_l_off;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
SendBuffer[0] = 0x09+(4*leg);
SendBuffer[1] = down_h_off;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
//printf("down even\r\n");
}
else
if (position == up && (leg == 1 || leg == 3 || leg ==5)){
SendBuffer[0] = 0x06+(4*leg);
SendBuffer[1] = up_l_on;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
SendBuffer[0] = 0x07+(4*leg);
SendBuffer[1] = up_h_on;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
SendBuffer[0] = 0x08+(4*leg);
SendBuffer[1] = up_l_off;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
SendBuffer[0] = 0x09+(4*leg);
SendBuffer[1] = up_h_off;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
//printf("down odd\r\n");
}
}
void SetFreq()
{
u8 SendBuffer[2];
SendBuffer[0] = 0xFE;
SendBuffer[1] = 0x64;
XIic_Send(iic.BaseAddress,IIC_SLAVE_ADDR,(u8 *)&SendBuffer, sizeof(SendBuffer),XIIC_STOP);
}
When the start_up() test is run the movement, you can see each of the legs moving as expected.
With basic motor control implemented, the next required capability is for the hexapod to be able to navigate within its environment, at least to a basic level.
For this we use the Pmod Sonar to determine if there is an obstacle in its path, and the Pmod Nav to enable it to know its orientation and avoid it.
Once the SW has performed, the initial startup movement of each joint it enters a continual loop where the hexapod moves forward unless there an object is detected less than 10 inches away.
If an object is detected, the current heading is recorded from the Pmod Nav and 90 degrees is added on to that heading.
The hexapod will then turn to the new heading before testing again the distance, and begin to walk forward.
The Result
When all of this was put together for the first time I recorded the video's below showing the hexapod walking forward and turning when it saw an obstacle in front of it.
Note, I used a Li-ion battery pack for power.
Have questions or comments? Continue the conversation on TechForum, DigiKey's online community and technical resource.
Visit TechForum