51
Main Page Classes Files Examples Class List Class Index Class Members SyRen/Sabertooth Packet Serial Library for Arduino Control your SyRen or Sabertooth with reliable Packet Serial. Class List Here are the classes, structs, unions and interfaces with brief descriptions: Sabertooth Controls a Sabertooth or SyRen motor driver running in Packet Serial mode

SyRen/Sabertooth Packet Serial Library for Arduino · SyRen/Sabertooth Packet Serial Library for Arduino Control your SyRen or Sabertooth with reliable Packet Serial. Class List Here

  • Upload
    others

  • View
    31

  • Download
    0

Embed Size (px)

Citation preview

MainPage Classes Files ExamplesClassList ClassIndex ClassMembers

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

ClassList

Herearetheclasses,structs,unionsandinterfaceswithbriefdescriptions:

Sabertooth ControlsaSabertoothorSyRenmotordriverrunninginPacketSerialmode

MainPage Classes Files ExamplesClassList ClassIndex ClassMembers

PublicMemberFunctions|StaticPublicMemberFunctions|

Listofallmembers

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

SabertoothClassReference

ControlsaSabertoothorSyRenmotordriverrunninginPacketSerialmode.More...

PublicMemberFunctions Sabertooth(byteaddress)

Sabertooth(byteaddress,SabertoothStream&port)

byte address()constSabertoothStream& port()const

void autobaud(booleandontWait=false)const

void command(bytecommand,bytevalue)const

void motor(intpower)const

void motor(bytemotor,intpower)const

void drive(intpower)const

void turn(intpower)const

void stop()const

void setMinVoltage(bytevalue)const

void setMaxVoltage(bytevalue)const

void setBaudRate(longbaudRate)const

void setDeadband(bytevalue)const

void setRamping(bytevalue)const

void setTimeout(intmilliseconds)const

StaticPublicMemberFunctions

staticvoid autobaud(SabertoothStream&port,booleandontWait=false)

DetailedDescription

ControlsaSabertoothorSyRenmotordriverrunninginPacketSerialmode.

Examples:1.Basics/Jolty/Jolty.ino,1.Basics/Sweep/Sweep.ino,1.Basics/TankStyleSweep/TankStyleSweep.ino,2.Settings/MinVoltage/MinVoltage.ino,2.Settings/Persistent/BaudRate/BaudRate.ino,2.Settings/Persistent/Deadband/Deadband.ino,2.Settings/Persistent/MaxVoltage/MaxVoltage.ino,2.Settings/Persistent/Ramping/Ramping.ino,2.Settings/SerialTimeout/SerialTimeout.ino,3.Advanced/SharedLine/SharedLine.ino,and3.Advanced/SoftwareSerial/SoftwareSerial.ino.

Constructor&DestructorDocumentation

Sabertooth::Sabertooth ( byte address )

InitializesanewinstanceoftheSabertoothclass.Thedriveraddressissettothevaluegiven,andtheArduinoTXserialportisused.

Parametersaddress Thedriveraddress.

Sabertooth::Sabertooth ( byte address,SabertoothStream& port)

InitializesanewinstanceoftheSabertoothclass.Thedriveraddressissettothevaluegiven,andthespecifiedserialportisused.

Parametersaddress Thedriveraddress.port Theporttouse.

MemberFunctionDocumentation

byteSabertooth::address ( ) const inline

Getsthedriveraddress.

ReturnsThedriveraddress.

voidSabertooth::autobaud ( boolean dontWait=false ) const

Sendstheautobaudcharacter.

ParametersdontWait Iffalse,adelayisaddedtogivethedriver

timetostartup.

Examples:3.Advanced/SharedLine/SharedLine.ino.

voidSabertooth::autobaud ( SabertoothStream& port,

boolean dontWait=false)

Sendstheautobaudcharacter.

Parametersport Theporttouse.dontWait Iffalse,adelayisaddedtogivethedrivertimetostart

up.

voidSabertooth::command ( byte command,byte value) const

Sendsapacketserialcommandtothemotordriver.

Parameterscommand Thenumberofthecommand.value Thecommand'svalue.

voidSabertooth::drive ( int power ) const

Setsthedrivingpower.

Parameterspower Thepower,between-127and127.

