element14 Community
element14 Community
    Register Log In
  • Site
  • Search
  • Log In Register
  • Members
    Members
    • Benefits of Membership
    • Achievement Levels
    • Members Area
    • Personal Blogs
    • Feedback and Support
    • What's New on element14
  • Learn
    Learn
    • Learning Center
    • eBooks
    • STEM Academy
    • Webinars, Training and Events
    • More
  • Technologies
    Technologies
    • 3D Printing
    • FPGA
    • Industrial Automation
    • Internet of Things
    • Power & Energy
    • Sensors
    • More
  • Challenges & Projects
    Challenges & Projects
    • Design Challenges
    • element14 presents
    • Project14
    • Arduino Projects
    • Raspberry Pi Projects
    • More
  • Products
    Products
    • Arduino
    • Dev Tools
    • Manufacturers
    • Raspberry Pi
    • RoadTests & Reviews
    • Avnet Boards Community
    • More
  • Store
    Store
    • Visit Your Store
    • Choose Another Store
      • Europe
      •  Austria (German)
      •  Belgium (Dutch, French)
      •  Bulgaria (Bulgarian)
      •  Czech Republic (Czech)
      •  Denmark (Danish)
      •  Estonia (Estonian)
      •  Finland (Finnish)
      •  France (French)
      •  Germany (German)
      •  Hungary (Hungarian)
      •  Ireland
      •  Israel
      •  Italy (Italian)
      •  Latvia (Latvian)
      •  
      •  Lithuania (Lithuanian)
      •  Netherlands (Dutch)
      •  Norway (Norwegian)
      •  Poland (Polish)
      •  Portugal (Portuguese)
      •  Romania (Romanian)
      •  Russia (Russian)
      •  Slovakia (Slovak)
      •  Slovenia (Slovenian)
      •  Spain (Spanish)
      •  Sweden (Swedish)
      •  Switzerland(German, French)
      •  Turkey (Turkish)
      •  United Kingdom
      • Asia Pacific
      •  Australia
      •  China
      •  Hong Kong
      •  India
      •  Korea (Korean)
      •  Malaysia
      •  New Zealand
      •  Philippines
      •  Singapore
      •  Taiwan
      •  Thailand (Thai)
      • Americas
      •  Brazil (Portuguese)
      •  Canada
      •  Mexico (Spanish)
      •  United States
      Can't find the country/region you're looking for? Visit our export site or find a local distributor.
  • Translate
  • Profile
FPGA
  • Technologies
  • More
FPGA
Blog Arty S7 50 ArtyBot - Color sensing and line follower
  • Blog
  • Forum
  • Documents
  • Events
  • Members
  • Mentions
  • Sub-Groups
  • Tags
  • More
  • Cancel
  • New
FPGA requires membership for participation - click to join
Blog Post Actions
  • Subscribe by email
  • More
  • Cancel
  • Share
  • Subscribe by email
  • More
  • Cancel
Group Actions
  • Group RSS
  • More
  • Cancel
Engagement
  • Author Author: javagoza
  • Date Created: 17 Jul 2022 11:30 AM Date Created
  • Views 23047 views
  • Likes 8 likes
  • Comments 2 comments
  • Artybot
  • PmodCOLOR
  • color sensor
  • 7 Ways to Leave Your Spartan-6
  • fpga_projects
  • xilinx
  • fpga
  • emubot
  • PmodOLED
  • spartan-7
  • Spartan_Migration
  • microblaze
Related
Recommended

Arty S7 50 ArtyBot - Color sensing and line follower

javagoza
javagoza
17 Jul 2022
Arty S7 50 ArtyBot - Color sensing and line follower

In this post we will add a Pmod COLOR sensor to our robot developed on the AMD-Xilinx Spartan-7 FPGA of the Digilent Arty S7 board. That sensor will allow the robot to detect colors in its vicinity and we will try to make a simple line follower using the sensor. The sensor response is quite slow for its application as a line sensor, but we will try to create a lazy line follower.

This lazy line follower uses the Bot Application Framework that we have prepared for the Digilent Arty S7 based robot.

This post is part 9 of my contribution to the "7 Ways to Leave Your Spartan-6" program, learning about the Xilinx Spartan-7 FPGA on the Digilent Arty S7 50 board.

"7 Ways to Leave Your Spartan-6" related posts
1 Arty S7 50 First Power Up and Hardware-Only Blinky
2 Arty S7 50 First Baremetal Software Project
3 Arty S7 50 Rapid Prototyping - Environmental Monitor
4 Arty S7 50 ArtyBot Pulse Width Modulation (PWM) for Motor Speed Control
5 Arty S7 50 ArtyBot Custom AXI4 Lite IP Peripheral for Sensing Motor Rotational Speed
6 Arty S7 50 ArtyBot How to Store MicroBlaze Program in the Quad-SPI Flash from Vivado
7 Arty S7 50 ArtyBot - Bot Application Framework
8 Arty S7 50 ArtyBot becomes Emubot, an educational robot for young children
9 Arty S7 50 ArtyBot - Color sensing and line follower
10 Arty S7 50 The Spartan-6 Migration Path Game. Learning the Differences Between Spartan-6 and Spartan-7 FPGAs
11 Arty S7 50 ArtyBot ToF Sensor for Obstacle Avoidance. Vivado Hierarchical Blocks
12 "7 Ways to Leave Your Spartan-6 FPGA" program. My summary
13 Arty S7 50 VGA Thermal Imaging Camera

ArtyBot following the line. The video is sped up. The minimum sensor response is 2.4 ms and it takes time for the robot to figure out where it is.

You don't have permission to edit metadata of this video.
Edit media
x
Upload Preview


Bill of materials

If you want to replicate this project you will need:

Product Name Manufacturer Datasheet
Arty S7 50  Digilent  Buy Now
TI-RSLK element14 Buy Now
PmodOLED Digilent Buy Now
PmodCOLOR Digilent Buy Now

Pmod COLOR

The Digilent Pmod COLOR (Revision A) is a color sensor module with the ability to sense red, green, blue and clear light.

The onboard AMS TCS3472 integrates an IR blocking filter to accurately determine the color of objects as well as sense ambient light under varying lighting conditions and through attenuating materials.

Reference: Pmod COLOR Reference Manual - Digilent Reference

Emubot Line Follower Digilent Pmod COLOR

The Pmod COLOR module comes in a small antistatic plastic envelope with this information:

Pmod COLOR

The Pmod Color utilizes the TCS3472 to detect color in the near vicinity. While communicating with the host board via the I²C protocol using an I²C address of 0x29 the robot can measure color.

A user controlled white LED is also provided to help illuminate the object and improve color determination.


Construction: Attaching and Connecting the Sensor

We connect using 200 mm male female cables with dupont terminations from the JC Pmod connector on the board to the Pmod COLOR module. We  place the new Pmod COLOR module below the robot chassis pointing towards the ground.

Pmod ports

The Pmod module does not have holes to screw the module to the chassis. We fix it to the chassis with two wires.

