Package barobo :: Module mobot :: Class Mobot
[hide private]
[frames] | no frames]

Class Mobot

source code

Known Subclasses:

The Mobot Class

Each instance of this class can be used to represent a physical Mobot. The member functions of this class can be used to get data, set motor angles, scan for button events, and more.

Blocking and Non-Blocking Member Functions

The member functions of the Mobot class which are responsible for moving the joints of the Mobot can be categorized into two general types of functions; "blocking" functions and "non-blocking" functions. A blocking function is a function that "hangs" until the complete motion is done, whereas a "non-blocking" function returns as soon as the motion begins, but does not wait until it is done. In the Mobot class, all functions are blocking unless the have the suffix "NB", such as "Mobot.moveNB()".

For example, consider the following lines of code:

   mobot.move(360, 0, 0, 360)
   angles = mobot.getJointAngles()

When the above lines of code are executed, the Mobot will rotate joint 1 360 degrees. Once the joint has rotated the full revolution, the joint angles will be retrieved and stored in the variable "angles". Now consider the following code:

   mobot.moveNB(360, 0, 0)
   angles = mobot.getJointAngles()

For these lines of code, joint 1 also moves 360 degrees. The difference is that with these lines of code, the joint angles will be retrieved as soon as the joint begins turning, instead of waiting for the motion to finish. This is because the non-blocking version of move() was used, which returns immediately after the joint begins moving allowing the getJointAngles() function to execute as the joint begins moving.

The moveWait() function can be used to block until non-blocking motion functions are finished. For instance, the following two blocks of code will accomplish the same task:

   mobot.move(360, 0, 0)
   angles = mobot.getJointAngles()

   mobot.moveNB(360, 0, 0)
   mobot.moveWait()
   angles = mobot.getJointAngles()
Instance Methods [hide private]
 
__init__(self) source code
 
checkStatus(self)
Check to see if the Linkbot is online.
source code
 
connect(self)
Connect to a Linkbot through BaroboLink
source code
 
connectBluetooth(self, bluetooth_mac_addr) source code
 
connectMobotBluetooth(self, bluetooth_mac_addr)
Connect to a legacy bluetooth Linkbot or Mobot.
source code
 
disableButtonCallback(self)
Disable the button callback.
source code
 
disconnect(self)
Disconnect from the Linkbot.
source code
 
driveJointTo(self, joint, angle)
Drive a single joint to a position as fast as possible, using the on-board PID motor controller.
source code
 
driveJointToNB(self, joint, angle)
Non-blocking version of driveJointTo().
source code
 
driveTo(self, angle1, angle2, angle3, angle4)
Drive the joints to angles as fast as possible using on-board PID controller.
source code
 
driveToNB(self, angle1, angle2, angle3, angle4)
Non-blocking version of driveTo().
source code
 
enableButtonCallback(self, callbackfunc, userdata=None)
Enable button callbacks.
source code
Robot Form
getFormFactor(self)
Get the form factor.
source code
number
getJointAngle(self, joint)
Get the current angle position of a joint.
source code
[float, float, float]
getJointAngles(self)
Get the current joint angles.
source code
float
getJointSpeed(self, joint)
Get the speed setting of a joint.
source code
(float, float, float, float)
getJointSpeeds(self)
Get a tuple of all joint speeds.
source code
 
getJointState(self, joint)
Get the current state of a joint.
source code
[numbers]
getJointAnglesTime(self)
Get the joint angles with a timestamp.
source code
 
getVersion(self)
Get the firmware version of the Linkbot
source code
 
isMoving(self) source code
 
moveJoint(self, joint, angle)
Move a joint from it's current position by 'angle' degrees.
source code
 
moveJointNB(self, joint, angle)
Non-blocking version of moveJoint().
source code
 
moveJointTo(self, joint, angle)
Move a joint to an angle.
source code
 
moveJointToNB(self, joint, angle)
Non-blocking version of moveJointTo.
source code
 
move(self, angle1, angle2, angle3, angle4)
Move all of the joints on a robot by a number of degrees.
source code
 
moveNB(self, angle1, angle2, angle3, angle4)
Non-blocking version of move().
source code
 
moveContinuous(self, dir1, dir2, dir3, dir4)
Make the joints begin moving continuously.
source code
 
moveTo(self, angle1, angle2, angle3, angle4) source code
 
moveToNB(self, angle1, angle2, angle3, angle4)
Move all joints on the Linkbot.
source code
 
moveWait(self)
Wait until the current robotic motion is finished.
source code
 
recordAnglesBegin(self, delay=0.05)
Begin recording joint angles.
source code
 
recordAnglesEnd(self)
End recording angles and return a list consisting of [time_values, joint1angles, joint2angles, joint3angles]
source code
 
recordAnglesPlot(self) source code
 
reset(self)
Reset the multi-revolution counter on the joints.
source code
 
resetToZero(self)
Reset the multi-revolution counter and move all the joints to zero positions.
source code
 
resetToZeroNB(self) source code
 
setJointMovementState(self, joint, state)
Set a joint movement state
source code
 
setJointSpeed(self, joint, speed)
Set the speed of a joint.
source code
 