voidSabertooth::motor ( int power ) const

Setsthepowerofmotor1.

Parameterspower Thepower,between-127and127.

Examples:3.Advanced/SharedLine/SharedLine.ino.

voidSabertooth::motor ( bytemotor,int power) const

Setsthepowerofthespecifiedmotor.

Parametersmotor Themotornumber,1or2.power Thepower,between-127and127.

SabertoothStream&Sabertooth::port ( ) const inline

Getstheserialport.

ReturnsTheserialport.

voidSabertooth::setBaudRate ( long baudRate ) const

Setsthebaudrate.BaudrateisstoredinEEPROM,sochangespersistbetweenpowercycles.

ParametersbaudRate Thebaudrate.Thiscanbe2400,9600,

19200,38400,oronsomedrivers115200.

voidSabertooth::setDeadband ( byte value ) const

Setsthedeadband.DeadbandisstoredinEEPROM,sochangespersistbetweenpowercycles.

Parametersvalue Thedeadbandvalue.Motorpowersintherange

[-deadband,deadband]willbeconsideredinthedeadband,andwillnotpreventthedriverfromenteringnorcausethedrivertoleaveanidlebrakestate.0resetstothedefault,whichis3.

voidSabertooth::setMaxVoltage ( byte value ) const

Setsthemaximumvoltage.MaximumvoltageisstoredinEEPROM,sochangespersistbetweenpowercycles.

Parametersvalue Thevoltage.Theunitsofthisvaluearedriver-

specificandarespecifiedinthePacketSerialchapterofthedriver'susermanual.

voidSabertooth::setMinVoltage ( byte value ) const

Setstheminimumvoltage.

Parametersvalue Thevoltage.Theunitsofthisvaluearedriver-

specificandarespecifiedinthePacketSerialchapterofthedriver'susermanual.

voidSabertooth::setRamping ( byte value ) const

Setstheramping.RampingisstoredinEEPROM,sochangespersistbetweenpowercycles.

Parametersvalue Therampingvalue.Consulttheusermanualfor

possiblevalues.

voidSabertooth::setTimeout ( int milliseconds ) const

Setstheserialtimeout.

Parametersmilliseconds Themaximumtimeinmilliseconds

betweenpackets.Ifthistimeisexceeded,thedriverwillstopthemotors.Thisvalueisroundeduptothenearest100milliseconds.Thislibraryassumesthecommandvalueisinunitsof100milliseconds.Thisistrueformostdrivers,butnotall.Checkthepacketserialchapterofthedriver'susermanualtomakesure.

voidSabertooth::stop ( ) const

Stops.

voidSabertooth::turn ( int power ) const

Setstheturningpower.

Parameterspower Thepower,between-127and127.

MainPage Classes Files ExamplesClassList ClassIndex ClassMembers

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

ClassIndex

S

S

Sabertooth

S

MainPage Classes Files ExamplesClassList ClassIndex ClassMembers

All Functions

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

Hereisalistofalldocumentedclassmemberswithlinkstotheclassdocumentationforeachmember:

address():Sabertoothautobaud():Sabertoothcommand():Sabertoothdrive():Sabertoothmotor():Sabertoothport():SabertoothSabertooth():SabertoothsetBaudRate():SabertoothsetDeadband():SabertoothsetMaxVoltage():SabertoothsetMinVoltage():SabertoothsetRamping():SabertoothsetTimeout():Sabertoothstop():Sabertoothturn():Sabertooth

MainPage Classes Files ExamplesClassList ClassIndex ClassMembers

All Functions

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

address():Sabertoothautobaud():Sabertoothcommand():Sabertoothdrive():Sabertoothmotor():Sabertoothport():SabertoothSabertooth():SabertoothsetBaudRate():SabertoothsetDeadband():SabertoothsetMaxVoltage():SabertoothsetMinVoltage():SabertoothsetRamping():SabertoothsetTimeout():Sabertoothstop():Sabertoothturn():Sabertooth

MainPage Classes Files ExamplesFileList

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

FileList

Hereisalistofalldocumentedfileswithbriefdescriptions:[detaillevel1 2]

SabertoothSabertooth.h

MainPage Classes Files ExamplesSabertooth

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

SabertoothDirectoryReference

Filesfile Sabertooth.cppfile Sabertooth.h[code]