Emubot Line Follower. Pmod COLOR placement

 Pmod COLOR module below the robot chassis pointing towards the ground.

The module has a very bright LED to improve color detection. We will use this feature for our line follower intent.

Enubot Line Follower


The Line Follower Application Program

It's a very simple application that makes extensive use of the Bot Application Framework introduced previously.

The application can be downloaded from the github repository under E14SpartanMigrationProgram/bot/src/line_follower_app.c

GitHub - javagoza/E14SpartanMigrationProgram

Line Follower Application Program flowchart:

Line Follower Application Flowchart


Following the Line with One Sensor

If the sensor detects more light than the threshold calibrated at the beginning, it accelerates the right wheel by a factor calculated by the PID controller, turning the robot to the left, towards the line, if it detects less light than the threshold, it accelerates the left wheel turning the robot to the right.

Line Follower Direction Correction


Line Follower Application source code

Go to the github repository for the most up-to-date copy of the code

/************************************************************************/
/*                                                                      */
/*  line_follower_app.c    --  simple line follower app for the emubot  */
/*  This file is part of the Arty S7 Bot Library                        */
/*                                                                      */
/************************************************************************/
/*    Author:     Enrique Albertos                                      */
/************************************************************************/
/*
 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
 */
/************************************************************************/
/*  Module Description:                                                 */
/*    simple line follower app for the emubot uses a PmodCOLOR module   */
/*                                                                      */
/************************************************************************/
/*  Revision History:                                                   */
/*                                                                      */
/*    2022/07/16: (EAC) created                                         */
/*                                                                      */
/************************************************************************/

#include "line_follower_app.h"

#define MAX(x, y) (((x) > (y)) ? (x) : (y))
#define MIN(x, y) (((x) < (y)) ? (x) : (y))

typedef struct {
    COLOR_Data min, max;
} CalibrationData;

CalibrationData DemoInitCalibrationData(COLOR_Data firstSample);
void DemoCalibrate(COLOR_Data newSample, CalibrationData *calib);
u16 getThreshold(BotDrivers* botDrivers, int increments);
void rotate15degreesLeft(BotDrivers* botDrivers);
void searchTheLine(BotDrivers* botDrivers, u16 threshold, int increments);



void line_follower_application() {

    BotDrivers botDrivers;
    BOT_init(&botDrivers);

    COLOR_GetID(botDrivers.drivingDriver.colorSensor);

    int increments = 1;
    while (1) {
        OLED_SetCharUpdate(&botDrivers.oled, 1);
        OLED_ClearBuffer(&botDrivers.oled);
        OLED_SetCursor(&botDrivers.oled, 0, 0);
        OLED_PutString(&botDrivers.oled, " BTN1 CALIBRATE");

        while (!BUTTONS_DRIVER_button1_pressed(&botDrivers.buttonsDriver)) {
        } // wait for push button 1
        BUTTONS_DRIVER_reset(&botDrivers.buttonsDriver);
        OLED_ClearBuffer(&botDrivers.oled);
        OLED_SetCursor(&botDrivers.oled, 0, 0);
        OLED_PutString(&botDrivers.oled, " CALIBRATING...");

        rotate15degreesLeft(&botDrivers);

        u16 threshold = getThreshold(&botDrivers, increments);
        OLED_ClearBuffer(&botDrivers.oled);
        OLED_SetCursor(&botDrivers.oled, 0, 0);
        OLED_PutString(&botDrivers.oled, "   CALIBRATED");
        OLED_SetCursor(&botDrivers.oled, 0, 1);
        OLED_PutString(&botDrivers.oled, "TH: ");
        OLED_putIntVariable(&botDrivers.oled, threshold);
        sleep(2);
        COLOR_SetLED(botDrivers.drivingDriver.colorSensor, 1);
        usleep(120000);

        searchTheLine(&botDrivers, threshold, increments);

        OLED_ClearBuffer(&botDrivers.oled);
        OLED_SetCursor(&botDrivers.oled, 0, 0);
        OLED_PutString(&botDrivers.oled, " BTN2 RUN");
        while (!BUTTONS_DRIVER_button2_pressed(&botDrivers.buttonsDriver)) {
        } // wait for button 2

        if (!SWITCHES_DRIVER_poll_switch2(&botDrivers.switchesDriver)) {
            OLED_PutString(&botDrivers.oled, " SW2 TO START  ");
        }
        while (!SWITCHES_DRIVER_poll_switch2(&botDrivers.switchesDriver)) {
        } // wait for swicth 2

        OLED_ClearBuffer(&botDrivers.oled);
        OLED_SetCursor(&botDrivers.oled, 0, 0);
        OLED_PutString(&botDrivers.oled, "     RUNNING");

        OLED_SetCursor(&botDrivers.oled, 0, 1);
        OLED_PutString(&botDrivers.oled, "  SW2 TO STOP   ");

        COLOR_SetLED(botDrivers.drivingDriver.colorSensor, 1);
        usleep(12000);

        LIGHT_PID_CONTROLLER_init(botDrivers.drivingDriver.lightPIDController,
        BOT_LIGHT_PID_K_PROPORTIONAL,
        BOT_LIGHT_PID_K_INTEGRAL,
        BOT_LIGHT_PID_K_DERIVATIVE, .10);

        while (SWITCHES_DRIVER_poll_switch2(&botDrivers.switchesDriver)) {
            DRIVING_DRIVER_drive_forward_continuous_light(
                    &botDrivers.drivingDriver, .2, threshold);
        }

        DRIVING_DRIVER_delay_until_stop(&botDrivers.drivingDriver);

        COLOR_SetLED(botDrivers.drivingDriver.colorSensor, 0);
    }

}

CalibrationData DemoInitCalibrationData(COLOR_Data firstSample) {
    CalibrationData calib;
    calib.min = firstSample;
    calib.max = firstSample;
    return calib;
}

void DemoCalibrate(COLOR_Data newSample, CalibrationData *calib) {
    if (newSample.c < calib->min.c)
        calib->min.c = newSample.c;
    if (newSample.r < calib->min.r)
        calib->min.r = newSample.r;
    if (newSample.g < calib->min.g)
        calib->min.g = newSample.g;
    if (newSample.b < calib->min.b)
        calib->min.b = newSample.b;

    if (newSample.c > calib->max.c)
        calib->max.c = newSample.c;
    if (newSample.r > calib->max.r)
        calib->max.r = newSample.r;
    if (newSample.g > calib->max.g)
        calib->max.g = newSample.g;
    if (newSample.b > calib->max.b)
        calib->max.b = newSample.b;
}

void rotate15degreesLeft(BotDrivers* botDrivers) {
    COLOR_SetLED(botDrivers->drivingDriver.colorSensor, 1);
    sleep(1);
    DRIVING_DRIVER_turn_left_degrees(&botDrivers->drivingDriver, 15);
}

