Public Member Functions | Public Attributes | Static Public Attributes
src.element_driver.Element Class Reference

List of all members.

Public Member Functions

def __init__
def blink_led
def clear_encoder
def close
def connect
def digo
def digo_m_per_s
def execute
def execute_ack
def execute_array
def execute_int
def fw
def get_all_analog
def get_analog
def get_analog_cache
def get_baud
def get_compass
def get_dpid
def get_encoder
def get_encoder_count
def get_encoder_resolution
def get_gear_reduction
def get_GP2D12
def get_io
def get_maxez1
def get_MaxEZ1
def get_PhidgetsCurrent
def get_PhidgetsTemperature
def get_PhidgetsVoltage
def get_pids
def get_Ping
def get_units
def get_vpid
def get_wheel_diameter
def get_wheel_track
def i2c
def init_PID
def line
def mogo
def mogo_m_per_s
def open
def pping
def pwm
def recv
def recv_ack
def recv_array
def recv_int
def reset
def restore
def rotate
def rotate_at_speed
def send
def sensor
def servo
def set_baud
def set_dpid
def set_encoder
def set_encoder_resolution
def set_gear_reduction
def set_io
def set_rpid
def set_units
def set_vpid
def set_wheel_diameter
def set_wheel_track
def setup_base_controller
def sp03
def srf04
def srf05
def srf08
def srf10
def step
def stop
def sweep
def tpa81
def travel_at_speed
def travel_distance
def twist
def update_analog_cache
def update_digital_cache
def vel
def vel_fps
def vel_m_per_s
def vel_mph
def voltage

Public Attributes

 analog_sensor_cache
 baudrate
 count
 digital_sensor_cache
 DPID_A
 DPID_B
 DPID_D
 DPID_I
 DPID_P
 encoder_count
 encoder_resolution
 encoder_type
 gear_reduction
 init_pid
 interCharTimeout
 loop_interval
 motors_reversed
 mutex
 port
 shutdown
 temp_units
 ticks_per_meter
 timeout
 units
 VPID_D
 VPID_I
 VPID_L
 VPID_P
 wheel_diameter
 wheel_track
 writeTimeout

Static Public Attributes

int BAD_VALUE = 999
tuple default_pid_params = dict()
float MILLISECONDS_PER_PID_LOOP = 1.6
int N_ANALOG_PORTS = 6
int N_DIGITAL_PORTS = 12
 pi_robot = False

Detailed Description

Configuration Parameters

Definition at line 35 of file element_driver.py.


Constructor & Destructor Documentation

def src.element_driver.Element.__init__ (   self,
  port = "/dev/ttyUSB0",
  baudrate = 19200,
  timeout = 0.5,
  units = 0 
)

Definition at line 72 of file element_driver.py.


Member Function Documentation

def src.element_driver.Element.blink_led (   self,
  id,
  rate 
)
Usage 1: blink_led(id, rate)  
    Usage 2: blink_led([id1, id2], [rate1, rate2]) 
    The blink_led command can blink one of the two onboard green LEDs
    simultaneously, or individually. Each complex parameter is comprised
    of an <ledId:blinkRate> pair. The ledId specifies which of the two
    green LEDs to blink, and blinkRate specifies the delay between blinks.
    The minimum blink rate is 1, and the largest is 127. A value of 0 turns
    the led off.

Definition at line 404 of file element_driver.py.

def src.element_driver.Element.clear_encoder (   self,
  id 
)
Usage 1: clear_encoder(id)
    Usage 2: clear_encoder([id1, id2])
    The clear_encoder command clears the values of the encoder
    count (channel B) for the specified encoder Id.

Definition at line 499 of file element_driver.py.

Close the serial port.

Definition at line 174 of file element_driver.py.

def src.element_driver.Element.connect (   self,
  use_base_controller = False,
  pid_params = default_pid_params 
)

Definition at line 92 of file element_driver.py.