MainPage Classes Files ExamplesFileList

Sabertooth

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

Sabertooth.h

1 /*

2 ArduinoLibraryforSyRen/SabertoothPacket

Serial

3 Copyright(c)2012-2013DimensionEngineering

LLC

4 http://www.dimensionengineering.com/arduino

5

6 Permissiontouse,copy,modify,and/or

distributethissoftwareforany

7 purposewithorwithoutfeeishereby

granted,providedthattheabove

8 copyrightnoticeandthispermissionnotice

appearinallcopies.

9

10 THESOFTWAREISPROVIDED"ASIS"ANDTHE

AUTHORDISCLAIMSALLWARRANTIES

11 WITHREGARDTOTHISSOFTWAREINCLUDINGALL

IMPLIEDWARRANTIESOF

12 MERCHANTABILITYANDFITNESS.INNOEVENT

SHALLTHEAUTHORBELIABLEFORANY

13 SPECIAL,DIRECT,INDIRECT,ORCONSEQUENTIAL

DAMAGESORANYDAMAGESWHATSOEVER

14 RESULTINGFROMLOSSOFUSE,DATAORPROFITS,

WHETHERINANACTIONOFCONTRACT,

15 NEGLIGENCEOROTHERTORTIOUSACTION,ARISING

OUTOFORINCONNECTIONWITHTHE

16 USEORPERFORMANCEOFTHISSOFTWARE.

17 */

18

19 #ifndefSabertooth_h

20 #defineSabertooth_h

21

22 #ifdefined(ARDUINO)&&ARDUINO>=100

23 #include<Arduino.h>

24 typedefStreamSabertoothStream;

25 #else

26 #include<WProgram.h>

27 typedefPrintSabertoothStream;

28 #endif

29

30 #ifdefined(USBCON)

31 #defineSabertoothTXPinSerialSerial1//

ArduinoLeonardohasTX->1onSerial1,not

Serial.

32 #else

33 #defineSabertoothTXPinSerialSerial

34 #endif

35 #defineSyRenTXPinSerial

SabertoothTXPinSerial

36

41 classSabertooth

42 {

43 public:

49 Sabertooth(byteaddress);

50

57 Sabertooth(byteaddress,SabertoothStream&

port);

58

59 public:

64 inlinebyteaddress()const{return

_address;}

65

70 inlineSabertoothStream&port()const{

return_port;}

71

76 voidautobaud(booleandontWait=false)

const;

77

83 staticvoidautobaud(SabertoothStream&

port,booleandontWait=false);

84

90 voidcommand(bytecommand,bytevalue)

const;

91

92 public:

97 voidmotor(intpower)const;

98

104 voidmotor(bytemotor,intpower)const;

105

110 voiddrive(intpower)const;

111

116 voidturn(intpower)const;

117

121 voidstop()const;

122

123 public:

128 voidsetMinVoltage(bytevalue)const;

129

135 voidsetMaxVoltage(bytevalue)const;

136

142 voidsetBaudRate(longbaudRate)const;

143

152 voidsetDeadband(bytevalue)const;

153

159 voidsetRamping(bytevalue)const;

160

169 voidsetTimeout(intmilliseconds)const;

170

171 private:

172 voidthrottleCommand(bytecommand,int

power)const;

173

174 private:

175 constbyte_address;

176 SabertoothStream&_port;

177 };

178

179 #endif

MainPage Classes Files Examples

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

Examples

Hereisalistofallexamples:

1.Basics/Jolty/Jolty.ino1.Basics/Sweep/Sweep.ino1.Basics/TankStyleSweep/TankStyleSweep.ino2.Settings/MinVoltage/MinVoltage.ino2.Settings/Persistent/BaudRate/BaudRate.ino2.Settings/Persistent/Deadband/Deadband.ino2.Settings/Persistent/MaxVoltage/MaxVoltage.ino2.Settings/Persistent/Ramping/Ramping.ino2.Settings/SerialTimeout/SerialTimeout.ino3.Advanced/SharedLine/SharedLine.ino3.Advanced/SoftwareSerial/SoftwareSerial.ino

MainPage Classes Files Examples

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

1.Basics/Jolty/Jolty.ino

Goesinonedirection,stops,andthengoesintheotherdirection.

