Page 2
Robot Kits manual Nexus Robot A. Attention!! Please read this manual carefully before applying power on the device. B. Attention!! Do not use this device for military or medical purpose as they are not designed to. C. Attention!! Do not use over-voltage power supply ! ensure stable power supply.
www.nexusrobot.com Robot Kits manual Arduino ........................1 Introduction......................1 Hardware .......................1 Specification ....................1 Arduino Board Pinout ..................2 Arduino 328 Features..................2 Memory function ..................3 Input and Output PinMode................3 Communication..................3 Configuration ....................3 Servo Power Select Jumper ..............3 Motor Control Pin Jumper ................4 Wireless Select Jumper ................4 Arduino IO Expansion Board ................4 Features .....................4 Software.........................5...
Page 4
www.nexusrobot.com Robot Kits manual Communication Protocols...............27 Sensor Connection ..................29 Sensor Networking..................29 APC220 Module ....................30 Parameters....................30 Kit list......................30 This module used to connect PC port.............30 Pin Change Interrupt..................31 PinChangeInt Library..................31 PID Control......................33 What Is PID....................33 The Library ....................33 Servo control Theory ..................34 The PWM signal ....................35 Motorwheel......................36 Motorwheel Class Reference .................36...
www.nexusrobot.com Robot Kits manual Arduino Introduction Arduino Controller is an All-in-One microcontroller especially designed for robotics application. Benefit from Arduino open source platform, it is supported by thousands of open source codes, and can be easily expanded with most Arduino Shields.Arduino can sense the environment by receiving input from a variety of sensors and can affect its surroundings by controlling lights, motors, and other actuators.
www.nexusrobot.com Robot Kits manual Arduino Board Pinout The picture above shows all of the I/O lines and Connectors on the controller, which includes: One Regulated Motor Power Input Terminal (6v to12v) One Unregulated Servo Power Input Terminal (you supply regulated 4v to 7.2v) One Servo input power selection jumper One Serial Interface Module Header for APC220 Module Two DC Motor Terminals –...
www.nexusrobot.com Robot Kits manual Memory function The ATmega328 has 32 KB (with 0.5 KB used for the bootloader). It also has 2 KB of SRAM and 1 KB of EEPROM (which can be read and written with the EEPROM library). Input and Output PinMode Each of the 14 digital pins on the Duemilanove can be used as an input or output, using pinMode(), digitalWrite(), and digitalRead() functions.
www.nexusrobot.com Robot Kits manual When the Servo Power Select Jumper is applied, the servo is powered by internal 5V. When the Servo Power Select Jumper is not applied, the servo is powered by external power source. Motor Control Pin Jumper Applying the Motor Control Pin Jumpers will allocate Pin 4,5,6,7 for motor control.
www.nexusrobot.com Robot Kits manual 4. Supporting Bluetooth module, APC220 module; 5. Auto Switch between external and onboard power supply; 6. Supporting SD card (read&write - our SD card module is needed); 7. Supporting IIC/I2C/TWI connection See: http://www.nexusrobot.com/product.php?id_product=51 Software The open-source Arduino environment makes it easy to write code and upload it to the i/o board. It runs on Windows, Mac OS X, and Linux.
Page 10
www.nexusrobot.com Robot Kits manual 2 | Download the Arduino environment Get the latest version from the download page. When the download finishes, unzip the downloaded file. Make sure to preserve the folder structure. Double-click the folder to open it. There should be a few files and sub-folders inside. 3 | Connect the board The Arduino Uno, Mega, Duemilanove and Arduino Nano automatically draw power from either the USB connection to the computer or an external power supply.
Page 11
www.nexusrobot.com Robot Kits manual See also: step-by-step screenshots for installing the Uno under Windows XP. Installing drivers for the Arduino Duemilanove, Nano, or Diecimila with Windows7, Vista, or XP: When you connect the board, Windows should initiate the driver installation process (if you haven't used the computer with an Arduino board before).
Page 12
www.nexusrobot.com Robot Kits manual 7 | Select your board You'll need to select the entry in the Tools > Board menu that corresponds to your Arduino. For Duemilanove Arduino boards with an ATmega328 (check the text on the chip on the board), select Arduino Duemilanove or Nano w/ ATmega328.
www.nexusrobot.com Robot Kits manual in the status bar. (Note: If you have an Arduino Mini, NG, or other board, you'll need to physically present the reset button on the board immediately before pressing the upload button.) A few seconds after the upload finishes, you should see the pin 13 (L) LED on the board start to blink (in orange).
www.nexusrobot.com Robot Kits manual if (digitalRead(buttonPin) == HIGH) serialWrite('H'); else serialWrite('L'); delay(1000); Re-write Arduino bootloader If you couldn't load the bootloader via the Arduino IDE with the parallel programmer from the Arduino website. Then you can used the following method to Re-write the bootloader on your chip. FT232RL BitBang Mode AVR-Writer FT232RL is an USB-Serial bridge on an Arduino Dicimila/NG/Duemilanove PCB.
www.nexusrobot.com Robot Kits manual Downloading To downloading the "avrdude-serjtag" FTDI BitBang AVR-Writer from the internet. configure-file for avrdude-serjtag avrdude.conf (Update: included chip-parameter of ATmega328P and 88P) avrdude-GUI-1.0.5.zip mirror site avrdude-GUI-1.0.5.zip original site (http://yuki-lab.jp/hw/avrdude-GUI/index.html)avrdude-GUI-1.0.5.zip mirror site avrdude-GUI (yuki-lab.jp Version) require Microsoft .NET Framework 2.0. When .NET Framework 2.0 is not installed.
www.nexusrobot.com Robot Kits manual If your chip isn’t the same ,Some of the blank’s setting is different .change it base on the following chips : Testing and confirming - Disconnect a USB cable from Diecimila. - Remove the wires of ICSP and X3. - Connect a USB cable to Diecimila.
www.nexusrobot.com Robot Kits manual 0x05: delay(62) or 62 millis() ~ 1 second (Or 63 if you need to round up. The number is actually 62.5) Also, the default settings for the other timers are: TCCR1B: 0x03 TCCR2B: 0x04 There may be other side effects from changing TCCR0B. For example my project would not properly run with TCCR0B set to 0x02 or 0x01.
www.nexusrobot.com Robot Kits manual Led control Button module The controller has 7 build-in buttons S1-S7. S1-S5 use analog input, S6, S7 use digital input. To enable S6 and S7, please apply the jumpers indicated in the red circle. S6 uses Digital Pin2, S7 uses Digital Pin3.
www.nexusrobot.com Robot Kits manual digitalWrite(ledPin, LOW); // Set a low value to the ledPin Arduino button Interrrupt control Description Specifies a function to call when an external interrupt occurs. Replaces any previous function that was attached to the interrupt. Most Arduino boards have two external interrupts: numbers 0 (on digital pin 2) and 1 (on digital pin 3).
www.nexusrobot.com Robot Kits manual Digital Read Serial Fall Detector Example This example shows you how to monitor the state of a Fall detector by establishing serial communication between your Arduino and your computer over USB. Sample code const int PIN = 12; //set pin 12 as the signal pin void setup() Serial.begin(9600);...
www.nexusrobot.com Robot Kits manual Select the display Baud Rate Analog Read Serial Sharp 2D12 Example This example shows you how to read analog input, which from the physical world using a Sharp 2D12. A Sharp 2D12 is a simple mechanical device that provides a varying amount of resistance when its shaft is turned.
Page 24
www.nexusrobot.com Robot Kits manual you need to drive more than one or two, you'll probably need to power them from a separate supply (i.e. not the +5V pin on your Arduino). Be sure to connect the grounds of the Arduino and external power supply together.
www.nexusrobot.com Robot Kits manual Motor Control Hardware Setting Connect four motor wires to Motor Terminal. And apply power through motor power terminal. The PWM DC motor control is implemented by manipulating two digital IO pins and two PWM pins. As illustrated in the diagram above, Pin 4,7 are motor direction control pins, Pin 5,6 are motor speed control pins.
www.nexusrobot.com Robot Kits manual analogWrite(E1,100); TCCR2B = TCCR2B & 0b11111000 | 0x01; //set the timer1 as the work intrrupt timer // to use the timer will defualt at the function of setup; void loop() { } The Motor sample to link wries Serial Port This example shows you how to monitor the state of a switch by establishing serial communication between your Arduino and your computer over USB.
www.nexusrobot.com Robot Kits manual void loop() incomingByte = ((10485/(analogRead(ISRpin[0])+5))-4); //read the data from signal pin Serial.println(incomingByte,DEC); // display delay(500); External device modules Dual Ultrasonic Sensor (DUS) Introduction DUS is based on RS485 interface. It allows a number of sensors working together. Up to 32 units may be connected together in a RS485 network.
www.nexusrobot.com Robot Kits manual Specification Power: +5V Current: <20mA Working temperature: -10℃~+70℃ Detecting range: 4cm-300cm Resolution: 1cm Frequency: 40KHz Interface: RS485 Units: Range reported in cm Temperature sensor: 12 bits reading from serial port Size: 34mm × 51 mm Weight: 30g Dimension and Pin definition RS485 Interface:Two connectors, + :...
www.nexusrobot.com Robot Kits manual RS485 Bus Introduction to RS485 RS485 are serial communication methods for computers and devices. RS485 bus advances in simpler cabling,longer transmitting distance and higher dependability. RS485 is the most versatile communication standard in the standard series defined by the EIA, as it performs well on all four points.
Page 30
www.nexusrobot.com Robot Kits manual Network topology with RS485 RS485 is the only of the interfaces capable of internetworking multiple transmitters and receivers in the same network. When using the default RS485 receivers with an input resistance of 12 kΩ it is possible to connect 32 devices to the network.
www.nexusrobot.com Robot Kits manual Communication Protocols The device is fixed at 19200 bps Baud Rate,8/N/1. Set Device Address Command: Header Address Length Cmd Set Address SUM 55 Aa Return Value: Header Address Length Cmd Flag SUM 55 Aa PS: All connected SONAR will be changed to the given address. The new address must be between 0x11 and 0x30.
Page 32
www.nexusrobot.com Robot Kits manual Read Distance Command: Header Address Length Cmd SUM 55 aa Header Address Length Cmd High Byte Low Byte SUM 55 aa PS: The command will return the measured distance value. The value consists of two bytes. If the measurement is out of range or unsuccessful, the return data will be “0xFF(H) 0xFF(L)”.
www.nexusrobot.com Robot Kits manual Simple code: #include <SONAR.h> //used the library of SONAR // The sonar whose address is 0x11 was named S11, and it was setted as the type of SONAR SONAR s11=SONAR(0x11); //SONAR s12(0x12); void setup() { SONAR::init(); //set up some parameters delay(100);...
www.nexusrobot.com Robot Kits manual APC220 Module Parameters Transmission Distance : 800m to 1200m Arduino Wireless Transmission APC220 PC Kits-1 based on APC220 Kit list 1. one APC220 Wireless Transmission module 2. one APC220 USB adaptation shield 3. one antenna This module used to connect PC port. How to use the RF module to control Arduino wirelessly? Its principle is similar to a remote control, which has 4 buttons for RF wireless remote control.
www.nexusrobot.com Robot Kits manual Pin Change Interrupt PinChangeInt Library This library was inspired by and derived from the PcInt example by "johnboiles", and written by a "jbrisbin" (it seems). While the PCInt example shows with generality how Pin Change interrupts can be done under Arduino, it is an 'example' effort that sacrifices performance for clarity of implementation.
Page 36
www.nexusrobot.com Robot Kits manual #define PIN 15 // the pin we are interested in byte burp=0; // a counter to see how many times the pin has changed 10. byte cmd=0; // a place to put our serial data 11. void setup() { Serial.begin(9600);...
www.nexusrobot.com Robot Kits manual PID Control What Is PID From Wikipedia: "A PID controller calculates an 'error' value as the difference between a measured [Input] and a desired setpoint. The controller attempts to minimize the error by adjusting [an Output]." So, you tell the PID what to measure (the "Input",) Where you want that measurement to be (the "Setpoint",) and the variable to adjust that can make that happen (the "Output".) The PID then adjusts the output trying to make the input equal the setpoint.
www.nexusrobot.com Robot Kits manual Input = analogRead(0); //initialize the variables we're linked to Setpoint = 100; myPID.SetMode(AUTOMATIC); //turn the PID on void loop() { Input = analogRead(0); myPID.Compute(); analogWrite(3,Output); See: http://www.arduino.cc/playground/Code/PIDLibrary Servo control Theory RC servos are comprised of a DC motor mechanically linked to a potentiometer. Pulse-width modulation (PWM) signals sent to the servo are translated into position commands by electronics inside the servo.
www.nexusrobot.com Robot Kits manual The PWM signal In a nutshell, PWM is a way of digitally encoding analog signal levels. Through the use of high-resolution counters, the duty cycle of a square wave is modulated to encode a specific analog signal level. The PWM signal is still digital because, at any given instant of time, the full DC supply is either fully on or fully off.
www.nexusrobot.com Robot Kits manual Motorwheel This page describes how to control the built-in Motorwheel. Motorwheel Class Reference This document describes how to use the Motor library to control Motors. On the Introduction, you will know how to controls the motor’s PWM, direction and speed . This motorwheel library version 1.1,compatible with maple.
www.nexusrobot.com Robot Kits manual Class Motor Reference This section gives a full listing of the capabilities of a Motor. Class Motor : public PID Interface for visit of peripherals . Inherit from the Public PID. Public functions Motor(unsigned char _pinPWM,unsigned char _pinDir, unsigned char _pinIRQ,unsigned char _pinIRQB, struct ISRVars* _isr) Construct a new Motor instance.
Page 42
www.nexusrobot.com Robot Kits manual Return: Direction pin unsigned char getPinIRQ() const Get the IRQ Pin number Return: IRQ pin unsigned char getPinIRQB() const Get the IRQB Pin number Return: IRQB pin unsigned int runPWM(unsigned int PWM,bool dir,bool saveDir=true); Set the PWM and direction for Motors .then return the PWM. unsigned int PWM The PWM set for the Motor Bool dir...
Page 43
www.nexusrobot.com Robot Kits manual unsigned int PWM Parameters: The PWM set for Motor See: Motor:: runPWM() bool setDesiredDir(bool dir) The desired direction set for the motor This will lie within the range specified at Motor::getDesiredDir() Bool dir Parameters: The direction set for Motor See: Motor::getDesiredDir() bool getDesiredDir() const...
Page 44
www.nexusrobot.com Robot Kits manual unsigned int setSpeedRPM(int speedRPM,bool dir) Set the speed and direction for the motor This will lie within the range specified at Motor::PIDSetSpeedRPMDesired() , Motor::setDesiredDir(), Motor::getSpeedRPM() int speedRPM The speed set for Motor Parameters: Bool dir The direction set for Motor Motor:: PIDSetSpeedRPMDesired() See: Motor::setDesiredDir()
Page 45
www.nexusrobot.com Robot Kits manual This will lie within the range specified at PID::PIDSetup() Float kc Proportional term Float taui Integral term Parameters: Float taud Derivative term Unsigded int sampletime The time the PID work last Return: pidCtrl equal ture See: pidCtrl equal ture bool PIDDisable() Disable the PID,release it...
Page 46
www.nexusrobot.com Robot Kits manual According to the User’s demands ,use the class PID to set the speed of Motor. This will lie within the range specified at PID::PIDGetSpeedRPMDesired() Unsigned int speedRPM parameters The speed User want to set See: PID::PIDGetSpeedRPMDesired() unsigned int PIDGetSpeedRPMDesired() const Get the desired speed Return:...
www.nexusrobot.com Robot Kits manual Define a Pointer named isr, as the member of the struct ISRVars Private members unsigned char pinPWM The PWM pin. unsigned char pinDir The diretion pin unsigned char pinIRQ The IRQ pin unsigned char pinIRQB The IRQB pin bool desiredDirection The desired direction unsigned int speedPWM...
Page 48
www.nexusrobot.com Robot Kits manual unsigned char _pinIRQ,unsigned char _pinIRQB, struct ISRVars* _isr, unsigned int _ratio=REDUCTION_RATIO); Construct a new GearedMotor instance. In your sketch. This will create a GearedMotor object called GearedMotor. You can then use any of its methods; for instance, to control a Gearedmotor attached to pins, you could write Unsigned char _pinPWM The PWM control pin unsigned char _pinDir...
www.nexusrobot.com Robot Kits manual Return: gearedSpeedRPM See: Motor::setSpeedRPM () unsigned int getRatio() const Get the ratio the car run at Return: _ ratio unsigned int setRatio(unsigned int ratio=REDUCTION_RATIO) Set the Ratio the car run at This will lie within the range specified at Motor::getRatio() unsigned int ratio parameters The value want to set...
Page 50
www.nexusrobot.com Robot Kits manual unsigned char _pinIRQ The IRQ pin unsigned char _pinIRQB The IRQB pin struct ISRVars* _isr A point of the struct IRSVars’s member unsigned int _ratio A variable equal 60 unsigned int cirMM A variable equal 314 mm unsigned int getCirMM() const Get the Circumference of the wheel Return:...
Page 51
www.nexusrobot.com Robot Kits manual unsigned int getSpeedMMPS() const Get the speed (millimeter per second) This will lie within the range specified at MotorWheel::getspeedCMPM(). See: MotorWheel::getspeedCMPM() unsigned int setSpeedMMPS(unsigned int mm,bool dir) Set the speed . This will lie within the range specified at MotorWheel::setspeedCMPM() and MotorWheel::getspeedCMPM().
Page 52
www.nexusrobot.com Robot Kits manual Serial.println(wheel1.getSpeedRPM(),DEC); //display the speed of the MotorWheel Serial.print("MMPS --> "); Serial.println(wheel1.getSpeedMMPS(),DEC); //display the speed of the motor //wheel1.debugger();...
www.nexusrobot.com Robot Kits manual R2WD This page describes how to control the built-in R2WD. It does not describe how the R2WD work on your board. For more information on that, please refer to R2WD Class Reference. *2 mobile wheel drive *Aluminum alloy body *Includes ultrasonic sensors and Bumper sensors *Optional IR sensors and Fall detect sensors...
Page 54
www.nexusrobot.com Robot Kits manual In your sketch. This will create a R2WD object called R2WD. You can then use any of its methods; for instance, to control a R2WD attached to pins, you could write MotorWheel*wheelLeft A point named wheelLeft as the object of MotorWheel,left wheel MotorWheel*wheelRight Parameters: A point named wheelRight as the object of MotorWhee,right wheel...
Page 55
www.nexusrobot.com Robot Kits manual R2WD::setCarStat() see : R2WD::setMotorAll() unsigned int setCarAdvance(unsigned int speedMMPS=0) Set car move advance This will lie within the range specified at R2WD::setCarStat() and R2WD::setcaradvanceBase() unsigned int speedMMPS Parameters: The speed of the car moves , initialize it R2WD::setCarStat() see : R2WD::setadvanceBase()
Page 56
www.nexusrobot.com Robot Kits manual This will lie within the range specified at R2WD::setCarStat() and R2WD::setMotorAllAdvance () unsigned int speedMMPS Parameters: The speed of the car moves , initialize it R2WD::setCarStat() see : R2WD::setMotorAllAdvance() unsigned int setCarUpperLeft(unsigned int speedMMPS,unsigned int radiusMM) Set car moves upper left This will lie within the range specified at R2WD::setCarStat() and R2WD::setCarArcBace() unsigned int speedMMPS...
Page 57
www.nexusrobot.com Robot Kits manual unsigned int radiusMM The radius of the car moves Locus R2WD::setCarStat() see : R2WD::setCarArcBace() unsigned int setCarLowerRight(unsigned int speedMMPS,unsigned int radiusMM) Set car moves Lower right This will lie within the range specified at R2WD::setCarStat() and R2WD::setCarArcBace() unsigned int speedMMPS The speed of the car moves , initialize it Parameters:...
Page 58
www.nexusrobot.com Robot Kits manual R2WD::setCarBackoff() see : R2WD::setCarStrightdistance() unsigned int setCarRotateLeftAngle(unsigned int speedMMPS,float radian); Set the angle when the car moves as rotate left This will lie within the range specified at R2WD::setCarRotateLeft()and R2WD::setCarRotateAngle() unsigned int speedMMPS The speed ofthe car moves , initialize it Parameters: float radian The radian when the car move as rotate left...
Page 59
www.nexusrobot.com Robot Kits manual The time of the car last , initialize it unsigned int uptime=500 The time the car used to stop R2WD::setCarUpperLeft() see : R2WD::setCarArcTime () unsigned int setCarLowerLeftTime(unsigned int speedMMPS=0,unsigned int radiusMM=WHEELSPAN,unsigned long duration=5000,unsigned int uptime=500); Set period of time for the car moves Lower left This will lie within the range specified at R2WD::setCarLowerLeft()and R2WD::setCarArcTime () unsigned int speedMMPS =0 The speed ofthe car moves , initialize it...
Page 60
www.nexusrobot.com Robot Kits manual The time the car used to stop R2WD::setCarUpperRight() see : R2WD::setCarArcTime () unsigned int setCarLowerRightTime(unsigned int speedMMPS=0,unsigned int radiusMM=WHEELSPAN,unsigned long duration=5000,unsigned int uptime=500); Set period of time for the car moves Lower Right This will lie within the range specified at R2WD::setCarLowerRight()and R2WD::setCarArcTime () unsigned int speedMMPS =0 The speed for the car to moves ,initialize it unsigned int radiusMM=WHEELSPAN...
Page 61
www.nexusrobot.com Robot Kits manual Set the angle when the car moves Upper left This will lie within the range specified at R2WD::setCarLowerLeft()and R2WD::setCarArcAngle() unsigned int speedMMPS The speed for the car to moves Parameters: Unsigned int radian The radian when the car moves lower left R2WD::setCarLowerLeft() see : R2WD::setCarArcAngle()
Page 62
www.nexusrobot.com Robot Kits manual Set the speed for Left wheel This will lie within the range specified at MotorWheel::setSpeedMMPS () unsigned int speedMMPS The speed for the car to moves Parameters: bool dir=DIR_ADVANCE The direction for the left wheel see : MotorWheel::setSpeedMMPS () unsigned int wheelLeftGetSpeedMMPS() const;...
Page 63
www.nexusrobot.com Robot Kits manual Float taui Integral term Float taud Derivative term Unsigded int interval The time the PID work last see : MotorWheel::PIDEnable() bool PIDRegulate() Regulate the PID ,in order to adjust the speed of the Motor. This will lie within the range specified at MotorWheel:: PIDRegulate() see : MotorWheel:: PIDRegulate() void delayMS(unsigned long ms=100, bool debug=false)
Page 64
www.nexusrobot.com Robot Kits manual STAT_ROTATELEFT STAT_ROTATERIGHT This will lie within the range specified at R2WD::GetCarSpeedMMPS() unsigned int speedMMPS=0 The speed for the car to moves ,initialize it Parameters: unsigned int ms=1000 The time the car’s speed changed from 0 to speedMMPS used see : R2WD::getCarSpeedMMPS() unsigned int setCarSpeedMMPSArc(unsigned int speedMMPS=0,unsigned int...
Page 65
www.nexusrobot.com Robot Kits manual void debugger(bool wheelLeftDebug=true,bool wheelRightDebug=true) const; Debug the all wheel’s speed Car _state enum Used to configure the behavior of a car. Note that not all car can be configured in every state. Variables: STAT_UNKNOWN The state of the car unknown STAT_STOP The car’s state is stop STAT_ADVANCE...
www.nexusrobot.com Robot Kits manual Motor _state enum Used to configure the behavior of a motor. Note that not all motors can be configured in every state. Variables: MOTORS_FB The switchmotorstat is FB MOTORS_BF The switchmotorstat is BF unsigned char getSwitchMotorsStat() const Get the state of the Motor return : The motor’s state...
Page 67
www.nexusrobot.com Robot Kits manual the state want to set Carstate if the stat in the range of the want return : STAT_UNKNOWN otherwise unsigned char _switchMotorsStat Save the state of the Motor,prepare for switch motors unsigned char setSwitchMotorsStat(unsigned char switchMotorsStat) Set the Motors’...
Page 68
www.nexusrobot.com Robot Kits manual bool dir=DIR_ADVANCE The direction set the motors run,initialize it R2WD:: wheelLeftSetSpeedMMPS() See: R2WD:: wheelRightSetSpeedMMPS() unsigned int setMotorAllStop() Set all Motors stop This will lie within the range specified at R2WD::setMotorAll() See: R2WD::setMotorAll() unsigned int setMotorAllAdvance(unsigned int speedMMPS=0) Set all motors run advance This will lie within the range specified at R2WD::setMotorAll() unsigned int speedMMPS=0...
Page 69
www.nexusrobot.com Robot Kits manual R2WD:: wheelLeftSetSpeedMMPS() See: R2WD:: wheelRightSetSpeedMMPS() R2WD::getCarSpeedMMPS() unsigned int setCarBackoffBase(unsigned int speedMMPSL=0,unsigned int speedMMPSR=0) Set car moves backoff This will lie within the range specified at R2WD:: wheelLeftSetSpeedMMPS() and R2WD::wheelRightSetSpeedMMPS() and R2WD::getCarSpeedMMPS() unsigned int speedMMPSL=0 The speed set to the left motor Parameters: unsigned int speedMMPSR=0 The speed set to the right motor...
Page 70
www.nexusrobot.com Robot Kits manual Return: timeMS,the time the car moves unsigned int setCarArcBase(unsigned int speedMMPS=0,unsigned int radiusMM=WHEELSPAN) Set the Arc the car moves The car have arc is on the basis of the two wheel have diffrent speed or direction This will lie within the range specified at R2WD::setCarBackoffBase() and R2WD::setCarAdvanceBase() unsigned int speedMMPS=0...
Page 71
www.nexusrobot.com Robot Kits manual The radius the car moves float radian=0 The radian the car moves unsigned int uptime=500 The time the car used to stop Return: The time the car used to moves and stop void demoActions(unsigned int speedMMPS=100,unsigned int duration=5000,unsigned int uptime=500,bool debug=false) A function for the car demo action void R2WD::demoActions(unsigned int speedMMPS,unsigned int duration,unsigned int uptime,bool...
www.nexusrobot.com Robot Kits manual setCarSpeedMMPSArc(speedMMPS,getRadiusMM(),uptime); delayMS(duration,debug); //duration=5000 the car moves this action willl last 5000 milliseconds setCarSlow2Stop(uptime); //uptime=500 set the car stop in 500 milliseconds R2WD_test Here’s an example ,we use it to test a car with two wheels.after this ,you will More thorough understanding of the library Simple code: #include <MotorWheel.h>...
Page 73
www.nexusrobot.com Robot Kits manual MotorWheel wheel2(10,11,6,7,&irq2,REDUCTION_RATIO,int(144*PI)); R2WD _2WD(&wheel1,&wheel2,WHEELSPAN); // This will create a R2WD object called R2WD. You // can then use any of its methods; for instance, to // control a R2WD attached to pins, you could write void setup() { //TCCR0B=TCCR0B&0xf8|0x01;...
www.nexusrobot.com Robot Kits manual 2WD platform with 3 SONAR Look the above figure of simple Wiring Diagram for RB004 2WD V2.0. this code is matched for it RB004_2WD_PID_3SONAR_3IR code #include <MotorWheel.h> #include <Omni3WD.h> #include <Omni4WD.h> #include <R2WD.h> #include <PID_Beta6.h> #include <PinChangeInt.h> #include <PinChangeIntConfig.h>...
Page 76
www.nexusrobot.com Robot Kits manual unsigned char irL0_pin=0; // Set Analog pin 0 as the left Infrared Sensor signal pin unsigned char irC0_pin=1; unsigned char irR0_pin=2; // Set Analog pin 2 as the right Infrared Sensor signal pin int ir_distance(unsigned char ir) { int val=analogRead(ir);...
Page 77
www.nexusrobot.com Robot Kits manual void loop() { _2WD.demoActions(80,5000); //Call the demoActions from the class 2WD void loop() { boolean bumperL=!digitalRead(bumperL_pin); // a flag to sure if the Left have someting boolean bumperC=!digitalRead(bumperC_pin); boolean bumperR=!digitalRead(bumperR_pin); int irL0=ir_distance(irL0_pin); // A variable to save the data of the left Infrared Sensor return int irC0=ir_distance(irC0_pin);...
www.nexusrobot.com Robot Kits manual Omni Wheel Robots employing omni wheel are capable of moving in any direction by changing velocity and direction of each wheel without changing its orientation.As there are small rollers around the circumference of omni wheels which are perpendicular to the rolling direction making them capable of sliding laterally.
www.nexusrobot.com Robot Kits manual *3WD 100mm Mecanum wheel *3 plate levels *Aluminum alloy body *Includes ultrasonic sensors and optional IR *DC motors with encoder *With microcontroller and IO expansion board *Programmable with C,C++ *Based on Arduino microcontroller RB013_3WD omni wheel mobile kit *Includes ultrasonic sensors and optional IR *3WD 100mm Mecanum wheel *Compact size...
www.nexusrobot.com Robot Kits manual Public functions Omni3WD (MotorWheel* wheelBack,MotorWheel* wheelRight,MotorWheel* wheelLeft) Construct a new Omni3WD instance. in your sketch. This will create a Omni3WD object called Omni3WD. You can then use any of its methods; for instance, to control a Omni3WD attached to pins, you could write MotorWheel* wheelBack A point named wheelBack as the object of MotorWheel,back wheel MotorWheel*wheelLeft...
Page 81
www.nexusrobot.com Robot Kits manual The speed for the motor to run,initialize it. bool dir=DIR_ADVANCE The direction for the motor to run Omni3WD::wheelBackSetSpeedMMPS() See: Omni3WD::wheelRightSetSpeedMMPS() Omni3WD::wheelLeftSetSpeedMMPS() unsigned int setMotorAllStop() Stop all Motors This will lie within the range specified at Omni3WD::setMotorAll() See: Omni3WD::setMotorAll() unsigned int setMotorAllAdvance(unsigned int speedMMPS=0)
Page 82
www.nexusrobot.com Robot Kits manual Set the car moves forward Because the car have three wheels ,so the car moves forward ,the wheels will have different state. This will lie within the range specified at Omni3WD::setCarstat() and Omni3WD::wheelBackSetSpeedMMPS() and Omni3WD::wheelRightSetSpeedMMPS() and Omni3WD::wheelLeftSetSpeedMMPS() unsigned int speedMMPS=0 Parameters:...
Page 83
www.nexusrobot.com Robot Kits manual Omni3WD::wheelBackSetSpeedMMPS() Omni3WD::wheelRightSetSpeedMMPS() Omni3WD::wheelLeftSetSpeedMMPS() unsigned int setCarRight(unsigned int speedMMPS=0) Set the car turn right This will lie within the range specified at Omni3WD::setCarstat() and Omni3WD::wheelBackSetSpeedMMPS() and Omni3WD::wheelRightSetSpeedMMPS() and Omni3WD::wheelLeftSetSpeedMMPS() unsigned int speedMMPS=0 Parameters: The speed for the car moves,initialize it. Omni3WD::setCarstat() Omni3WD::wheelBackSetSpeedMMPS() See:...
Page 84
www.nexusrobot.com Robot Kits manual unsigned int getCarSpeedMMPS() const Get the car’s speed return: The car’s speed unsigned int setCarSpeedMMPS(unsigned int speedMMPS=0,unsigned int ms=1000) The car’s speed be set This will lie within the range specified at Omni3WD::getCarSpeedMMPS() unsigned int speedMMPS=0 The speed for the car moves,initialize it.
Page 85
www.nexusrobot.com Robot Kits manual See: MotorWheel::getSpeedMMPS() unsigned int wheelRightSetSpeedMMPS(unsigned int speedMMPS=0,bool dir=DIR_ADVANCE) Set the speed for the right wheel This will lie within the range specified at MotorWheel::setSpeedMMPS() unsigned int speedMMPS=0 The speed for the wheel to run,initialize it Parameters: bool dir=DIR_ADVANCE The direction for the wheel to run See:...
Page 86
www.nexusrobot.com Robot Kits manual Float kc Proportional term,initialize it Float taui Integral term Parameters: Float taud Derivative term Unsigded int interval The time the PID work last see : MotorWheel::PIDEnable() bool PIDRegulate() Regulate the PID ,in order to adjust the speed of the Motor. This will lie within the range specified at MotorWheel:: PIDRegulate() see : MotorWheel:: PIDRegulate()
Page 87
www.nexusrobot.com Robot Kits manual STAT_STOP The car’s state is stop STAT_ADVANCE The car’s state is moves forward STAT_BACKOFF The car’s state is get backoff STAT_ROTATELEFT The car’s state is moves rotate left STAT_ROTATERIGHT The car’s state is moves rotate right STAT_RIGHT The car’s state is turn right STAT_LEFT...
www.nexusrobot.com Robot Kits manual Private parameters MotorWheel* _wheelBack A point named wheelBack as the object of MotorWheel MotorWheel* _wheelRight A point named wheelright as the object of MotorWheel MotorWheel* _wheelLeft A point named wheelLeft as the object of MotorWheel unsigned char _carStat To save the car’s state unsigned char setCarStat(unsigned char stat) Set the state of the car...
Page 89
www.nexusrobot.com Robot Kits manual void Omni3WD::demoActions(unsigned int speedMMPS,unsigned int duration,unsigned int uptime,bool debug) { unsigned int (Omni3WD::*carAction[])(unsigned int speedMMPS)={ &Omni3WD::setCarAdvance, //set car moves forward &Omni3WD::setCarBackoff, //set car moves Reverse &Omni3WD::setCarLeft, //set car turn left &Omni3WD::setCarRight, //set car turn right &Omni3WD::setCarRotateLeft,//set car rotate left &Omni3WD::setCarRotateRight //set car rotate right for(int i=0;i<6;++i) { //there are six base actions...
www.nexusrobot.com Robot Kits manual Omni3WD_test Here’s an example ,we use it to test a car with three wheels.after this ,you will More thorough understanding of the library Simple code: #include <MotorWheel.h> #include <Omni3WD.h> #include <Omni4WD.h> #include <PID_Beta6.h> #include <PinChangeInt.h> #include <PinChangeIntConfig.h> // Include the header files Wheel3 \\ Wheel2...
Page 91
www.nexusrobot.com Robot Kits manual // to control a Omni3WD attached to pins, you could write void setup() { TCCR1B=TCCR1B&0xf8|0x01; // Timer1.Pin9,Pin10 PWM 31250Hz TCCR2B=TCCR2B&0xf8|0x01; // Timer2 .Pin3,Pin11 PWM 31250Hz Omni.PIDEnable(0.26,0.02,0,10); // Enable PID void loop() { Omni.demoActions(100,5000,1000,false); //Call the demoActions speedMMPS=100 duration=5000 uptime =1000.
Page 92
www.nexusrobot.com Robot Kits manual Diagram for Omni3WD_V1.0...
www.nexusrobot.com Robot Kits manual Omni3WD platform with 3 SONARS Look the above figure of simple Wiring Diagram for Omni3WD_V1.0. Tis code is matched for it Diagram_Omni3WD_V1.0 code /********************************************************************/ Power Switch Sonar0x11 ------------------------- \ M2 INT0 / \INT1 Sonar0x12 / Sonar0x13 -------------------------- #include <fuzzy_table.h>...
Page 94
www.nexusrobot.com Robot Kits manual SONAR sonar11(0x11),sonar12(0x12),sonar13(0x13); // Software initialization //SONAR is be defined in <SONAR.h> as a class unsigned short distBuf[3]; // Used to save the data of the 3 sonars return; void sonarsUpdate() { //the function to static unsigned char sonarCurr=1; // A variable save a data used to flag the current of sonar if(sonarCurr==3) sonarCurr=1;...
Page 95
www.nexusrobot.com Robot Kits manual /******************************************/ // demo unsigned long currMillis=0; void demoWithSensors(unsigned int speedMMPS,unsigned int distance) { if(millis()-currMillis>SONAR::duration) { // every 60ms call sonarUpdate once currMillis=millis(); sonarsUpdate(); if(distBuf[1]<distance) { // If the left side have something if(Omni.getCarStat()!=Omni3WD::STAT_RIGHT) Omni.setCarSlow2Stop(500); Omni.setCarRight(speedMMPS); // Set car turn right } else if(distBuf[2]<distance) { // If the right have something if(Omni.getCarStat()!=Omni3WD::STAT_LEFT) Omni.setCarSlow2Stop(500);...
www.nexusrobot.com Robot Kits manual Omni3WD platform with 6 SONARS Look the above figure of simple Wiring Diagram for Omni3WD_V3.3. Tis code is matched for it Diagram_Omni3WD_V3.3 code /********************************************************************/ Power Switch Sonar0x11 ----------------------- Sonar0x16 Sonar0x12 M3,IR03 / \ M2,IR02 Sonar0x15 \ / Sonar0x13 ------------------------ Sonar0x14...
Page 98
www.nexusrobot.com Robot Kits manual SONAR sonar11(0x11),sonar12(0x12),sonar13(0x13),sonar14(0x14),sonar15(0x15),sonar16(0x16); // Software initialization //SONAR is be defined in <SONAR.h> as a class unsigned short distBuf[6]; // Used to save the data of the 6 sonars return; void sonarsUpdate() { static unsigned char sonarCurr=1; // A variable save a data used to flag the current of sonar if(sonarCurr==3) sonarCurr=1;...
Page 100
www.nexusrobot.com Robot Kits manual if(IRs[1] || IRs[2]) { // The Anti-drop return a High Value Omni.setCarBackoff(speedMMPS); // get car back Omni.delayMS(ms); // delay “ms” ,every 10 ms call the PIDregulate() once time. if(IRs[1]) { Omni.setCarRotateLeft(speedMMPS); } else Omni.setCarRotateRight(speedMMPS); Omni.delayMS(ms); } else if(distBuf[1]<distance || distBuf[2]<distance) { // the right side have something Omni.setCarLeft(speedMMPS);...
www.nexusrobot.com Robot Kits manual Omni4WD This page describes how to control the built-in Omni4WD. It does not describe how the Omni4WD work on your board. For more information on that, Please refer to Omni4WD Class Reference. *4WD 100mm Mecanum wheel * Includes ultrasonic sensors and optional IR *Suspension structure to ensure roadholding of each single wheel...
www.nexusrobot.com Robot Kits manual Omni4WD Class Reference This document describes a car with four Motors. On the Introduction, you will know how to use the Omni4WD library to control the Motors,then to control the car #include<MotorWheel.h> Include the header file MotorWheel.h This section gives a full listing of the capabilities of Omni4WD Class Omni4WD Interface for visit of peripherals...
Page 103
www.nexusrobot.com Robot Kits manual See: Omni3WD::getSwitchMotorsStat() unsigned char switchMotorsReset() Reset for switch motors to control unsigned int setMotorAll(unsigned int speedMMPS=0,bool dir=DIR_ADVANCE) Set all motors’ speed and direction This will lie within the range specified at Omni4WD:: wheelULSetSpeedMMPS() and Omni4WD::wheelLLSetSpeedMMPS() and Omni4WD::wheelLRSetSpeedMMPS() and Omni4WD::wheelURSetSpeedMMPS() unsigned int speedMMPS=0 The speed for the motor run,initialize it.
Page 104
www.nexusrobot.com Robot Kits manual This will lie within the range specified at Omni4WD::setMotorAll() unsigned int speedMMPS=0 Parameters: The speed for the motor run,initialize it. See: Omni4WD::setMotorAll() unsigned int setCarStop() Stop the car This will lie within the range specified at Omni4WD::setMotorAll() and Omni4WD::setCarstat() Omni4WD::setMotorAll() See: Omni4WD::setCarstat()
Page 105
www.nexusrobot.com Robot Kits manual unsigned int speedMMPS=0 Parameters: The speed for the motor run,initialize it. Omni4WD:: wheelULSetSpeedMMPS() Omni4WD::wheelLLSetSpeedMMPS() See: Omni4WD::wheelLRSetSpeedMMPS() Omni4WD::wheelURSetSpeedMMPS() Omni4WD::setCarstat() unsigned int setCarLeft(unsigned int speedMMPS=0) Set the car turn Left This will lie within the range specified at Omni4WD:: wheelULSetSpeedMMPS() and Omni4WD::wheelLLSetSpeedMMPS() and Omni4WD::wheelLRSetSpeedMMPS() and Omni4WD::wheelURSetSpeedMMPS() and Omni4WD::setCarstat() unsigned int speedMMPS=0...
Page 106
www.nexusrobot.com Robot Kits manual Omni4WD::setCarstat() unsigned int setCarRotateLeft(unsigned int speedMMPS=0) Set the car rotate left This will lie within the range specified at Omni4WD::setCarstat() and mni4WD::setMotorAllBackoff() unsigned int speedMMPS=0 Parameters: The speed for the car moves,initialize it. Omni4WD::setCarstat() See: Omni4WD::setMotorAllBackoff() unsigned int setCarRotateRight(unsigned int speedMMPS=0) Set the car for rotate right This will lie within the range specified at Omni4WD::setCarstat() and...
Page 107
www.nexusrobot.com Robot Kits manual unsigned int setCarLowerLeft(unsigned int speedMMPS=0) Set the car Lower left This will lie within the range specified at Omni4WD::wheelULSetSpeedMMPS() and Omni4WD::wheelLLSetSpeedMMPS() and Omni4WD::wheelLRSetSpeedMMPS() and Omni4WD::wheelURSetSpeedMMPS() and Omni4WD::setCarstat() unsigned int speedMMPS=0 Parameters: The speed for the motor run,initialize it. Omni4WD::wheelULSetSpeedMMPS() Omni4WD::wheelLLSetSpeedMMPS() See:...
Page 108
www.nexusrobot.com Robot Kits manual The speed for the motor run,initialize it. Omni4WD::wheelULSetSpeedMMPS() Omni4WD::wheelLLSetSpeedMMPS() See: Omni4WD::wheelLRSetSpeedMMPS() Omni4WD::wheelURSetSpeedMMPS() Omni4WD::setCarstat() unsigned int getCarSpeedMMPS() const Get the car’s speed return: The car’s speed unsigned int setCarSpeedMMPS(unsigned int speedMMPS=0,unsigned int ms=1000) Set the speed of the car This will lie within the range specified at Omni4WD::getCarSpeedMMPS() unsigned int speedMMPS=0 The speed for the car moves,initialize it.
Page 109
www.nexusrobot.com Robot Kits manual This will lie within the range specified at Omni4WD::getCarSpeedMMPS() unsigned int speedMMPS=0 The speed for the car moves,initialize it. Parameters: unsigned int ms=1000 The time used for the car moves at this speed See: Omni4WD::getCarSpeedMMPS() unsigned int setCarSlow2Stop(unsigned int ms=1000) Stop the car in 1000 milliseconds This will lie within the range specified at Omni4WD::setCarSpeedMMPS() unsigned int ms=1000...
Page 110
www.nexusrobot.com Robot Kits manual unsigned int wheelLLSetSpeedMMPS(unsigned int speedMMPS=0,bool dir=DIR_ADVANCE) Set the speed for the lower left wheel This will lie within the range specified at MotorWheel::setSpeedMMPS() unsigned int speedMMPS=0 The speed for the wheel run,initialize it Parameters: bool dir=DIR_ADVANCE The direction for the wheel run See: MotorWheel::setSpeedMMPS()
Page 111
www.nexusrobot.com Robot Kits manual The speed for the wheel run,initialize it bool dir=DIR_ADVANCE The direction for the wheel run See: MotorWheel::setSpeedMMPS() bool PIDEnable(float kc=KC,float taui=TAUI,float taud=TAUD,unsigned int interval=1000) Call the PID,make it work for the car. Then this will work for every wheels This will lie within the range specified at MotorWheel::PIDEnable() Float kc Proportional term,initialize it...
Page 112
www.nexusrobot.com Robot Kits manual void debugger(bool wheelBackDebug=true,bool wheelRightDebug=true,bool wheelLeftDebug=true) const Debug the speed of the wheel Car _state enum Used to configure the behavior of a car. Note that not all car can be configured in every state. Variables: STAT_UNKNOWN The state of the car unknown STAT_STOP The car’s state is stop...
www.nexusrobot.com Robot Kits manual unsigned char getCarStat() const Get the state of the car return : The car’s state Motor _state enum Used to configure the behavior of a motor. Note that not all motors can be configured in every state. Variables: MOTORS_FB The switchmotorstat is front back...
Page 114
www.nexusrobot.com Robot Kits manual Carstate if the stat in the range of the want return : STAT_UNKNOWN otherwise unsigned char _switchMotorsStat Switch the motors’ state unsigned char setSwitchMotorsStat(unsigned char switchMotorsStat) Set the Motors’ state This will lie within the range specified at Omni4WD::getSwitchMotorsStat() Parameters: unsigned char switchMotorsStat The state want to set...
Page 115
www.nexusrobot.com Robot Kits manual for(int i=0;i<10;++i) { //the car have 10 demo actions (this->*carAction[i])(0); // default parameters not available in function pointer setCarSpeedMMPS(speedMMPS,uptime); //in the uptime , the car’s speed accelerate from 0 to speedMMPS delayMS(duration,debug); //the car’s state last “duration” times setCarSlow2Stop(uptime);...
www.nexusrobot.com Robot Kits manual Omni4WD_test Here’s an example ,we use it to test a car with four wheels.after this ,you will More thorough understanding of the library Simple code: #include <MotorWheel.h> #include <Omni3WD.h> #include <Omni4WD.h> #include <PID_Beta6.h> #include <PinChangeInt.h> #include <PinChangeIntConfig.h> // Include the header files wheel1 \ wheel4...
Page 117
www.nexusrobot.com Robot Kits manual MotorWheel wheel3(9,8,16,17,&irq3); irqISR(irq4,isr4); MotorWheel wheel4(10,7,18,19,&irq4); Omni4WD Omni(&wheel1,&wheel2,&wheel3,&wheel4); // This will create a Omni4WD object called Omni4WD. //You can then use any of its methods; for instance, // to control a Omni4WD attached to pins, you could write void setup() { //TCCR0B=TCCR0B&0xf8|0x01;...
www.nexusrobot.com Robot Kits manual 4WD platform with 4 SONAR Look the above figure of simple Wiring Diagram for RB011 ,Mecanum 4WD V4.1. this code is matched for it 4WD platform with 4 SONAR code #include <MotorWheel.h> #include <Omni4WD.h> #include <PID_Beta6.h> #include <PinChangeInt.h>...
Page 120
www.nexusrobot.com Robot Kits manual irqISR(irq4,isr4); MotorWheel wheel4(10,7,18,19,&irq4); Omni4WD Omni(&wheel1,&wheel2,&wheel3,&wheel4); // This will create a Omni4WD object called Omni. then You can use any of its methods; // for instance, to control a Omni4WD attached to pins, you could write SONAR sonar11(0x11),sonar12(0x12),sonar13(0x13),sonar14(0x14); // Software initialization //SONAR is be defined in <SONAR.h>...
www.nexusrobot.com Robot Kits manual rotateLeft, backOff, turnLeft, allStop}; // used the method of demotion unsigned long currMillis=0; void demoWithSensors(unsigned int speedMMPS,unsigned int distance) { unsigned char sonarcurrent = 0; if(millis()-currMillis>SONAR::duration + 20) { // every 80 ms to call sonarUpdate once currMillis=millis();...
Page 123
www.nexusrobot.com Robot Kits manual This document describes a car with three servo Motors. On the Introduction, you will know how to control the servo Motors,then to control the car Before you read this code,you should know about the Servo Motor Theory.To understand how the motor works.
Page 124
www.nexusrobot.com Robot Kits manual analogWrite(MOTOR3_E,53); //forward run motor3 void Right(){ analogWrite(MOTOR1_E,66); //forward run motor1 analogWrite(MOTOR2_E,40); //Reverse run motor2 analogWrite(MOTOR3_E,40); //Reverse run motor3 //************************************************// void RotateRight(){ analogWrite(MOTOR1_E,66); //forward run motor1 analogWrite(MOTOR2_E,62); //forward run motor2 analogWrite(MOTOR3_E,64); //forward run motor3 //*************************************************// void RotateLeft(){ analogWrite(MOTOR1_E,36);...
Page 125
www.nexusrobot.com Robot Kits manual pinMode(MOTOR1_E, OUTPUT); // Define the pin Mode as OUTPUT pinMode(MOTOR2_E, OUTPUT); pinMode(MOTOR3_E, OUTPUT); Serial.begin(19200); void loop(){ demotion(); // Call the demotion Sample Wiring Diagram for 3WD omni wheel mobile robot...
www.nexusrobot.com Robot Kits manual Servo_3WD platform with 3 SONAR Look the above figure of simple Wiring Diagram for 3WD omni wheel mobile robot. Tis code is matched for it Servo_3WD omni wheel mobile robot code #include <SONAR.h> // Include the header files SONAR sonar11(0x11),sonar12(0x12),sonar13(0x13);...
Page 128
www.nexusrobot.com Robot Kits manual analogWrite(MOTOR1_E, 48); // stop the motor1 analogWrite(MOTOR2_E, 44); // stop the motor2 analogWrite(MOTOR3_E, 46); // stop the motor3 //*************************************************// void (*motion[8])()={ goAhead,RotateLeft,turnRight,RotateLeft,turnLeft,RotateLeft,judge,allStop}; //change the void demowithSosars(){ unsigned char sonarcurrent=0; if(millis()-currMillis>SONAR::duration){ //judge if the time more than SONAR::duration; currMillis=millis();...
Need help?
Do you have a question about the Nexus Robot and is the answer not in the manual?
Questions and answers