MonoBrick EV3 Firmware
Public Member Functions | Properties | List of all members
MonoBrickFirmware.Movement.Vehicle Class Reference

Class for controlling a vehicle More...

Public Member Functions

 Vehicle (MotorPort left, MotorPort right)
 Initializes a new instance of the Vehicle class. More...
 
void Backward (sbyte speed)
 Run backwards More...
 
WaitHandle Backward (sbyte speed, UInt32 degrees, bool brake)
 Run backwards More...
 
void Forward (sbyte speed)
 Run forward More...
 
WaitHandle Forward (sbyte speed, UInt32 degrees, bool brake)
 Run forward More...
 
void SpinLeft (sbyte speed)
 Spins the vehicle left. More...
 
WaitHandle SpinLeft (sbyte speed, UInt32 degrees, bool brake)
 Spins the left. More...
 
void SpinRight (sbyte speed)
 Spins the vehicle right More...
 
WaitHandle SpinRight (sbyte speed, UInt32 degrees, bool brake)
 Spins the vehicle right More...
 
void Off ()
 Stop moving the vehicle More...
 
void Brake ()
 Brake the vehicle (the motor is still on but it does not move) More...
 
void TurnRightForward (sbyte speed, sbyte turnPercent)
 Turns the vehicle right More...
 
WaitHandle TurnRightForward (sbyte speed, sbyte turnPercent, UInt32 degrees, bool brake)
 Turns the vehicle right More...
 
void TurnRightReverse (sbyte speed, sbyte turnPercent)
 Turns the vehicle right while moving backwards More...
 
WaitHandle TurnRightReverse (sbyte speed, sbyte turnPercent, UInt32 degrees, bool brake)
 Turns the vehicle right while moving backwards More...
 
void TurnLeftForward (sbyte speed, sbyte turnPercent)
 Turns the vehicle left More...
 
WaitHandle TurnLeftForward (sbyte speed, sbyte turnPercent, UInt32 degrees, bool brake)
 Turns the vehicle left More...
 
void TurnLeftReverse (sbyte speed, sbyte turnPercent)
 Turns the vehicle left while moving backwards More...
 
WaitHandle TurnLeftReverse (sbyte speed, sbyte turnPercent, UInt32 degrees, bool brake)
 Turns the vehicle left while moving backwards More...
 

Properties

MotorPort LeftPort [get, set]
 Gets or sets the left motor More...
 
MotorPort RightPort [get, set]
 Gets or sets the right motor More...
 
bool ReverseLeft [get, set]
 Gets or sets a value indicating whether the left motor is running in reverse direction More...
 
bool ReverseRight [get, set]
 Gets or sets a value indicating whether the right motor is running in reverse direction More...
 

Detailed Description

Class for controlling a vehicle

Constructor & Destructor Documentation

MonoBrickFirmware.Movement.Vehicle.Vehicle ( MotorPort  left,
MotorPort  right 
)
inline

Initializes a new instance of the Vehicle class.

Parameters
leftThe left motor of the vehicle
rightThe right motor of the vehicle

Member Function Documentation

void MonoBrickFirmware.Movement.Vehicle.Backward ( sbyte  speed)
inline

Run backwards

Parameters
speedSpeed of the vehicle -100 to 100
WaitHandle MonoBrickFirmware.Movement.Vehicle.Backward ( sbyte  speed,
UInt32  degrees,
bool  brake 
)
inline

Run backwards

Parameters
speedSpeed.
degreesDegrees.
brakeIf set to true motors will brake when done otherwise off.
void MonoBrickFirmware.Movement.Vehicle.Brake ( )
inline

Brake the vehicle (the motor is still on but it does not move)

void MonoBrickFirmware.Movement.Vehicle.Forward ( sbyte  speed)
inline

Run forward

Parameters
speedSpeed of the vehicle -100 to 100
WaitHandle MonoBrickFirmware.Movement.Vehicle.Forward ( sbyte  speed,
UInt32  degrees,
bool  brake 
)
inline

Run forward

Parameters
speedSpeed.
degreesDegrees.
brakeIf set to true motors will brake when done otherwise off.
void MonoBrickFirmware.Movement.Vehicle.Off ( )
inline

Stop moving the vehicle