//JoltySampleforPacketSerial

//Copyright(c)2012DimensionEngineeringLLC

//Seelicense.txtforlicensedetails.

#include<Sabertooth.h>

SabertoothST(128);//TheSabertoothisonaddress

128.We'llnameitsobjectST.

//Ifyou'vesetupyourSabertoothonadifferent

address,ofcoursechange

//thathere.Forhowtoconfigureaddress,etc.

seetheDIPSwitchWizardfor

//Sabertooth-

http://www.dimensionengineering.com/datasheets/

SabertoothDIPWizard/start.htm

//SyRen-

http://www.dimensionengineering.com/datasheets/

SyrenDIPWizard/start.htm

//BesuretoselectPacketizedSerialModefor

usewiththislibrary.

//

//Onthatnote,youcanusethislibraryfor

SyRenjustaseasily.

//Thediff-drivecommands(drive,turn)donot

workonaSyRen,ofcourse,butitwillrespond

correctly

//ifyoucommandmotor1todosomething

(ST.motor(1,...)),justlikeaSabertooth.

//

//Inthissample,hardwareserialTXconnectsto

S1.

//SeetheSoftwareSerialexamplein3.Advanced

forhowtouseotherpins.

voidsetup()

{

SabertoothTXPinSerial.begin(9600);//9600isthe

defaultbaudrateforSabertoothpacketserial.

ST.autobaud();//Sendtheautobaudcommandto

theSabertoothcontroller(s).

//NOTE:*Notall*Sabertoothcontrollersneed

thiscommand.

//Itdoesn'thurtanything,butV2

controllersusean

//EEPROMsetting(changeablewiththe

functionsetBaudRate)toset

//thebaudrateinsteadofdetectingwith

autobaud.

//

//Ifyouhavea2x12,2x25V2,2x60or

SyRen50,youcanremove

//theautobaudlineandsaveyourselftwo

secondsofstartupdelay.

}

voidloop()

{

ST.motor(1,127);//Goforwardatfullpower.

delay(2000);//Wait2seconds.

ST.motor(1,0);//Stop.

delay(2000);//Wait2seconds.

ST.motor(1,-127);//Reverseatfullpower.

delay(2000);//Wait2seconds.

ST.motor(1,0);//Stop.

delay(2000);

}

MainPage Classes Files Examples

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

1.Basics/Sweep/Sweep.ino

Sweepsfromfullreversetofullforwardandthenfromfullforwardtofullreverse.

//SweepSampleforPacketSerial

//Copyright(c)2012DimensionEngineeringLLC

//Seelicense.txtforlicensedetails.

#include<Sabertooth.h>

SabertoothST(128);//TheSabertoothisonaddress

128.We'llnameitsobjectST.

//Ifyou'vesetupyourSabertoothonadifferent

address,ofcoursechange

//thathere.Forhowtoconfigureaddress,etc.

seetheDIPSwitchWizardfor

//Sabertooth-

http://www.dimensionengineering.com/datasheets/

SabertoothDIPWizard/start.htm

//SyRen-

http://www.dimensionengineering.com/datasheets/

SyrenDIPWizard/start.htm

//BesuretoselectPacketizedSerialModefor

usewiththislibrary.

//

//Onthatnote,youcanusethislibraryfor

SyRenjustaseasily.

//Thediff-drivecommands(drive,turn)donot

workonaSyRen,ofcourse,butitwillrespond

correctly

//ifyoucommandmotor1todosomething

(ST.motor(1,...)),justlikeaSabertooth.

//

//Inthissample,hardwareserialTXconnectsto

S1.

//SeetheSoftwareSerialexamplein3.Advanced

forhowtouseotherpins.

voidsetup()

{

SabertoothTXPinSerial.begin(9600);//9600isthe

defaultbaudrateforSabertoothpacketserial.

ST.autobaud();//Sendtheautobaudcommandto

theSabertoothcontroller(s).

//NOTE:*Notall*Sabertoothcontrollersneed

thiscommand.

//Itdoesn'thurtanything,butV2

controllersusean

//EEPROMsetting(changeablewiththe

functionsetBaudRate)toset

//thebaudrateinsteadofdetectingwith

autobaud.

//

//Ifyouhavea2x12,2x25V2,2x60or