u16 getThreshold(BotDrivers* botDrivers, int increments) {
    CalibrationData calib;

    u16 prevLight = DRIVING_DRIVER_light(
            COLOR_GetData(botDrivers->drivingDriver.colorSensor));

    int32_t maxLightDelta = 0;
    u16 actualLight = 0;
    u16 thresholdMin = 0;
    u16 thresholdMax = 0;

    COLOR_Data data;
// go 30 degrees to the right
    for (int degrees = 0; degrees < 30 / increments; degrees += increments) {
        DRIVING_DRIVER_turn_right_continuous_degrees(&botDrivers->drivingDriver,
                increments);

        usleep(120000);
        data = COLOR_GetData(botDrivers->drivingDriver.colorSensor);
        actualLight = DRIVING_DRIVER_light(data);
        if (abs(actualLight - prevLight) > maxLightDelta) {
            thresholdMin = MIN(actualLight, prevLight);
            thresholdMax = MAX(actualLight, prevLight);
            maxLightDelta = thresholdMax - thresholdMin;
        }
        DemoCalibrate(data, &calib);
    }

    COLOR_SetLED(botDrivers->drivingDriver.colorSensor, 0);
    DRIVING_DRIVER_delay_until_stop(&botDrivers->drivingDriver);

    u16 threshold = thresholdMin + (thresholdMax - thresholdMin) / 8;
    return threshold;
}

void searchTheLine(BotDrivers* botDrivers, u16 threshold, int increments) {
    COLOR_Data data;
    data = COLOR_GetData(botDrivers->drivingDriver.colorSensor);
    OLED_SetCharUpdate(&botDrivers->oled, 0);

    while (DRIVING_DRIVER_light(data) > threshold) {
        DRIVING_DRIVER_turn_left_continuous_degrees(&botDrivers->drivingDriver,
                increments);

        OLED_ClearBuffer(&botDrivers->oled);

        OLED_SetCursor(&botDrivers->oled, 0, 0);
        OLED_PutString(&botDrivers->oled, "DAT:");
        OLED_putIntVariable(&botDrivers->oled,
                (int32_t) DRIVING_DRIVER_light(data));

        OLED_SetCursor(&botDrivers->oled, 0, 3);
        OLED_PutString(&botDrivers->oled, "THD:");
        OLED_putIntVariable(&botDrivers->oled, (int32_t) threshold);

        OLED_Update(&botDrivers->oled);
        usleep(120000);
        data = COLOR_GetData(botDrivers->drivingDriver.colorSensor);
    }
    COLOR_SetLED(botDrivers->drivingDriver.colorSensor, 0);
}


Light Difference PID Controller source code

A new PID controller has been added to the library with the goal of minimizing the difference to the established light threshold.

/************************************************************************/
/*                                                                      */
/* light_pid_control.c PID controller for controlling motor speed       */
/* with goal minimizing ligth difference from target                    */
/************************************************************************/
/*  This file is part of the Arty S7 Bot Library                        */
/*  Parts of this Library are based in Arvin Tang's ArtyBot Library     */
/************************************************************************/
/*    Author:     Enrique Albertos                                      */
/************************************************************************/

/*
 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.
 */

/************************************************************************/
/*  Module Description:                                                 */
/*  This module implements a PID controller to compute new duty cycles  */
/*  for the right and left motors with goal of minimizing the light     */
/*  difference from target to 0                                         */
/*  Assumes that this function gets called at regular time intervals    */
/*                                                                      */
/*                                                                      */
/************************************************************************/
/*  Revision History:                                                   */
/*                                                                      */
/*     2022/07/16: (EAC) created                                         */
/*                                                                      */
/************************************************************************/

#include "light_pid_control.h"

/**
 * void LIGHT_PID_CONTROLLER_init(LightPIDController * controller,
 *         double KProportional, double KIntegral, double KDerivative,
 *         double baseDutyCyclePct)
 *
 * Uses a PID controller to compute new duty cycles for motor1 and motor2
 * with goal of minimizing light difference from target. Assumes that this
 * function gets called at regular time intervals.
 *
 * @param controller            Distance PID controller configuration and state
 * @param KProportional         PID proportional term
 * @param KIntegral             PID Integral term
 * @param KDerivative           PID Derivative term
 * @param baseDutyCyclePct      Base duty cycle percentage
 */
void LIGHT_PID_CONTROLLER_init(LightPIDController * controller,
        double KProportional, double KIntegral, double KDerivative,
        double baseDutyCyclePct) {

    controller->KProportional = KProportional;
    controller->KIntegral = KIntegral;
    controller->KDerivative = KDerivative;
    controller->baseDutyCyclePct = baseDutyCyclePct;

}

/**
 * void LIGHT_PID_CONTROLLER_set_duty_cycle(LightPIDController * controller,
 *       double baseDutyCyclePct)
 *
 * Set the new base duty cycle
 *
 * @param controller        Distance PID controller configuration and state
 * @param baseDutyCyclePct  Base duty cycle percentage 0.4 typical 0.75 for fast speed
 *                          If using PMODColor do not exceed .2 for fast
 */
void LIGHT_PID_CONTROLLER_set_duty_cycle(LightPIDController * controller,
        double baseDutyCyclePct) {
    controller->baseDutyCyclePct = baseDutyCyclePct;
}

/**
 * void LIGHT_PID_CONTROLLER_get_new_outputs(
 *      LightPIDController * controller, int light_diff, double dutyCyclePct[])
 *
 *  Uses a PID controller to compute new duty cycles for the right motor and the left motor
 *  with goal of minimizing light difference to 0 and store them in duty_cycle.
 *  Assumes that this function gets called at regular time intervals
 *
 * @param controller        Distance PID controller configuration and state
 * @param light_diff
 * @param dutyCyclePct      returns base duty cycle values (from 0.0 to 1.0)
 *                          for right and left motors
 */
void LIGHT_PID_CONTROLLER_get_new_outputs(
        LightPIDController * controller, int light_diff, double dutyCyclePct[]) {

    controller->accumulated_error += light_diff;


    double correction = controller->KProportional * light_diff
            + controller->KIntegral * controller->accumulated_error
            + controller->KDerivative * (light_diff - controller->previous_error);


    if (correction > 0.0) {
        dutyCyclePct[0] = controller->baseDutyCyclePct + correction; //
        dutyCyclePct[1] = controller->baseDutyCyclePct ;
    } else  {
        dutyCyclePct[0] = controller->baseDutyCyclePct;
        dutyCyclePct[1] = controller->baseDutyCyclePct - correction;
    }
    controller->previous_error = light_diff;

    // Bound duty cycles between 0 and 1
    if (dutyCyclePct[0] < 0.0) {
        dutyCyclePct[0] = 0.0;
    } else if (dutyCyclePct[0] > 1.0) {
        dutyCyclePct[0] = 1.0;
    }

    if (dutyCyclePct[1] < 0.0) {
        dutyCyclePct[1] = 0.0;
    } else if (dutyCyclePct[1] > 1.0) {
        dutyCyclePct[1] = 1.0;
    }

}