def src.element_driver.Element.digo (   self,
  id,
  dist,
  vel 
)
Usage 1: m(id, dist, vel)
    Usage 2: digo([id1, id2], [dist1, dist2], [vel1, vel2]) 
    Simply put, the digo command allows you to command your robot to
    travel a specified distance, at a specified speed. This command uses
    the internal VPID and DPID algorithms to control velocity and distance.
    Therefore, you must have dual motors, and dual wheel encoders
    connected to the Element motor ports and encoder inputs.

Definition at line 575 of file element_driver.py.

def src.element_driver.Element.digo_m_per_s (   self,
  id,
  dist,
  vel 
)
Identical to digo but specifies velocities in meters per second.

Definition at line 594 of file element_driver.py.

def src.element_driver.Element.execute (   self,
  cmd 
)
Thread safe execution of "cmd" on the Element returning a single value.

Definition at line 232 of file element_driver.py.

def src.element_driver.Element.execute_ack (   self,
  cmd 
)
Thread safe execution of "cmd" on the Element returning True if response is ACK.

Definition at line 304 of file element_driver.py.

def src.element_driver.Element.execute_array (   self,
  cmd 
)
Thread safe execution of "cmd" on the Element returning an array.

Definition at line 265 of file element_driver.py.

def src.element_driver.Element.execute_int (   self,
  cmd 
)
Thread safe execution of "cmd" on the Element returning an int.

Definition at line 338 of file element_driver.py.

The fw command returns the current firmware version.

Definition at line 391 of file element_driver.py.

Return the readings from all analog ports.

Definition at line 736 of file element_driver.py.

def src.element_driver.Element.get_analog (   self,
  id 
)

Definition at line 733 of file element_driver.py.

Definition at line 385 of file element_driver.py.

Get the current baud rate on the serial port.

Definition at line 448 of file element_driver.py.

def src.element_driver.Element.get_compass (   self,
  i2c_addr = None 
)
Usage 1: heading = get_compass()
    Usage 2: heading = get_compass(i2c_addr)           
    The get_compass command queries a Devantech CMPS03 Electronic
    compass module attached to the Elements I2C port.
    The current heading is returned in Binary Radians, or BRADS.To
    convert BRADS to DEGREES, multiply BRADS by 360/255 (~1.41).
    The default I2C address is 0xC0, however another I2C address can be
    supplied as an optional parameter.

Definition at line 418 of file element_driver.py.

Get the PIDA parameter values.

Definition at line 612 of file element_driver.py.

The get_encoder command returns the encoder type for the Element,
    single (0) or quadrature (1).

Definition at line 430 of file element_driver.py.

Usage 1: get_encoder_count(id)
    Usage 2: get_encoder_count([id1, id2])
    The get_encoder_count command returns the values of the encoder
    count (channel B) for the specified encoder Id(s). NOTE: The encoder
    counts for channel A are used for internal VPID and DPID algorithms.

Definition at line 481 of file element_driver.py.

Definition at line 957 of file element_driver.py.

Definition at line 951 of file element_driver.py.

def src.element_driver.Element.get_GP2D12 (   self,
  pin,
  cached = False 
)
Get the distance reading from a GP2D12 IR sensor on the given analog pin.

Definition at line 978 of file element_driver.py.

def src.element_driver.Element.get_io (   self,
  id 
)
Usage 1: get_io(id)
    Usage 2: get_io([id1, id2, id3, ... , idN]) 
    The get_io command changes the pin, pinId (range 0-12), to an input
    (if it was an output), and gets the value of the specified General
    Purpose I/O lines on the Element. The valid range of I/O pin Ids is
    0 thru 12. More than one pid can be specified by enter a list as argument.

Definition at line 508 of file element_driver.py.

def src.element_driver.Element.get_maxez1 (   self,
  triggerPin,
  outputPin 
)
The maxez1 command queries a Maxbotix MaxSonar-EZ1 sonar
    sensor connected to the General Purpose I/O lines, triggerPin, and
    outputPin, for a distance, and returns it in Centimeters. NOTE: MAKE
    SURE there's nothing directly in front of the MaxSonar-EZ1 upon
    power up, otherwise it wont range correctly for object less than 6
    inches away! The sensor reading defaults to use English units
    (inches). The sensor distance resolution is integer based. Also, the
    maxsonar trigger pin is RX, and the echo pin is PW.