SyRen50,youcanremove

//theautobaudlineandsaveyourselftwo

secondsofstartupdelay.

}

voidloop()

{

intpower;

//Rampmotor1from-127to127(fullreverseto

fullforward),

//waiting20ms(1/50thofasecond)pervalue.

for(power=-127;power<=127;power++)

{

ST.motor(1,power);

delay(20);

}

//Nowgobackthewaywecame.

for(power=127;power>=-127;power--)

{

ST.motor(1,power);//TipforSyRenusers:

TypingST.motor(power)doesthesamethingas

ST.motor(1,power).

delay(20);//

SinceSyRendoesn'thaveamotor2,this

alternativecansaveyoutyping.

}

}

MainPage Classes Files Examples

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

1.Basics/TankStyleSweep/TankStyleSweep.ino

Sweepsvariousrangesinmixed(rover)mode.

//Tank-StyleSweepSampleforPacketSerial

//Copyright(c)2012DimensionEngineeringLLC

//Seelicense.txtforlicensedetails.

#include<Sabertooth.h>

//Mixedmodeisfortank-stylediff-driverobots.

SabertoothST(128);//TheSabertoothisonaddress

128.We'llnameitsobjectST.

//Ifyou'vesetupyourSabertoothonadifferent

address,ofcoursechange

//thathere.Forhowtoconfigureaddress,etc.

seetheDIPSwitchWizardfor

//Sabertooth-

http://www.dimensionengineering.com/datasheets/

SabertoothDIPWizard/start.htm

//SyRen-

http://www.dimensionengineering.com/datasheets/

SyrenDIPWizard/start.htm

//BesuretoselectPacketizedSerialModefor

usewiththislibrary.

//

//Thissampleusesthemixedmode(diff-drive)

commands,whichrequiretwomotors

//andhencedonotworkonaSyRen.

//

//Inthissample,hardwareserialTXconnectsto

S1.

//SeetheSoftwareSerialexamplein3.Advanced

forhowtouseotherpins.

voidsetup()

{

SabertoothTXPinSerial.begin(9600);//9600isthe

defaultbaudrateforSabertoothpacketserial.

ST.autobaud();//Sendtheautobaudcommandto

theSabertoothcontroller(s).

//NOTE:*Notall*Sabertoothcontrollersneed

thiscommand.

//Itdoesn'thurtanything,butV2

controllersusean

//EEPROMsetting(changeablewiththe

functionsetBaudRate)toset

//thebaudrateinsteadofdetectingwith

autobaud.

//

//Ifyouhavea2x12,2x25V2,2x60or

SyRen50,youcanremove

//theautobaudlineandsaveyourselftwo

secondsofstartupdelay.

ST.drive(0);//TheSabertoothwon'tactonmixed

modepacketserialcommandsuntil

ST.turn(0);//ithasreceivedpowerlevelsfor

BOTHthrottleandturning,sinceit

//mixesthetwotogethertogetdiff-drivepower

levelsforbothmotors.

}

//TheSLOWramphereisturning,andtheFASTramp

isthrottle.

//Ifthat'stheoppositeofwhatyou'reseeing,

swapM2AandM2B.

voidloop()

{

intpower;

//Don'tturn.Rampfromgoingbackwardstogoing

forwards,waiting20ms(1/50thofasecond)

pervalue.

for(power=-127;power<=127;power++)

{

ST.drive(power);

delay(20);

}

//Now,let'suseapowerlevelof20(outof127)

forward.

//Thisway,ourturningwillhavearadius.

ST.drive(20);

//Rampturningfromfulllefttofullright

SLOWLYbywaiting50ms(1/20thofasecond)

pervalue.

for(power=-127;power<=127;power++)

{

ST.turn(power);

delay(50);

}

//Nowstopturning,andstopdriving.

ST.turn(0);

ST.drive(0);

//Waitabit.Thisissoyoucancatchyourrobot

ifyouwantto.:-)

delay(5000);

}

MainPage Classes Files Examples

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

2.Settings/MinVoltage/MinVoltage.ino

Setstheminimumvoltage.

//SetMinimumVoltageSampleforPacketSerial

//Copyright(c)2012DimensionEngineeringLLC

//Seelicense.txtforlicensedetails.