setJointSpeeds(self, speed1, speed2, speed3, speed4)
Set all three motor speed simultaneously.
source code
 
setJointState(self, joint, state)
Set a joint's movement state.
source code
 
setJointStates(self, states, speeds)
Set the joint states for all 3 joints simultaneously.
source code
 
setMotorPower(self, joint, power)
Set the power of a motor.
source code
 
setMotorPowers(self, power1, power2, power3, power4) source code
 
setMovementState(self, state1, state2, state3, state4, time=-1)
Set the movement state for all three motors.
source code
 
stop(self) source code
 
_transactMessage(self, buf, maxTries=3, timeout=10.0) source code
 
__messageThread(self) source code
 
__eventThread(self) source code
Method Details [hide private]

checkStatus(self)

source code 

Check to see if the Linkbot is online. Raises an exception if the Linkbot is not online.

connectMobotBluetooth(self, bluetooth_mac_addr)

source code 

Connect to a legacy bluetooth Linkbot or Mobot.

Parameters:
  • bluetooth_mac_addr (string) - The MAC address of the bluetooth Linkbot. Should be something like '00:06:66:6D:12:34'

disableButtonCallback(self)

source code 

Disable the button callback.

See also: enableButtonCallback()

driveJointTo(self, joint, angle)

source code 

Drive a single joint to a position as fast as possible, using the on-board PID motor controller.

Parameters:
  • joint (number [1,3]) - The joint to move
  • angle (number) - The angle to move the joint to, in degrees

driveJointToNB(self, joint, angle)

source code 

Non-blocking version of driveJointTo(). Please see driveJointTo() for more details.

driveTo(self, angle1, angle2, angle3, angle4)

source code 

Drive the joints to angles as fast as possible using on-board PID controller.

Parameters:
  • angle1 (number) - Position to move the joint, in degrees
  • angle2 (number) - Position to move the joint, in degrees
  • angle3 (number) - Position to move the joint, in degrees

driveToNB(self, angle1, angle2, angle3, angle4)

source code 

Non-blocking version of driveTo(). See driveTo() for more details

enableButtonCallback(self, callbackfunc, userdata=None)

source code 

Enable button callbacks. This function temporarily disables the robot's default button actions. Instead, whenever a button is pressed or released, the function given as the parameter 'callbackfunc' is called.

See also: disableButtonCallback()

Parameters:
  • userdata (Anything) - This is data that will be passed into the callbackfunc whenever it is called.
  • callbackfunc (function: func(buttonMask, buttonDown, userdata) . The 'buttonMask' parameter of the callback function will contain a bitmask indicating which buttons have changed. The buttonDown parameter is another bitmask, indicating the current state of each button.)

getFormFactor(self)

source code 

Get the form factor.

Returns: Robot Form
Returns barobo.ROBOTFORM_MOBOT, barobo.ROBOTFORM_I, barobo.ROBOTFORM_L, or barobo.ROBOTFORM_T

getJointAngle(self, joint)

source code 

Get the current angle position of a joint.

Parameters:
  • joint (number) - Get the position of this joint. Can be 1, 2, or 3
Returns: number
Return the joint angle in degrees

getJointAngles(self)

source code 

Get the current joint angles.

Returns: [float, float, float]
The joint angles in degrees

getJointSpeed(self, joint)

source code 

Get the speed setting of a joint. Returned value is in deg/s

Returns: float
The joint speed in deg/sec

getJointSpeeds(self)

source code 

Get a tuple of all joint speeds. See getJointSpeed()

Returns: (float, float, float, float)

getJointState(self, joint)

source code 

Get the current state of a joint. Possible return values are ROBOT_NEUTRAL=0, ROBOT_FORWARD=1, ROBOT_BACKWARD=2, ROBOT_HOLD=3, ROBOT_POSITIVE=4, ROBOT_NEGATIVE=5

getJointAnglesTime(self)

source code 

Get the joint angles with a timestamp. The timestamp is the number of seconds since the robot has powered on.

Returns: [numbers]
[seconds, angle1, angle2, angle3], all angles in degrees

getVersion(self)

source code 

Get the firmware version of the Linkbot

Returns:
Something like (0, 0, 94) or (3, 0, 3), depending on the oldness of the firmware

moveJoint(self, joint, angle)

source code 

Move a joint from it's current position by 'angle' degrees.

Parameters:
  • joint (number) - The joint to move: 1, 2, or 3
  • angle (number) - The number of degrees to move the joint from it's current position. For example, "45" will move the joint in the positive direction by 45 degrees from it's current location, and "-30" will move the joint in the negative direction by 30 degrees.

moveJointNB(self, joint, angle)

source code 

Non-blocking version of moveJoint(). See moveJoint() for more details.

moveJointTo(self, joint, angle)

source code 

Move a joint to an angle.

Parameters:
  • joint (number) - The joint to move: 1, 2, or 3
  • angle (number) - The absolute position you want the joint to move to. Values are in degrees and can be any value. For example, the value "720" means two full rotations in the positive directions past "0".

moveJointToNB(self, joint, angle)