Definition at line 541 of file element_driver.py.

def src.element_driver.Element.get_MaxEZ1 (   self,
  trigger_pin,
  output_pin,
  cached = False 
)
Get the distance reading from a MaxEZ1 sonarl sensor on the given trigger and output pins.

Definition at line 969 of file element_driver.py.

def src.element_driver.Element.get_PhidgetsCurrent (   self,
  pin,
  cached = False,
  model = 20,
  ac_dc = "dc" 
)

Definition at line 1030 of file element_driver.py.

def src.element_driver.Element.get_PhidgetsTemperature (   self,
  pin,
  cached = False,
  units = "F" 
)
Get the temperature from a Phidgets Temperature sensor on an analog sensor port and return
    the reading in either Farhenheit or Celcius depending on the units argument.

Definition at line 998 of file element_driver.py.

def src.element_driver.Element.get_PhidgetsVoltage (   self,
  pin,
  cached = False 
)
Get the voltage from a Phidgets Voltage sensor on an analog sensor port.

Definition at line 1018 of file element_driver.py.

Once a digo command is issued, an internal state variable within the
    firmware is set to 1, and it stays in that state until the algorithm has
    completed. Upon completion, the state is set to 0. The pids
    command simply returns the value of the internal variable to
    determine if the algorithms is currently busy, or if it has finished, thus
    allowing subsequent digo commands to be issued w/o clobbering
    previous ones.

Definition at line 635 of file element_driver.py.

def src.element_driver.Element.get_Ping (   self,
  pin,
  cached = False 
)
Get the distance reading from a Ping sonarl sensor on the given GPIO pin.

Definition at line 960 of file element_driver.py.

The get_units returns the current units used for sensor
    readings. Values are 0 for metric mode, 1 for English mode, and 2 for
    raw mode.  In raw mode, srf04, srf05, pping, and maxez1 return
    reading in units of 0.4us. srf08 and srf10 return readings of 1us..

Definition at line 463 of file element_driver.py.

Get the PIDL parameter values.

Definition at line 558 of file element_driver.py.

Definition at line 939 of file element_driver.py.

Definition at line 945 of file element_driver.py.

def src.element_driver.Element.i2c (   self,
  op,
  addr,
  data = None 
)
Usage1: i2c(op, addr)
    Usage2: i2c(op, addr, data)
    The flexible i2c command allows you to execute a generic i2c read, or
    write command to the specified device at address addr. Depending on
    whether you issue a read or write, additional parameters vary.

Definition at line 902 of file element_driver.py.

Definition at line 162 of file element_driver.py.

def src.element_driver.Element.line (   self,
  addr,
  newaddr = None,
  seven = False 
)
Queries a RoboticsConnection Line Following Sensor at address addr.
    If the -a option is specified, then the address of the module will be
    changed to the new address associated w the -a switch.
    If the optional 7 is appended to the end of the line command, e.g.
    line7, then two additional values will be returned from those Line
    Following Sensors (manufactured after 11/1/07) which have additional
    sensor inputs on the sides of the board. This can be used to read
    additional Single Line Following sensors, or read any type of on/off
    momentary switch, such those used for bumpers.

Definition at line 887 of file element_driver.py.

def src.element_driver.Element.mogo (   self,
  id,
  vel 
)
Usage 1: mogo(id, vel)
    Usage 2: mogo([id1, id2], [vel1, vel2])
    The mogo command sets motor speed using one or more complex
    parameters containing a <motorId:spd> value pair.
    The motorId can be either 1 or 2, which corresponds to the Motor
    Terminal port.
    The vel value specifies the motor velocity, and it's range depends on
    your VPID settings. See the VPID parameters section below to
    determine your MAX velocity. A positive value rotates the motors in
    one direction, which a negative value rotates the motors in the
    opposite direction.
    You will have to determine which direction is positive for your motors,
    and connect the motors wires to the terminals on the Element board
    in the appropriate configuration.