//Thevaluesinthissamplearespecificallyfor

theSabertooth2x25,andmay

//nothavethesameeffectonothermodels.

#include<Sabertooth.h>

SabertoothST(128);

voidsetup()

{

SabertoothTXPinSerial.begin(9600);

ST.autobaud();

//Thissettingdoesnotpersistbetweenpower

cycles.

//SeethePacketSerialsectionofthe

documentationforwhatvaluestouse

//fortheminimumvoltagecommand.Itmayvary

betweenSabertoothmodels

//(2x25,2x60,etc.).

//

//OnaSabertooth2x25,thevalueis(Desired

Volts-6)X5.

//So,inthissample,we'llmakethelowbattery

cutoff12V:(12-6)X5=30.

ST.setMinVoltage(30);

}

voidloop()

{

ST.motor(1,50);

delay(5000);

ST.motor(1,-50);

delay(5000);

}

MainPage Classes Files Examples

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

2.Settings/Persistent/BaudRate/BaudRate.ino

ChangesthePacketSerialbaudrate.

WARNING:Thissamplemakeschangesthatwillpersistbetweenrestarts.

//SetBaudRateSampleforPacketSerial

//Copyright(c)2012DimensionEngineeringLLC

//Seelicense.txtforlicensedetails.

//WARNING:Thissamplemakeschangesthatwill

persistbetweenrestarts.

//NOTE:ThesetBaudRatefunctionwillonlyhavean

effectonV2controllers(2x12,2x25V2,2x60,

SyRen50).

//Earliercontrollersautomaticallydetect

thebaudrateyouchooseinSerial.begin

//whenyoucalltheautobaudfunction.

AutobaudwasreplacedinV2controllersfor

reliability

//intheeventthattheSabertoothlost

power.

#include<Sabertooth.h>

SabertoothST(128);

voidsetup()

{

//ThissamplewilltelltheSabertooth*at9600

baud*to*switchto2400baud*.

//Keepinmindyoumustsendthecommandto

changethebaudrate*atthebaudrate

//theSabertoothislisteningat*(factory

defaultis9600).Afterthat,ifitworks,

//youwillbeabletocommunicateusingthenew

baudrate.

//

//Optionsare:

//2400

//9600

//19200

//38400

//115200(onlysupportedbysomedevicessuch

as2X60--checkthedevice'sdatasheet)

//

//WARNING:TheSabertoothremembersthiscommand

betweenrestarts.

//TochangeyourSabertoothbacktoitsdefault,

youmust*beatthebaudrateyou've

//settheSabertoothto*,andthencall

ST.setBaudRate(9600)

SabertoothTXPinSerial.begin(9600);

ST.setBaudRate(2400);

SabertoothTXPinSerial.end();

//OK,we'reat2400.Let'stalktotheSabertooth

atthatspeed.

SabertoothTXPinSerial.begin(2400);

}

voidloop()

{

ST.drive(0);

ST.turn(20);

delay(2000);

ST.turn(-20);

delay(2000);

}

MainPage Classes Files Examples

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

2.Settings/Persistent/Deadband/Deadband.ino

Modifiesthedeadband.

WARNING:Thissamplemakeschangesthatwillpersistbetweenrestarts.

//SetDeadbandSampleforPacketSerial

//Copyright(c)2012DimensionEngineeringLLC

//Seelicense.txtforlicensedetails.

//WARNING:Thissamplemakeschangesthatwill

persistbetweenrestartsANDinallmodes.

#include<Sabertooth.h>

SabertoothST(128);

voidsetup()

{

SabertoothTXPinSerial.begin(9600);

ST.autobaud();

//Thismakesthedeadbandfrom-20to20(of

127).

//Ifyourcommandsforamotorstayentirely

withinthedeadbandformorethan

//asecond,themotordriverwillstopthemotor.

//WARNING:TheSabertoothremembersthiscommand

betweenrestartsANDinallmodes.

//TochangeyourSabertoothbacktoitsdefault,

callST.setDeadband(0)

ST.setDeadband(20);

}

voidloop()

{

//50isgreaterthan20,sothemotormoves.

ST.motor(1,50);

delay(5000);

//10isNOT,sothemotordoesnotmove.

ST.motor(1,10);

delay(5000);

}