/**
 * void LIGHT_PID_CONTROLLER_reset_errors(LightPIDController * controller)
 *
 * Reset accumulated errors and previous errors to 0
 *
 * @param controller    Distance PID controller configuration and state
 */
void LIGHT_PID_CONTROLLER_reset_errors(LightPIDController * controller) {
    controller->accumulated_error = 0;
    controller->previous_error = 0;
}


New Driving Driver function source code

void DRIVING_DRIVER_drive_forward_continuous_light(DrivingDriver* driver, double distanceCm, u16 lightTarget);

/**
 * Drive motors given distance using light control (motors will have
 *       turned about the same amount at the end)
 * @param driver        Driving driver to use with its actual state
 * @param distanceCm    Distance in cm to drive the Bot
 * @param lightTarget   The target light value
 */
void DRIVING_DRIVER_drive_forward_continuous_light(DrivingDriver* driver,
        double distanceCm, u16 lightTarget) {
    DRIVING_DRIVER_set_direction_forward(driver);
    DRIVING_DRIVER_drive_light(driver, distanceCm, lightTarget);
}

/**
 * Returns a value of the sensed light
 *
 * @param sample
 * @return a value of the sensed light
 */
u16 DRIVING_DRIVER_light(COLOR_Data sample) {
    return sample.r;
}

/**
 * void DRIVING_DRIVER_drive_cm(DrivingDriver* driver, double distance_cm)
 *
 * @details Drive motors given distance using light control (motors will have
 *       turned about the same amount at the end)
 *
 * @param driver            Driving driver to use with its actual state
 * @param distance_cm       Distance in cm to drive the Bot
 * @param lightTarget        The target light value
 */
void DRIVING_DRIVER_drive_light(DrivingDriver* driver, double distance_cm,
        u16 lightTarget) {

    int16_t dist_converted = (int16_t) (distance_cm
            * driver->distanceCmCorrection); // TODO cm to sensed edges

    int16_t light_diff = DRIVING_DRIVER_light(COLOR_GetData(driver->colorSensor)) - lightTarget;
    double duty_cycle[2];

    LIGHT_PID_CONTROLLER_get_new_outputs(driver->lightPIDController, light_diff,
            duty_cycle);

    int16_t dist_traveled = MOTOR_POSITION_get_distance_traveled(
            driver->motorPosition);

    disableMotors(driver);

    PWM_DRIVER_set_duty_pct(driver->pwmRightMotor, duty_cycle[RIGHT_MOTOR]);
    PWM_DRIVER_set_duty_pct(driver->pwmLeftMotor, duty_cycle[LEFT_MOTOR]);

    enableMotors(driver);

    while (dist_traveled < dist_converted) {
        usleep(SAMPLE_PER);

        light_diff = DRIVING_DRIVER_light(COLOR_GetData(driver->colorSensor)) - lightTarget;

        LIGHT_PID_CONTROLLER_get_new_outputs(driver->lightPIDController, light_diff,
                duty_cycle);

        disableMotors(driver);

        PWM_DRIVER_set_duty_pct(driver->pwmRightMotor, duty_cycle[RIGHT_MOTOR]);
        PWM_DRIVER_set_duty_pct(driver->pwmLeftMotor, duty_cycle[LEFT_MOTOR]);

        enableMotors(driver);

        dist_traveled = MOTOR_POSITION_get_distance_traveled(
                driver->motorPosition);

    }

    driver->previousLightDifference = light_diff;

    disableMotors(driver);

}


FPGA Hardware Design

We just have to add a new Pmod COLOR module from the Digilent library and assign the pmod JC port.
The automatic connection wizard leaves several pins of the JC connector undefined, we define them through the constraints file.

Refer to previous blogs for more information about this design and how to store the bitstream to program the FPGA inside non-volatile flash memory.


Constraints

New constraints file:

## This file is a general .xdc for the Arty S7-50 Rev. E
## To use it in a project:
## - uncomment the lines corresponding to used pins
## - rename the used ports (in each line, after get_ports) according to the top level signal names in the project

## Clock Signals
#set_property -dict { PACKAGE_PIN F14   IOSTANDARD LVCMOS33 } [get_ports { CLK12MHZ }]; #IO_L13P_T2_MRCC_15 Sch=uclk
#create_clock -add -name sys_clk_pin -period 83.333 -waveform {0 41.667} [get_ports { CLK12MHZ }];
#set_property -dict { PACKAGE_PIN R2    IOSTANDARD SSTL135 } [get_ports { CLK100MHZ }]; #IO_L12P_T1_MRCC_34 Sch=ddr3_clk[200]
#create_clock -add -name sys_clk_pin -period 10.000 -waveform {0 5.000}  [get_ports { CLK100MHZ }];

## Switches
#set_property -dict { PACKAGE_PIN H14   IOSTANDARD LVCMOS33 } [get_ports { sw[0] }]; #IO_L20N_T3_A19_15 Sch=sw[0]
#set_property -dict { PACKAGE_PIN H18   IOSTANDARD LVCMOS33 } [get_ports { sw[1] }]; #IO_L21P_T3_DQS_15 Sch=sw[1]
#set_property -dict { PACKAGE_PIN G18   IOSTANDARD LVCMOS33 } [get_ports { sw[2] }]; #IO_L21N_T3_DQS_A18_15 Sch=sw[2]
#set_property -dict { PACKAGE_PIN M5    IOSTANDARD SSTL135 } [get_ports { sw[3] }]; #IO_L6N_T0_VREF_34 Sch=sw[3]

## RGB LEDs
#set_property -dict { PACKAGE_PIN J15   IOSTANDARD LVCMOS33 } [get_ports { led0_r }]; #IO_L23N_T3_FWE_B_15 Sch=led0_r
#set_property -dict { PACKAGE_PIN G17   IOSTANDARD LVCMOS33 } [get_ports { led0_g }]; #IO_L14N_T2_SRCC_15 Sch=led0_g
#set_property -dict { PACKAGE_PIN F15   IOSTANDARD LVCMOS33 } [get_ports { led0_b }]; #IO_L13N_T2_MRCC_15 Sch=led0_b
#set_property -dict { PACKAGE_PIN E15   IOSTANDARD LVCMOS33 } [get_ports { led1_r }]; #IO_L15N_T2_DQS_ADV_B_15 Sch=led1_r
#set_property -dict { PACKAGE_PIN F18   IOSTANDARD LVCMOS33 } [get_ports { led1_g }]; #IO_L16P_T2_A28_15 Sch=led1_g
#set_property -dict { PACKAGE_PIN E14   IOSTANDARD LVCMOS33 } [get_ports { led1_b }]; #IO_L15P_T2_DQS_15 Sch=led1_b