Definition at line 1063 of file element_driver.py.

def src.element_driver.Element.mogo_m_per_s (   self,
  id,
  vel 
)
Set the motor speeds in meters per second.

Definition at line 1088 of file element_driver.py.

Open the serial port.

Definition at line 169 of file element_driver.py.

def src.element_driver.Element.pping (   self,
  pinId 
)
The srf05/Ping command queries an SRF05/Ping sonar sensor
    connected to the General Purpose I/O line pinId for a distance,
    and returns it in the units configured (default is English - inches).
    If the Element units are configured (using cfg units) for raw mode,
    pping and srf05 return readings in units of 0.4us, and the max
    distance returned is 65000 (out of range). When configured for
    English units, max distance returned is 100 inches (out of range), and
    when configured for Metric units, max distance returned is 255 (out of
    range). Sonar distance resolution is integer based.

Definition at line 794 of file element_driver.py.

def src.element_driver.Element.pwm (   self,
  id,
  vel,
  rate = None 
)
Usage 1: pwm(id, vel)
    Usage 2: pwm(id, vel, rate=r)
    Usage 3: pwm([id1, id2], [vel1, vel2]) 
    Usage 4: pwm([id1, id2], [vel1, vel2], rate=r)   
    The pwm command sets the Pulse Width Modulation value for
    Motor 1 & Motor 2. Each complex parameter is a motor
    <motorId:pwm value> pair, where the motor id can be 1 or 2, and the
    pwm value can be -100 to 100. Each complex parameter pair is
    separated by one or more spaces.
    The optional rate parameter allows the
    motor(s) speed(s)s to be ramped up or down to the specified speed
    from the current motor speed.

Definition at line 646 of file element_driver.py.

def src.element_driver.Element.recv (   self,
  timeout = 0.5 
)

Definition at line 185 of file element_driver.py.

This command should not be used on its own: it is called by the execute commands
    below in a thread safe manner.

Definition at line 205 of file element_driver.py.

This command should not be used on its own: it is called by the execute commands
    below in a thread safe manner.

Definition at line 222 of file element_driver.py.

This command should not be used on its own: it is called by the execute commands
    below in a thread safe manner.

Definition at line 212 of file element_driver.py.

The reset command resets the Element board and reboots it. You
    will see the Element welcome screen appear after a short delay.
    Once the welcome string appears, the Element is ready to accept
    commands.

Definition at line 396 of file element_driver.py.

Restores the factory default settings, and resets the board. NOTE:
    This will erase any configurations you have saved to EEPROM,
    including VPID, DPID, and baud rate settings.

Definition at line 880 of file element_driver.py.

def src.element_driver.Element.rotate (   self,
  angle,
  vel 
)
Rotate the robot through 'angle' degrees or radians at speed 'vel'.  Use the ROS convention for right handed
    coordinate systems with the z-axis pointing up so that a positive angle is counterclockwise.
    Use negative angles to rotate clockwise.

Definition at line 1117 of file element_driver.py.

def src.element_driver.Element.rotate_at_speed (   self,
  vel 
)
Rotate the robot continously at speed 'vel' radians or degrees per second.  Use the ROS convention for right handed
    coordinate systems with the z-axis pointing up so that a positive speed is counterclockwise.
    Use negative speeds to rotate clockwise.

Definition at line 1139 of file element_driver.py.

def src.element_driver.Element.send (   self,
  cmd 
)
This command should not be used on its own: it is called by the execute commands
    below in a thread safe manner.

Definition at line 179 of file element_driver.py.

def src.element_driver.Element.sensor (   self,
  id 
)
Usage 1: reading = sensor(id)
    Usage 2: readings = sensor([id1, id2, ..., idN])
    The sensor command returns the raw A/D (8 bit) reading from the
    analog sensor ports 0-5. Multiple values can be read at a time by
    specifying multiple pins as a list. Pin 5 is 1/3 of
    the voltage of the power supply for the Element. To calculate the
    battery voltage, simply multiply the value returned by Sensor 5 by 
    15/1024.