MainPage Classes Files Examples

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

2.Settings/Persistent/MaxVoltage/MaxVoltage.ino

Modifiesthemaximumvoltage.

WARNING:Thissamplemakeschangesthatwillpersistbetweenrestarts.

//SetMaximumVoltageSampleforPacketSerial

//Copyright(c)2012DimensionEngineeringLLC

//Seelicense.txtforlicensedetails.

//WARNING:Thissamplemakeschangesthatwill

persistbetweenrestartsANDinallmodes.

//Thevaluesinthissampleare

specificallyfortheSabertooth2x25,andmay

//nothavethesameeffectonother

models.

#include<Sabertooth.h>

SabertoothST(128);

voidsetup()

{

SabertoothTXPinSerial.begin(9600);

ST.autobaud();

//SeethePacketSerialsectionofthe

documentationforwhatvaluestouse

//forthemaximumvoltagecommand.Itmayvary

betweenSabertoothmodels

//(2x25,2x60,etc.).

//

//OnaSabertooth2x25,thevalueis(Desired

Volts)X5.12.

//Inthissample,we'llcapthemaxvoltage

beforethemotordriverdoes

//ahardbrakeat14V.Fora12VATXpowersupply

thismightbereasonable--

//at16Vtheytendtoshutoff.Here,ifthe

voltageclimbsabove

//14Vduetoregenerativebraking,theSabertooth

willgointohardbrakeinstead.

//Whilethisisoccuring,theredErrorLEDwill

turnon.

//

//14X5.12=71.68,sowe'llgowith71,cutting

offslightlybelow14V.

//

//WARNING:Thissettingpersistsbetweenpower

cycles.

ST.setMaxVoltage(71);

}

voidloop()

{

ST.motor(1,50);

delay(5000);

ST.motor(1,-50);

delay(5000);

}

MainPage Classes Files Examples

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

2.Settings/Persistent/Ramping/Ramping.ino

Modifiestheramptime.

WARNING:Thissamplemakeschangesthatwillpersistbetweenrestarts.

//SetRampingSampleforPacketSerial

//Copyright(c)2012DimensionEngineeringLLC

//Seelicense.txtforlicensedetails.

//WARNING:Thissamplemakeschangesthatwill

persistbetweenrestartsANDinallmodes.

#include<Sabertooth.h>

SabertoothST(128);

voidsetup()

{

SabertoothTXPinSerial.begin(9600);

ST.autobaud();

//SeetheSabertooth2x60documentationfor

informationonrampingvalues.

//Therearethreeranges:1-10(Fast),11-20

(Slow),and21-80(Intermediate).

//Therampingvalue14usedheresetsaramptime

of4secondsforfull

//forward-to-fullreverse.

//

//0turnsofframping.Turningofframping

requiresapowercycle.

//

//WARNING:TheSabertoothremembersthiscommand

betweenrestartsANDinallmodes.

//TochangeyourSabertoothbacktoitsdefault,

callST.setRamping(0)

ST.setRamping(14);

}

voidloop()

{

//Fullforward,bothmotors.

ST.motor(1,127);

ST.motor(2,127);

delay(5000);

//Fullreverse

ST.motor(1,-127);

ST.motor(2,-127);

delay(5000);

}

MainPage Classes Files Examples

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

2.Settings/SerialTimeout/SerialTimeout.ino

Setsaserialtimeout,andthendelaystodemonstrateitsstoppingbehavior.

//SetSerialTimeoutSampleforPacketSerial

//Copyright(c)2012DimensionEngineeringLLC

//Seelicense.txtforlicensedetails.

#include<Sabertooth.h>

SabertoothST(128);

voidsetup()

{

SabertoothTXPinSerial.begin(9600);

ST.autobaud();

//setTimeoutroundsuptothenearest100

milliseconds,sothis950willactuallybe1

second.

//Avalueof0disablestheserialtimeout.

ST.setTimeout(950);

}

voidloop()

{

//Setmotor1toreverse20(outof127),and

sleepfor5seconds.

//Noticehowitcutsoutafter1second--this

istheserialtimeoutinaction.

//Sinceweconfigureditinsetup()for1second,

1secondwithoutanynew

//commandswillcausethemotorstostop.

ST.motor(1,-20);

delay(5000);

//Whydothis?

//IftheS1wiregetscutforsomereason,orif

yourprogramcrashes,

//theSabertoothwillstopreceivingcommands

fromtheArduino.

//Withatimeout,yourrobotwillstop.So,it's

asafetyfeaturemostly.

}