## LEDs
#set_property -dict { PACKAGE_PIN E18   IOSTANDARD LVCMOS33 } [get_ports { led[0] }]; #IO_L16N_T2_A27_15 Sch=led[2]
#set_property -dict { PACKAGE_PIN F13   IOSTANDARD LVCMOS33 } [get_ports { led[1] }]; #IO_L17P_T2_A26_15 Sch=led[3]
#set_property -dict { PACKAGE_PIN E13   IOSTANDARD LVCMOS33 } [get_ports { led[2] }]; #IO_L17N_T2_A25_15 Sch=led[4]
#set_property -dict { PACKAGE_PIN H15   IOSTANDARD LVCMOS33 } [get_ports { led[3] }]; #IO_L18P_T2_A24_15 Sch=led[5]

## Buttons
#set_property -dict { PACKAGE_PIN G15   IOSTANDARD LVCMOS33 } [get_ports { btn[0] }]; #IO_L18N_T2_A23_15 Sch=btn[0]
#set_property -dict { PACKAGE_PIN K16   IOSTANDARD LVCMOS33 } [get_ports { btn[1] }]; #IO_L19P_T3_A22_15 Sch=btn[1]
#set_property -dict { PACKAGE_PIN J16   IOSTANDARD LVCMOS33 } [get_ports { btn[2] }]; #IO_L19N_T3_A21_VREF_15 Sch=btn[2]
#set_property -dict { PACKAGE_PIN H13   IOSTANDARD LVCMOS33 } [get_ports { btn[3] }]; #IO_L20P_T3_A20_15 Sch=btn[3]

## Pmod Header JA
#set_property -dict { PACKAGE_PIN L17   IOSTANDARD LVCMOS33 } [get_ports { ja[0] }]; #IO_L4P_T0_D04_14 Sch=ja_p[1]
#set_property -dict { PACKAGE_PIN L18   IOSTANDARD LVCMOS33 } [get_ports { ja[1] }]; #IO_L4N_T0_D05_14 Sch=ja_n[1]
#set_property -dict { PACKAGE_PIN M14   IOSTANDARD LVCMOS33 } [get_ports { ja[2] }]; #IO_L5P_T0_D06_14 Sch=ja_p[2]
#set_property -dict { PACKAGE_PIN N14   IOSTANDARD LVCMOS33 } [get_ports { ja[3] }]; #IO_L5N_T0_D07_14 Sch=ja_n[2]
#set_property -dict { PACKAGE_PIN M16   IOSTANDARD LVCMOS33 } [get_ports { ja[4] }]; #IO_L7P_T1_D09_14 Sch=ja_p[3]
#set_property -dict { PACKAGE_PIN M17   IOSTANDARD LVCMOS33 } [get_ports { ja[5] }]; #IO_L7N_T1_D10_14 Sch=ja_n[3]
#set_property -dict { PACKAGE_PIN M18   IOSTANDARD LVCMOS33 } [get_ports { ja[6] }]; #IO_L8P_T1_D11_14 Sch=ja_p[4]
#set_property -dict { PACKAGE_PIN N18   IOSTANDARD LVCMOS33 } [get_ports { ja[7] }]; #IO_L8N_T1_D12_14 Sch=ja_n[4]

## Pmod Header JB
#set_property -dict { PACKAGE_PIN P17   IOSTANDARD LVCMOS33 } [get_ports { jb[0] }]; #IO_L9P_T1_DQS_14 Sch=jb_p[1]
#set_property -dict { PACKAGE_PIN P18   IOSTANDARD LVCMOS33 } [get_ports { jb[1] }]; #IO_L9N_T1_DQS_D13_14 Sch=jb_n[1]
#set_property -dict { PACKAGE_PIN R18   IOSTANDARD LVCMOS33 } [get_ports { jb[2] }]; #IO_L10P_T1_D14_14 Sch=jb_p[2]
#set_property -dict { PACKAGE_PIN T18   IOSTANDARD LVCMOS33 } [get_ports { jb[3] }]; #IO_L10N_T1_D15_14 Sch=jb_n[2]
set_property -dict {PACKAGE_PIN P14 IOSTANDARD LVCMOS33} [get_ports jb_pin7_io]
set_property -dict {PACKAGE_PIN P15 IOSTANDARD LVCMOS33} [get_ports jb_pin8_io]
set_property -dict {PACKAGE_PIN N15 IOSTANDARD LVCMOS33} [get_ports jb_pin9_io]
set_property -dict {PACKAGE_PIN P16 IOSTANDARD LVCMOS33} [get_ports jb_pin10_io]

## Pmod Header JC
#set_property -dict { PACKAGE_PIN U15   IOSTANDARD LVCMOS33 } [get_ports { jc[0] }]; #IO_L18P_T2_A12_D28_14 Sch=jc1/ck_io[41]
#set_property -dict { PACKAGE_PIN V16   IOSTANDARD LVCMOS33 } [get_ports { jc[1] }]; #IO_L18N_T2_A11_D27_14 Sch=jc2/ck_io[40]
#set_property -dict { PACKAGE_PIN U17   IOSTANDARD LVCMOS33 } [get_ports { jc[2] }]; #IO_L15P_T2_DQS_RDWR_B_14 Sch=jc3/ck_io[39]
#set_property -dict { PACKAGE_PIN U18   IOSTANDARD LVCMOS33 } [get_ports { jc[3] }]; #IO_L15N_T2_DQS_DOUT_CSO_B_14 Sch=jc4/ck_io[38]
set_property -dict { PACKAGE_PIN U16   IOSTANDARD LVCMOS33 } [get_ports { jc_pin7_io }]; #IO_L16P_T2_CSI_B_14 Sch=jc7/ck_io[37]
set_property -dict { PACKAGE_PIN P13   IOSTANDARD LVCMOS33 } [get_ports { jc_pin8_io }]; #IO_L19P_T3_A10_D26_14 Sch=jc8/ck_io[36]
set_property -dict { PACKAGE_PIN R13   IOSTANDARD LVCMOS33 } [get_ports { jc_pin9_io }]; #IO_L19N_T3_A09_D25_VREF_14 Sch=jc9/ck_io[35]
set_property -dict { PACKAGE_PIN V14   IOSTANDARD LVCMOS33 } [get_ports { jc_pin10_io }]; #IO_L20P_T3_A08_D24_14 Sch=jc10/ck_io[34]

## Pmod Header JD
#set_property -dict { PACKAGE_PIN V15   IOSTANDARD LVCMOS33 } [get_ports { jd[0] }]; #IO_L20N_T3_A07_D23_14 Sch=jd1/ck_io[33]
#set_property -dict { PACKAGE_PIN U12   IOSTANDARD LVCMOS33 } [get_ports { jd[1] }]; #IO_L21P_T3_DQS_14 Sch=jd2/ck_io[32]
#set_property -dict { PACKAGE_PIN V13   IOSTANDARD LVCMOS33 } [get_ports { jd[2] }]; #IO_L21N_T3_DQS_A06_D22_14 Sch=jd3/ck_io[31]
#set_property -dict { PACKAGE_PIN T12   IOSTANDARD LVCMOS33 } [get_ports { jd[3] }]; #IO_L22P_T3_A05_D21_14 Sch=jd4/ck_io[30]
#set_property -dict { PACKAGE_PIN T13   IOSTANDARD LVCMOS33 } [get_ports { jd[4] }]; #IO_L22N_T3_A04_D20_14 Sch=jd7/ck_io[29]
#set_property -dict { PACKAGE_PIN R11   IOSTANDARD LVCMOS33 } [get_ports { jd[5] }]; #IO_L23P_T3_A03_D19_14 Sch=jd8/ck_io[28]
#set_property -dict { PACKAGE_PIN T11   IOSTANDARD LVCMOS33 } [get_ports { jd[6] }]; #IO_L23N_T3_A02_D18_14 Sch=jd9/ck_io[27]
#set_property -dict { PACKAGE_PIN U11   IOSTANDARD LVCMOS33 } [get_ports { jd[7] }]; #IO_L24P_T3_A01_D17_14 Sch=jd10/ck_io[26]

## USB-UART Interface
#set_property -dict { PACKAGE_PIN R12   IOSTANDARD LVCMOS33 } [get_ports { uart_rxd_out }]; #IO_25_14 Sch=uart_rxd_out
#set_property -dict { PACKAGE_PIN V12   IOSTANDARD LVCMOS33 } [get_ports { uart_txd_in }]; #IO_L24N_T3_A00_D16_14 Sch=uart_txd_in

## ChipKit Outer Digital Header
# Right Motor Control
set_property -dict {PACKAGE_PIN L13 IOSTANDARD LVCMOS33} [get_ports pwm0_0]
set_property -dict {PACKAGE_PIN N13 IOSTANDARD LVCMOS33} [get_ports {hbridge_control[0]}]
set_property -dict {PACKAGE_PIN L16 IOSTANDARD LVCMOS33} [get_ports {hbridge_control[1]}]
# Left motor Control
set_property -dict {PACKAGE_PIN R14 IOSTANDARD LVCMOS33} [get_ports pwm0_1]
set_property -dict {PACKAGE_PIN T14 IOSTANDARD LVCMOS33} [get_ports {hbridge_control[2]}]
set_property -dict {PACKAGE_PIN R16 IOSTANDARD LVCMOS33} [get_ports {hbridge_control[3]}]

set_property -dict {PACKAGE_PIN R17 IOSTANDARD LVCMOS33} [get_ports m1_sensor_0]
set_property -dict {PACKAGE_PIN V17 IOSTANDARD LVCMOS33} [get_ports m2_sensor_0]
#set_property -dict { PACKAGE_PIN R15   IOSTANDARD LVCMOS33 } [get_ports { ck_io8 }]; #IO_L17P_T2_A14_D30_14   Sch=ck_io[8]
#set_property -dict { PACKAGE_PIN T15   IOSTANDARD LVCMOS33 } [get_ports { ck_io9 }]; #IO_L17N_T2_A13_D29_14   Sch=ck_io[9]

## ChipKit SPI Header
## NOTE: The ChipKit SPI header ports can also be used as digital I/O and share FPGA pins with ck_io10-13. Do not use both at the same time.
#set_property -dict { PACKAGE_PIN H16   IOSTANDARD LVCMOS33 } [get_ports { ck_io10_ss   }]; #IO_L22P_T3_A17_15   Sch=ck_io10_ss
#set_property -dict { PACKAGE_PIN H17   IOSTANDARD LVCMOS33 } [get_ports { ck_io11_mosi }]; #IO_L22N_T3_A16_15   Sch=ck_io11_mosi
#set_property -dict { PACKAGE_PIN K14   IOSTANDARD LVCMOS33 } [get_ports { ck_io12_miso }]; #IO_L23P_T3_FOE_B_15 Sch=ck_io12_miso
#set_property -dict { PACKAGE_PIN G16   IOSTANDARD LVCMOS33 } [get_ports { ck_io13_sck  }]; #IO_L14P_T2_SRCC_15  Sch=ck_io13_sck

## ChipKit Inner Digital Header
## Note: these pins are shared with PMOD Headers JC and JD and cannot be used at the same time as the applicable PMOD interface(s)
#set_property -dict { PACKAGE_PIN U11   IOSTANDARD LVCMOS33 } [get_ports { ck_io26 }]; #IO_L24P_T3_A01_D17_14        Sch=jd10/ck_io[26]
#set_property -dict { PACKAGE_PIN T11   IOSTANDARD LVCMOS33 } [get_ports { ck_io27 }]; #IO_L23N_T3_A02_D18_14        Sch=jd9/ck_io[27]
#set_property -dict { PACKAGE_PIN R11   IOSTANDARD LVCMOS33 } [get_ports { ck_io28 }]; #IO_L23P_T3_A03_D19_14        Sch=jd8/ck_io[28]
#set_property -dict { PACKAGE_PIN T13   IOSTANDARD LVCMOS33 } [get_ports { ck_io29 }]; #IO_L22N_T3_A04_D20_14        Sch=jd7/ck_io[29]
#set_property -dict { PACKAGE_PIN T12   IOSTANDARD LVCMOS33 } [get_ports { ck_io30 }]; #IO_L22P_T3_A05_D21_14        Sch=jd4/ck_io[30]
#set_property -dict { PACKAGE_PIN V13   IOSTANDARD LVCMOS33 } [get_ports { ck_io31 }]; #IO_L21N_T3_DQS_A06_D22_14    Sch=jd3/ck_io[31]
#set_property -dict { PACKAGE_PIN U12   IOSTANDARD LVCMOS33 } [get_ports { ck_io32 }]; #IO_L21P_T3_DQS_14            Sch=jd2/ck_io[32]
#set_property -dict { PACKAGE_PIN V15   IOSTANDARD LVCMOS33 } [get_ports { ck_io33 }]; #IO_L20N_T3_A07_D23_14        Sch=jd1/ck_io[33]
#set_property -dict { PACKAGE_PIN V14   IOSTANDARD LVCMOS33 } [get_ports { ck_io34 }]; #IO_L20P_T3_A08_D24_14        Sch=jc10/ck_io[34]
#set_property -dict { PACKAGE_PIN R13   IOSTANDARD LVCMOS33 } [get_ports { ck_io35 }]; #IO_L19N_T3_A09_D25_VREF_14   Sch=jc9/ck_io[35]
#set_property -dict { PACKAGE_PIN P13   IOSTANDARD LVCMOS33 } [get_ports { ck_io36 }]; #IO_L19P_T3_A10_D26_14        Sch=jc8/ck_io[36]
#set_property -dict { PACKAGE_PIN U16   IOSTANDARD LVCMOS33 } [get_ports { ck_io37 }]; #IO_L16P_T2_CSI_B_14          Sch=jc7/ck_io[37]
#set_property -dict { PACKAGE_PIN U18   IOSTANDARD LVCMOS33 } [get_ports { ck_io38 }]; #IO_L15N_T2_DQS_DOUT_CSO_B_14 Sch=jc4/ck_io[38]
#set_property -dict { PACKAGE_PIN U17   IOSTANDARD LVCMOS33 } [get_ports { ck_io39 }]; #IO_L15P_T2_DQS_RDWR_B_14     Sch=jc3/ck_io[39]
#set_property -dict { PACKAGE_PIN V16   IOSTANDARD LVCMOS33 } [get_ports { ck_io40 }]; #IO_L18N_T2_A11_D27_14        Sch=jc2/ck_io[40]
#set_property -dict { PACKAGE_PIN U15   IOSTANDARD LVCMOS33 } [get_ports { ck_io41 }]; #IO_L18P_T2_A12_D28_14        Sch=jc1/ck_io[41]