Definition at line 696 of file element_driver.py.

def src.element_driver.Element.servo (   self,
  id,
  pos 
)
Usage 1: servo(id, pos)
    Usage 2: servo([id1, id2, ... , idN], [pos1, pos2, ..., posN)     
    The servo command sets a servo connected to General Purpose I/O
    port the specified position. The value of the position can range from 
    -99 to 100, where 0 is the center position. Setting the position to -100
    will disable the servo, allowing it to turn freely by hand.
    Each parameter is a <servo id:position> pair, where the servo
    id can be 1,2,3,4,5, or 6.

Definition at line 742 of file element_driver.py.

def src.element_driver.Element.set_baud (   self,
  baudrate 
)
The set_baud command configures the serial baud rate on the
    Element. Values can be 0=2400, 1=4800, 2=9600, 3=19200,
    4=57600, or 5=115200. You can also type in the actual baud rate
    string as well (e.g. 19200). The default baud rate used to
    communicate with the Element is 19200. The cfg baud command
    without a parameter returns the value currently stored in EEPROM.

Definition at line 453 of file element_driver.py.

def src.element_driver.Element.set_dpid (   self,
  prop,
  integ,
  deriv,
  accel,
  dead_band 
)
The set_dpid command gets/sets the PIDA (Proportional, Integral,
    Derivative, and Acceleration) parameters for the distance PID control
    on the Element. If the PIDA parameters are absent, the PIDA
    values are returned. Otherwise the PIDA parameters are parsed, and
    saved (in eeprom).  

Definition at line 618 of file element_driver.py.

def src.element_driver.Element.set_encoder (   self,
  encoder_type 
)
The set_encoder command configures the internal encoder type to be either
    single (0) or quadrature (1) type. This information is saved in the
    EEPROM, so that the configuration will be retained after a reboot. If
    you are using a quadrature encoder (dual channels), and the Element
    is configured for single encoder operation, then the second quadrature
    channel will be ignored. Thus make sure the correct encoder type is
    configured according to your setup. The cfg enc command without a
    parameter returns the value currently stored in EEPROM.

Definition at line 436 of file element_driver.py.

Definition at line 954 of file element_driver.py.

def src.element_driver.Element.set_gear_reduction (   self,
  ratio 
)

Definition at line 948 of file element_driver.py.

def src.element_driver.Element.set_io (   self,
  id,
  val 
)
Usage 1: set_io(id, val)
    Usage 2: set_io([id1, id2, ... , idN], [val1, val2, ..., valN)  
    The set_io command sets the specified General Purpose I/O line pinId
    (range 0-12) on the Element to the specified value. Each complex
    parameter is a <pinId:value> pair, where the valid range of pinId is 0
    thru 12, and value can be 0 or 1 which corresponds to 0v or +5V
    respectively.  Also I/O lines 4,5,6,7, 8 and 9 cannot be used if you
    have servos connected to them. Pin 10, 11, and 12 correspond to the
    internal h-bridge enable, SCL, and SDA respectively.

Definition at line 526 of file element_driver.py.

def src.element_driver.Element.set_rpid (   self,
  r 
)
The rpid command sets the default PID params known to work with
    either the Stinger or Traxster Robotic Kits in the firmware. This makes
    it quick and easy to set up the PID params for both robots.

Definition at line 628 of file element_driver.py.

def src.element_driver.Element.set_units (   self,
  units 
)
The set_units command sets the internal units used for sensor
    readings. Values are 0 for metric mode, 1 for English mode, and 2 for
    raw mode.  In raw mode, srf04, srf05, pping, and maxez1 return
    reading in units of 0.4us. srf08 and srf10 return readings of 1us.
    The cfg units command without a parameter returns the value

Definition at line 471 of file element_driver.py.

def src.element_driver.Element.set_vpid (   self,
  prop,
  integ,
  deriv,
  loop 
)
The set_vpid command sets the PIDL (Proportional, Integral,
    Derivative, and Loop) parameters for the Velocity PID control on the
    Element. The PIDL parameters are parsed, and saved (in
    eeprom). For more information on PIDL control, see the PIDL
    configuration section below.  By default the Element VPID
    parameters are configured to work with our Traxster Robot Kit

Definition at line 564 of file element_driver.py.

def src.element_driver.Element.set_wheel_diameter (   self,
  diameter 
)

Definition at line 936 of file element_driver.py.

def src.element_driver.Element.set_wheel_track (   self,
  track 
)

Definition at line 942 of file element_driver.py.

def src.element_driver.Element.setup_base_controller (   self,
  pid_params 
)

Definition at line 117 of file element_driver.py.

def src.element_driver.Element.sp03 (   self,
  msg,
  i2c_addr 
)
Usage1: sp03(msg)
    Usage2: sp03(msg, ic2_addr)
    The sp03 command instructs a Devantech SP03 Speech Synthesizer to
    speak the appropriate phrase. If a character representing a number in
    the range of 0 to 30, then the SP03 will speak previously programmed
    canned phrases. If a phrase is sent, then it will speak the phrase. An
    optional I2C address can also be specified. Otherwise, the default I2C
    address of 0xC4.
 

Definition at line 756 of file element_driver.py.

def src.element_driver.Element.srf04 (   self,
  triggerPin,
  outputPin 
)
The srf04 command queries an SRF04 sonar sensor
    connected to the General Purpose I/O lines triggerPin and outputPin,
    for a distance and returns it in the units configured (default is English
    inches). If the Element units are configured (using cfg units) for raw mode,
    srf04 returns readings in units of 0.4us, and the max distance returned
    is 65000 (out of range). When configured for English units, max
    distance returned is 100 inches (out of range), and when configured
    for Metric units, max distance returned is 255 (out of range). NOTE:
    Sonar distance resolution is integer based.

Definition at line 768 of file element_driver.py.

def src.element_driver.Element.srf05 (   self,
  pinId 
)
The srf05/Ping command queries an SRF05/Ping sonar sensor
    connected to the General Purpose I/O line pinId for a distance,
    and returns it in the units configured (default is English - inches).
    If the Element units are configured (using cfg units) for raw mode,
    pping and srf05 return readings in units of 0.4us, and the max
    distance returned is 65000 (out of range). When configured for
    English units, max distance returned is 100 inches (out of range), and
    when configured for Metric units, max distance returned is 255 (out of
    range). Sonar distance resolution is integer based.

Definition at line 781 of file element_driver.py.

def src.element_driver.Element.srf08 (   self,
  i2c_addr = None 
)
Usage1: srf08()
    Usage2: srf08(ic2_addr)
    The srf08/srf10 command queries a Devantech SRF08/SRF10 sonar
    sensor at address i2c_addr for a distance reading in the units
    configured (default is English - inches).  The i2cAddr parameter is
    optional, and defaults to 0xE0 for both sensors. The i2c address can
    be changed for any i2c module using the i2cp command.  Sonar
    distance resolution is integer based.  If the Element units are 
    configured (using cfg units) for raw mode, srf08 and srf10 return
    readings in units of 1us.
 

Definition at line 809 of file element_driver.py.

def src.element_driver.Element.srf10 (   self,
  i2caddr = None 
)
Usage1: srf10()
    Usage2: srf10(ic2_addr)
    The srf08/srf10 command queries a Devantech SRF08/SRF10 sonar
    sensor at address ic2_addr for a distance reading in the units
    configured (default is English - inches). The ic2_addr parameter is
    optional, and defaults to 0xE0 for both sensors. The i2c address can
    be changed for any i2c module using the i2cp command. Sonar
    distance resolution is integer based. If the Element units are
    configured (using cfg units) for raw mode, srf08 and srf10 return
    readings in units of 1us.
 

Definition at line 823 of file element_driver.py.

def src.element_driver.Element.step (   self,
  dir,
  speed,
  steps 
)
The step command is used to step a bipolar stepper motor in direction
    dir, at the specified speed, for the specified number of steps.
    The dir parameter specifies a CW or CCW rotational direction, and its
    value can be either 0 (CCW) or 1(CW). Your specific direction is based
    on the way that you have your bipolar motor connected to the
    Element.  The speed parameter can be a value from 0 to 100.
    The steps parameter specifies the maximum number of steps to take.
    A value of 0 means step infinitely. Internally, this number is stored in
    an unsigned 32 bit variable, so the user can specify a larger number of
    steps.

Definition at line 668 of file element_driver.py.

Stop both motors.

Definition at line 553 of file element_driver.py.

def src.element_driver.Element.sweep (   self,
  id,
  speed,
  steps 
)
The sweep command is used to sweep a bipolar motor, for step
    number of steps, at speed (0-100), thus providing a sweeping motion.
    The initial rotational direction of sweep is in the CW direction.
    Upon initial receipt of the command, the firmware will sweep the
    motor for 1/2 of the number of steps specified, starting in a CW
    direction. Once that number of steps has occurred, the sweep
    direction will change, and subsequent sweeps will rotate for the full
    amount of steps.     Thus, the starting point for the motor is in the
    middle of each sweep. You may stop the sweep by either issuing a sweep 
    command w a 0 speed, or simply sending a stop command.

Definition at line 682 of file element_driver.py.

def src.element_driver.Element.tpa81 (   self,
  i2caddr = None 
)
Usage1: tpa81()
    Usage2: tpa81(ic2_addr) 
    The tpa81 command queries a Devantech TPA81 thermopile sensor for
    temperature values. It returns 8 temperature values.

Definition at line 837 of file element_driver.py.

def src.element_driver.Element.travel_at_speed (   self,
  id,
  vel 
)
Move forward or backward at speed 'vel' in meters per second.  Use negative speeds
    to move backward.  This is just an alias for mogo_m_per_s so see that function for
    more details.

Definition at line 1110 of file element_driver.py.

def src.element_driver.Element.travel_distance (   self,
  dist,
  vel 
)
Move forward or backward 'dist' (inches or meters depending on units) at speed 'vel'.  Use negative distances
    to move backward.

Definition at line 1049 of file element_driver.py.

def src.element_driver.Element.twist (   self,
  twist 
)

Definition at line 1167 of file element_driver.py.

def src.element_driver.Element.update_analog_cache (   self,
  id,
  value 
)

Definition at line 381 of file element_driver.py.

def src.element_driver.Element.update_digital_cache (   self,
  id,
  value 
)

Definition at line 377 of file element_driver.py.

The vel command returns the left and right wheel velocities. The
    velocity returned is based on the PIDL parameter configuration.  The
    units are encoder ticks per PID loop interval.

Definition at line 845 of file element_driver.py.

Return the left and right wheel velocities in feet per second.

Definition at line 873 of file element_driver.py.

Return the left and right wheel velocities in meters per second.

Definition at line 852 of file element_driver.py.

Return the left and right wheel velocities in miles per hour.

Definition at line 866 of file element_driver.py.

def src.element_driver.Element.voltage (   self,
  cached = False 
)

Definition at line 917 of file element_driver.py.


Member Data Documentation

Definition at line 72 of file element_driver.py.

Definition at line 70 of file element_driver.py.

Definition at line 72 of file element_driver.py.

Definition at line 72 of file element_driver.py.

Definition at line 67 of file element_driver.py.

Definition at line 72 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 72 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 72 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 41 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 72 of file element_driver.py.

Definition at line 38 of file element_driver.py.

Definition at line 39 of file element_driver.py.

Definition at line 43 of file element_driver.py.

Definition at line 72 of file element_driver.py.

Definition at line 72 of file element_driver.py.

Definition at line 1000 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 72 of file element_driver.py.

Definition at line 72 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 117 of file element_driver.py.

Definition at line 72 of file element_driver.py.


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


element
Author(s): Patrick Goebel
autogenerated on Sun Oct 5 2014 23:44:54