source code 

Non-blocking version of moveJointTo. See moveJointTo for more details.

move(self, angle1, angle2, angle3, angle4)

source code 

Move all of the joints on a robot by a number of degrees.

Parameters:
  • angle1 (number) - Number of degrees to move joint 1. Similar for parameters 'angle2' and 'angle3'.

moveNB(self, angle1, angle2, angle3, angle4)

source code 

Non-blocking version of move(). See move() for more details

moveContinuous(self, dir1, dir2, dir3, dir4)

source code 

Make the joints begin moving continuously.

Parameters:
  • dir1 (Barobo Direction Macro) - This parameter may take the following values:
    • ROBOT_NEUTRAL: Makes the joint relax
    • ROBOT_FORWARD: Rotates the joint to move the robot in the "forward" direction, if the robot has wheels.
    • ROBOT_BACKWARD: Same as above but backwards
    • ROBOT_HOLD: Hold the joint at its current position
    • ROBOT_POSITIVE: Rotates the joint in the "positive" direction, according to the right-hand-rule.
    • ROBOT_NEGATIVE: Same as above but in the negative direction.

moveToNB(self, angle1, angle2, angle3, angle4)

source code 

Move all joints on the Linkbot. Linkbot-I modules will ignore the 'angle2' parameter and Linkbot-L modules will ignore the 'angle3' parameter.

This function is the non-blocking version of moveTo(), meaning this function will return immediately after the robot has begun moving and will not wait until the motion is finished.

Parameters:
  • angle1 (number) - Position to move the joint, in degrees
  • angle2 (number) - Position to move the joint, in degrees
  • angle3 (number) - Position to move the joint, in degrees

recordAnglesBegin(self, delay=0.05)

source code 

Begin recording joint angles.

Parameters:
  • delay (number) - The number of seconds to delay between joint angles readings.

setJointMovementState(self, joint, state)

source code 

Set a joint movement state

Parameters:
  • state (Barobo Direction Macro) - This parameter may take the following values:
    • ROBOT_NEUTRAL: Makes the joint relax
    • ROBOT_FORWARD: Rotates the joint to move the robot in the "forward" direction, if the robot has wheels.
    • ROBOT_BACKWARD: Same as above but backwards
    • ROBOT_HOLD: Hold the joint at its current position
    • ROBOT_POSITIVE: Rotates the joint in the "positive" direction, according to the right-hand-rule.
    • ROBOT_NEGATIVE: Same as above but in the negative direction.

setJointSpeed(self, joint, speed)

source code 

Set the speed of a joint.

Parameters:
  • joint (number) - The joint to change the speed. Can be 1, 2, or 3
  • speed (number) - The speed to set the joint to, in degrees/second.

setJointSpeeds(self, speed1, speed2, speed3, speed4)

source code 

Set all three motor speed simultaneously. Parameters in degrees/second.

setJointState(self, joint, state)

source code 

Set a joint's movement state.

Parameters:
  • joint - The joint id: 1, 2, or 3
  • state (Barobo Direction Macro) - This parameter may take the following values:
    • ROBOT_NEUTRAL: Makes the joint relax
    • ROBOT_FORWARD: Rotates the joint to move the robot in the "forward" direction, if the robot has wheels.
    • ROBOT_BACKWARD: Same as above but backwards
    • ROBOT_HOLD: Hold the joint at its current position
    • ROBOT_POSITIVE: Rotates the joint in the "positive" direction, according to the right-hand-rule.
    • ROBOT_NEGATIVE: Same as above but in the negative direction.

setJointStates(self, states, speeds)

source code 

Set the joint states for all 3 joints simultaneously.

Parameters:
  • states ([state1, state2...]) - Each state may take the following values:
    • ROBOT_NEUTRAL: Makes the joint relax
    • ROBOT_FORWARD: Rotates the joint to move the robot in the "forward" direction, if the robot has wheels.
    • ROBOT_BACKWARD: Same as above but backwards
    • ROBOT_HOLD: Hold the joint at its current position
    • ROBOT_POSITIVE: Rotates the joint in the "positive" direction, according to the right-hand-rule.
    • ROBOT_NEGATIVE: Same as above but in the negative direction.
  • speeds ([speed1, speed2 ...]) - The speeds to set each joint

setMotorPower(self, joint, power)

source code 

Set the power of a motor.

Parameters:
  • joint (number) - The joint to control. Can be 1, 2, or 3
  • power (integer) - An integer between -255 and 255.

setMovementState(self, state1, state2, state3, state4, time=-1)

source code 

Set the movement state for all three motors.

Parameters:
  • state1 (movement_state) - This parameter may take the following values:
    • ROBOT_NEUTRAL: Makes the joint relax
    • ROBOT_FORWARD: Rotates the joint to move the robot in the "forward" direction, if the robot has wheels.
    • ROBOT_BACKWARD: Same as above but backwards
    • ROBOT_HOLD: Hold the joint at its current position
    • ROBOT_POSITIVE: Rotates the joint in the "positive" direction, according to the right-hand-rule.
    • ROBOT_NEGATIVE: Same as above but in the negative direction.