## Dedicated Analog Inputs
#set_property -dict { PACKAGE_PIN J10   } [get_ports { vp_in }]; #IO_L1P_T0_AD4P_35 Sch=v_p
#set_property -dict { PACKAGE_PIN K9    } [get_ports { vn_in }]; #IO_L1N_T0_AD4N_35 Sch=v_n

## ChipKit Outer Analog Header - as Single-Ended Analog Inputs
## NOTE: These ports can be used as single-ended analog inputs with voltages from 0-3.3V (ChipKit analog pins A0-A5) or as digital I/O.
## WARNING: Do not use both sets of constraints at the same time!
## NOTE: The following constraints should be used with the XADC IP core when using these ports as analog inputs.
#set_property -dict { PACKAGE_PIN B13   IOSTANDARD LVCMOS33 } [get_ports { vaux0_p  }]; #IO_L1P_T0_AD0P_15     Sch=ck_an_p[0]   ChipKit pin=A0
#set_property -dict { PACKAGE_PIN A13   IOSTANDARD LVCMOS33 } [get_ports { vaux0_n  }]; #IO_L1N_T0_AD0N_15     Sch=ck_an_n[0]   ChipKit pin=A0
#set_property -dict { PACKAGE_PIN B15   IOSTANDARD LVCMOS33 } [get_ports { vaux1_p  }]; #IO_L3P_T0_DQS_AD1P_15 Sch=ck_an_p[1]   ChipKit pin=A1
#set_property -dict { PACKAGE_PIN A15   IOSTANDARD LVCMOS33 } [get_ports { vaux1_n  }]; #IO_L3N_T0_DQS_AD1N_15 Sch=ck_an_n[1]   ChipKit pin=A1
#set_property -dict { PACKAGE_PIN E12   IOSTANDARD LVCMOS33 } [get_ports { vaux9_p  }]; #IO_L5P_T0_AD9P_15     Sch=ck_an_p[2]   ChipKit pin=A2
#set_property -dict { PACKAGE_PIN D12   IOSTANDARD LVCMOS33 } [get_ports { vaux9_n  }]; #IO_L5N_T0_AD9N_15     Sch=ck_an_n[2]   ChipKit pin=A2
#set_property -dict { PACKAGE_PIN B17   IOSTANDARD LVCMOS33 } [get_ports { vaux2_p  }]; #IO_L7P_T1_AD2P_15     Sch=ck_an_p[3]   ChipKit pin=A3
#set_property -dict { PACKAGE_PIN A17   IOSTANDARD LVCMOS33 } [get_ports { vaux2_n  }]; #IO_L7N_T1_AD2N_15     Sch=ck_an_n[3]   ChipKit pin=A3
#set_property -dict { PACKAGE_PIN C17   IOSTANDARD LVCMOS33 } [get_ports { vaux10_p }]; #IO_L8P_T1_AD10P_15    Sch=ck_an_p[4]   ChipKit pin=A4
#set_property -dict { PACKAGE_PIN B18   IOSTANDARD LVCMOS33 } [get_ports { vaux10_n }]; #IO_L8N_T1_AD10N_15    Sch=ck_an_n[4]   ChipKit pin=A4
#set_property -dict { PACKAGE_PIN E16   IOSTANDARD LVCMOS33 } [get_ports { vaux11_p }]; #IO_L10P_T1_AD11P_15   Sch=ck_an_p[5]   ChipKit pin=A5
#set_property -dict { PACKAGE_PIN E17   IOSTANDARD LVCMOS33 } [get_ports { vaux11_n }]; #IO_L10N_T1_AD11N_15   Sch=ck_an_n[5]   ChipKit pin=A5
## ChipKit Outer Analog Header - as Digital I/O
## NOTE: The following constraints should be used when using these ports as digital I/O.
#set_property -dict { PACKAGE_PIN G13   IOSTANDARD LVCMOS33 } [get_ports { ck_a0 }]; #IO_0_15            Sch=ck_a[0]
#set_property -dict { PACKAGE_PIN B16   IOSTANDARD LVCMOS33 } [get_ports { ck_a1 }]; #IO_L4P_T0_15       Sch=ck_a[1]
#set_property -dict { PACKAGE_PIN A16   IOSTANDARD LVCMOS33 } [get_ports { ck_a2 }]; #IO_L4N_T0_15       Sch=ck_a[2]
#set_property -dict { PACKAGE_PIN C13   IOSTANDARD LVCMOS33 } [get_ports { ck_a3 }]; #IO_L6P_T0_15       Sch=ck_a[3]
#set_property -dict { PACKAGE_PIN C14   IOSTANDARD LVCMOS33 } [get_ports { ck_a4 }]; #IO_L6N_T0_VREF_15  Sch=ck_a[4]
#set_property -dict { PACKAGE_PIN D18   IOSTANDARD LVCMOS33 } [get_ports { ck_a5 }]; #IO_L11P_T1_SRCC_15 Sch=ck_a[5]

## ChipKit Inner Analog Header - as Differential Analog Inputs
## NOTE: These ports can be used as differential analog inputs with voltages from 0-1.0V (ChipKit analog pins A6-A11) or as digital I/O.
## WARNING: Do not use both sets of constraints at the same time!
## NOTE: The following constraints should be used with the XADC core when using these ports as analog inputs.
#set_property -dict { PACKAGE_PIN B14   IOSTANDARD LVCMOS33 } [get_ports { vaux8_p }]; #IO_L2P_T0_AD8P_15     Sch=ad_p[8]   ChipKit pin=A6
#set_property -dict { PACKAGE_PIN A14   IOSTANDARD LVCMOS33 } [get_ports { vaux8_n }]; #IO_L2N_T0_AD8N_15     Sch=ad_n[8]   ChipKit pin=A7
#set_property -dict { PACKAGE_PIN D16   IOSTANDARD LVCMOS33 } [get_ports { vaux3_p }]; #IO_L9P_T1_DQS_AD3P_15 Sch=ad_p[3]   ChipKit pin=A8
#set_property -dict { PACKAGE_PIN D17   IOSTANDARD LVCMOS33 } [get_ports { vaux3_n }]; #IO_L9N_T1_DQS_AD3N_15 Sch=ad_n[3]   ChipKit pin=A9
## ChipKit Inner Analog Header - as Digital I/O
## NOTE: The following constraints should be used when using the inner analog header ports as digital I/O.
#set_property -dict { PACKAGE_PIN B14   IOSTANDARD LVCMOS33 } [get_ports { ck_a6  }]; #IO_L2P_T0_AD8P_15     Sch=ad_p[8]
#set_property -dict { PACKAGE_PIN A14   IOSTANDARD LVCMOS33 } [get_ports { ck_a7  }]; #IO_L2N_T0_AD8N_15     Sch=ad_n[8]
#set_property -dict { PACKAGE_PIN D16   IOSTANDARD LVCMOS33 } [get_ports { ck_a8  }]; #IO_L9P_T1_DQS_AD3P_15 Sch=ad_p[3]
#set_property -dict { PACKAGE_PIN D17   IOSTANDARD LVCMOS33 } [get_ports { ck_a9  }]; #IO_L9N_T1_DQS_AD3N_15 Sch=ad_n[3]
#set_property -dict { PACKAGE_PIN D14   IOSTANDARD LVCMOS33 } [get_ports { ck_a10 }]; #IO_L12P_T1_MRCC_15    Sch=ck_a10_r   (Cannot be used as an analog input)
#set_property -dict { PACKAGE_PIN D15   IOSTANDARD LVCMOS33 } [get_ports { ck_a11 }]; #IO_L12N_T1_MRCC_15    Sch=ck_a11_r   (Cannot be used as an analog input)