MainPage Classes Files Examples

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

3.Advanced/SharedLine/SharedLine.ino

CommunicateswithtwoSabertoothmotordriversusingasharedTX/S1wire.

//SharedLineSampleforPacketSerial

//Copyright(c)2012DimensionEngineeringLLC

//Seelicense.txtforlicensedetails.

#include<Sabertooth.h>

//Upto8Sabertooth/SyRenmotordriverscanshare

thesameS1line.

//Thissampleusesthree:address128and129on

ST1[0]andST1[2],

//andaddress130onST2.

SabertoothST1[2]={Sabertooth(128),

Sabertooth(129)};

SabertoothST2(130);

voidsetup()

{

SabertoothTXPinSerial.begin(9600);

Sabertooth::autobaud(SabertoothTXPinSerial);//

Autobaudisforthewholeserialline--you

don'tneedtodo

//itforeachindividualmotordriver.Thisis

theversionof

//theautobaudcommandthatisnottiedtoa

particular

//Sabertoothobject.

//Seetheexamplesin1.Basicsforinformationon

whetheryou

//needthislineatall.

}

voidloop()

{

//ST1[0](address128)haspower50(of127max)

onM1,

//ST1[1](address129)haspower60(of127max)

onM2,and

//ST2(address130)we'lldotank-styleand

haveitdrive20andturnright50.

//Dothisfor5seconds.

ST1[0].motor(1,50);

ST1[1].motor(2,60);

ST2.drive(20);

ST2.turn(50);

delay(5000);

//Andnowlet'sstopfor5seconds,except

address130--we'llletitstopandturn

left...

ST1[0].motor(1,0);

ST1[1].motor(2,0);

ST2.drive(0);

ST2.turn(-40);

delay(5000);

}

MainPage Classes Files Examples

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

3.Advanced/SoftwareSerial/SoftwareSerial.ino

UsesapinotherthanTXtoconnecttoS1.

//SoftwareSerialSampleforPacketSerial

//Copyright(c)2012DimensionEngineeringLLC

//Seelicense.txtforlicensedetails.

#include<SoftwareSerial.h>

#include<Sabertooth.h>

SoftwareSerialSWSerial(NOT_A_PIN,11);//RXonno

pin(unused),TXonpin11(toS1).

SabertoothST(128,SWSerial);//Address128,and

useSWSerialastheserialport.

voidsetup()

{

SWSerial.begin(9600);

ST.autobaud();

}

voidloop()

{

intpower;

//Rampfrom-127to127(fullreversetofull

forward),waiting20ms(1/50thofasecond)

pervalue.

for(power=-127;power<=127;power++)

{

ST.motor(1,power);

delay(20);

}

//Nowgobackthewaywecame.

for(power=127;power>=-127;power--)

{

ST.motor(1,power);

delay(20);

}

}

MainPage Classes Files ExamplesClassList ClassIndex ClassMembers

SyRen/SabertoothPacketSerialLibraryforArduinoControlyourSyRenorSabertoothwithreliablePacketSerial.

SabertoothMemberList

ThisisthecompletelistofmembersforSabertooth,includingallinheritedmembers.

address()const Sabertoothautobaud(booleandontWait=false)const Sabertoothautobaud(SabertoothStream&port,booleandontWait=false) Sabertoothcommand(bytecommand,bytevalue)const Sabertoothdrive(intpower)const Sabertoothmotor(intpower)const Sabertoothmotor(bytemotor,intpower)const Sabertoothport()const SabertoothSabertooth(byteaddress) SabertoothSabertooth(byteaddress,SabertoothStream&port) SabertoothsetBaudRate(longbaudRate)const SabertoothsetDeadband(bytevalue)const SabertoothsetMaxVoltage(bytevalue)const SabertoothsetMinVoltage(bytevalue)const SabertoothsetRamping(bytevalue)const SabertoothsetTimeout(intmilliseconds)const Sabertoothstop()const Sabertoothturn(intpower)const Sabertooth