Reference firmware for PixArt's PMW3901MB sensor and evaluation board. "Hello World" and "Library" contain the exact same files. Please import just one of the two into your mBed compiler as a new program and not as a library.

Welcome to the code repository for PixArt's PMW3901MB sensor and evaluation board.

For general information about this product, please visit this product's components page here:
https://os.mbed.com/components/PMW3901MB-Far-Field-Optical-Motion-Track/

For guides and tips on how to setup and evaluate the PMW3901MB sensor with the Nordic nRF52-DK microcontroller using this reference code, please visit this guide:
https://os.mbed.com/teams/PixArt/code/3901_referenceFirmware/wiki/Guide-for-nRF52-DK-Platform

For guides and tips on how to setup and evaluate the PMW3901MB sensor with any microcontroller using this reference code, please visit this guide:
https://os.mbed.com/teams/PixArt/code/3901_referenceFirmware/wiki/Guide-for-Any-Platform

main.cpp

Committer:
PixArtVY
Date:
2018-07-18
Revision:
1:10365086d44e
Parent:
0:c00f2464eee3

File content as of revision 1:10365086d44e:

// PMW3901MB: Optical Motion Tracking Chip reference code.
// Version: 1.1
// Latest Revision Date: 18 July 2018
// By PixArt Imaging Inc.
// Primary Engineer: Vincent Yeh (PixArt USA)

// Copyright [2018] [Vincent Yeh]
// Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at:
// http://www.apache.org/licenses/LICENSE-2.0


/*
//=======================
//Revision History
//=======================
Version 1.1 -- 18 July 2018
Added apache license notice.

Version 1.0 -- 13 Mar. 2018
First release.
*/

#include "mbed.h"
#include "SPIcommFunctions.h"

int main()
{
    pc.baud(115200);                    // Set baud rate to 115200. Remember to sync serial terminal baud rate to the same value.

    spi.format(8,3);                    // Set SPI to 8 bits with inverted polarity and phase-shifted to second edge.
    spi.frequency(1000000);             // Set frequency for SPI communication.
    cs = 1;                             // Initialize chip select as inactive.
    
    pc.printf("Program START\n\r");
    
    pc.printf("ID Check: %2X\n\r", readRegister(0x00)); //Checks product ID to make sure communication protocol is working properly.
    if(readRegister(0x00) != 0x49)
    {
        pc.printf("Communication protocol error! Terminating program.\n\r");
        return 0;
    }
    
    initializeSensor();
    
    while(1)
    {
        //pc.printf("MOTION bit: %2X\n\r", (readRegister(0x02) & 0x80) >> 7);   //Prints motion bit for debugging. 1 = motion detected. 0 = no motion detected.
        
        if(readRegister(0x02) & 0x80)
        {
            grabData();
            printData();
        }
    }
}