## ChipKit I2C
#set_property -dict { PACKAGE_PIN J14   IOSTANDARD LVCMOS33 } [get_ports { ck_scl }]; #IO_L24N_T3_RS0_15 Sch=ck_scl
#set_property -dict { PACKAGE_PIN J13   IOSTANDARD LVCMOS33 } [get_ports { ck_sda }]; #IO_L24P_T3_RS1_15 Sch=ck_sda

## Misc. ChipKit Ports
#set_property -dict { PACKAGE_PIN K13   IOSTANDARD LVCMOS33 } [get_ports { ck_ioa }]; #IO_25_15 Sch=ck_ioa
#set_property -dict { PACKAGE_PIN C18   IOSTANDARD LVCMOS33 } [get_ports { ck_rst }]; #IO_L11N_T1_SRCC_15

## Quad SPI Flash
## Note: the SCK clock signal can be driven using the STARTUPE2 primitive
#set_property -dict { PACKAGE_PIN M13   IOSTANDARD LVCMOS33 } [get_ports { qspi_cs }]; #IO_L6P_T0_FCS_B_14 Sch=qspi_cs
#set_property -dict { PACKAGE_PIN K17   IOSTANDARD LVCMOS33 } [get_ports { qspi_dq[0] }]; #IO_L1P_T0_D00_MOSI_14 Sch=qspi_dq[0]
#set_property -dict { PACKAGE_PIN K18   IOSTANDARD LVCMOS33 } [get_ports { qspi_dq[1] }]; #IO_L1N_T0_D01_DIN_14 Sch=qspi_dq[1]
#set_property -dict { PACKAGE_PIN L14   IOSTANDARD LVCMOS33 } [get_ports { qspi_dq[2] }]; #IO_L2P_T0_D02_14 Sch=qspi_dq[2]
#set_property -dict { PACKAGE_PIN M15   IOSTANDARD LVCMOS33 } [get_ports { qspi_dq[3] }]; #IO_L2N_T0_D03_14 Sch=qspi_dq[3]

## Configuration options, can be used for all designs
set_property BITSTREAM.CONFIG.CONFIGRATE 33 [current_design]
set_property CONFIG_VOLTAGE 3.3 [current_design]
set_property CFGBVS VCCO [current_design]
set_property BITSTREAM.CONFIG.SPI_BUSWIDTH 4 [current_design]
set_property CONFIG_MODE SPIx4 [current_design]

## SW3 is assigned to a pin M5 in the 1.35v bank. This pin can also be used as
## the VREF for BANK 34. To ensure that SW3 does not define the reference voltage
## and to be able to use this pin as an ordinary I/O the following property must
## be set to enable an internal VREF for BANK 34. Since a 1.35v supply is being
## used the internal reference is set to half that value (i.e. 0.675v). Note that
## this property must be set even if SW3 is not used in the design.
set_property INTERNAL_VREF 0.675 [get_iobanks 34]




Emubot Following the Line

Emubot Following the Line


Summary

Our robot can already detect colors. We will use this ability in an upcoming educational project with the Emubot.
In this blog we have implemented as an exercise a painful line follower.

We discourage this way of implementing a line follower. It is an interesting exercise to fight with the PID controllers but you're not going to achieve great results.


"7 Ways to Leave Your Spartan-6" related posts
1 Arty S7 50 First Power Up and Hardware-Only Blinky
2 Arty S7 50 First Baremetal Software Project
3 Arty S7 50 Rapid Prototyping - Environmental Monitor
4 Arty S7 50 ArtyBot Pulse Width Modulation (PWM) for Motor Speed Control
5 Arty S7 50 ArtyBot Custom AXI4 Lite IP Peripheral for Sensing Motor Rotational Speed
6 Arty S7 50 ArtyBot How to Store MicroBlaze Program in the Quad-SPI Flash from Vivado
7 Arty S7 50 ArtyBot - Bot Application Framework
8 Arty S7 50 ArtyBot becomes Emubot, an educational robot for young children
9 Arty S7 ArtyBot - Color sensing and line follower
10 Arty S7 50 The Spartan-6 Migration Path Game. Learning the Differences Between Spartan-6 and Spartan-7 FPGAs
11 Arty S7 50 ArtyBot ToF Sensor for Obstacle Avoidance. Vivado Hierarchical Blocks
12 "7 Ways to Leave Your Spartan-6 FPGA" program. My summary
13 Arty S7 50 VGA Thermal Imaging Camera
Anonymous
  • javagoza
    javagoza 29 days ago in reply to DAB

    Thanks DAB for the great suggestion. We are working on a game for Emubot, the programmable sequence robot, in which you have to “collect” colored cards by going over them in the indicated order to complete the assigned tasks.

    • Cancel
    • Vote Up 0 Vote Down
    • Reply
    • More
    • Cancel
  • DAB
    DAB 30 days ago

    I can see where you could lay out different tracks in different colors and have the robot follow them in color sequence.

    • Cancel
    • Vote Up 0 Vote Down
    • Reply
    • More
    • Cancel
element14 Community

element14 is the first online community specifically for engineers. Connect with your peers and get expert answers to your questions.

  • Members
  • Learn
  • Technologies
  • Challenges & Projects
  • Products
  • Store
  • About Us
  • Feedback & Support
  • FAQs
  • Terms of Use
  • Privacy Policy
  • Legal and Copyright Notices
  • Sitemap
  • Cookies

An Avnet Company © 2022 Premier Farnell Limited. All Rights Reserved.

Premier Farnell Ltd, registered in England and Wales (no 00876412), registered office: Farnell House, Forge Lane, Leeds LS12 2NE.

ICP 备案号 10220084.

Follow element14

  • Facebook
  • Twitter
  • linkedin
  • YouTube