void MonoBrickFirmware.Movement.Vehicle.SpinLeft ( sbyte  speed)
inline

Spins the vehicle left.

Parameters
speedSpeed of the vehicle -100 to 100
WaitHandle MonoBrickFirmware.Movement.Vehicle.SpinLeft ( sbyte  speed,
UInt32  degrees,
bool  brake 
)
inline

Spins the left.

Parameters
speedSpeed.
degreesDegrees.
brakeIf set to true motors will brake when done otherwise off.
void MonoBrickFirmware.Movement.Vehicle.SpinRight ( sbyte  speed)
inline

Spins the vehicle right

Parameters
speedSpeed -100 to 100
WaitHandle MonoBrickFirmware.Movement.Vehicle.SpinRight ( sbyte  speed,
UInt32  degrees,
bool  brake 
)
inline

Spins the vehicle right

Parameters
speedSpeed.
degreesDegrees.
brakeIf set to true motors will brake when done otherwise off.
void MonoBrickFirmware.Movement.Vehicle.TurnLeftForward ( sbyte  speed,
sbyte  turnPercent 
)
inline

Turns the vehicle left

Parameters
speedSpeed of the vehicle -100 to 100
turnPercentTurn percent.
WaitHandle MonoBrickFirmware.Movement.Vehicle.TurnLeftForward ( sbyte  speed,
sbyte  turnPercent,
UInt32  degrees,
bool  brake 
)
inline

Turns the vehicle left

Parameters
speedSpeed.
turnPercentTurn percent.
degreesDegrees.
brakeIf set to true motors will brake when done otherwise off.
void MonoBrickFirmware.Movement.Vehicle.TurnLeftReverse ( sbyte  speed,
sbyte  turnPercent 
)
inline

Turns the vehicle left while moving backwards

Parameters
speedSpeed of the vehicle -100 to 100
turnPercentTurn percent.
WaitHandle MonoBrickFirmware.Movement.Vehicle.TurnLeftReverse ( sbyte  speed,
sbyte  turnPercent,
UInt32  degrees,
bool  brake 
)
inline

Turns the vehicle left while moving backwards

Parameters
speedSpeed.
turnPercentTurn percent.
degreesDegrees.
brakeIf set to true motors will brake when done otherwise off.
void MonoBrickFirmware.Movement.Vehicle.TurnRightForward ( sbyte  speed,
sbyte  turnPercent 
)
inline

Turns the vehicle right

Parameters
speedSpeed of the vehicle -100 to 100
turnPercentTurn percent
WaitHandle MonoBrickFirmware.Movement.Vehicle.TurnRightForward ( sbyte  speed,
sbyte  turnPercent,
UInt32  degrees,
bool  brake 
)
inline

Turns the vehicle right

Parameters
speedSpeed.
turnPercentTurn percent.
degreesDegrees.
brakeIf set to true motors will brake when done otherwise off.
void MonoBrickFirmware.Movement.Vehicle.TurnRightReverse ( sbyte  speed,
sbyte  turnPercent 
)
inline

Turns the vehicle right while moving backwards

Parameters
speedSpeed of the vehicle -100 to 100
turnPercentTurn percent.
WaitHandle MonoBrickFirmware.Movement.Vehicle.TurnRightReverse ( sbyte  speed,
sbyte  turnPercent,
UInt32  degrees,
bool  brake 
)
inline

Turns the vehicle right while moving backwards

Parameters
speedSpeed.
turnPercentTurn percent.
degreesDegrees.
brakeIf set to true motors will brake when done otherwise off.

Property Documentation

MotorPort MonoBrickFirmware.Movement.Vehicle.LeftPort
getset

Gets or sets the left motor

The left motor

bool MonoBrickFirmware.Movement.Vehicle.ReverseLeft
getset

Gets or sets a value indicating whether the left motor is running in reverse direction

true if left motor is reverse; otherwise, false.

bool MonoBrickFirmware.Movement.Vehicle.ReverseRight
getset

Gets or sets a value indicating whether the right motor is running in reverse direction

true if right motor is reverse; otherwise, false.

MotorPort MonoBrickFirmware.Movement.Vehicle.RightPort
getset

Gets or sets the right motor

The right motor


The documentation for this class was generated from the following file: