Public Member Functions | Public Attributes | Private Member Functions
dynamixel_driver.dynamixel_io.DynamixelIO Class Reference

List of all members.

Public Member Functions

def __del__
def __init__
def close
def exception_on_error
def get_angle_limits
def get_current
def get_drive_mode
def get_feedback
def get_firmware_version
def get_led
def get_model_number
 Servo status access functions #.
def get_position
def get_return_delay_time
def get_speed
def get_voltage
def get_voltage_limits
def ping
def read
def set_acceleration
def set_angle_limit_ccw
def set_angle_limit_cw
def set_angle_limits
def set_baud_rate
def set_compliance_margin_ccw
def set_compliance_margin_cw
def set_compliance_margins
def set_compliance_slope_ccw
def set_compliance_slope_cw
def set_compliance_slopes
def set_d_gain
def set_drive_mode
def set_goal_torque
def set_i_gain
def set_id
 These function modify EEPROM data which persists after power cycle #.
def set_led
def set_multi_compliance_margin_ccw
def set_multi_compliance_margin_cw
def set_multi_compliance_margins
def set_multi_compliance_slope_ccw
def set_multi_compliance_slope_cw
def set_multi_compliance_slopes
def set_multi_position
def set_multi_position_and_speed
def set_multi_punch
def set_multi_speed
def set_multi_torque_enabled
 These functions can send multiple commands to multiple servos # These commands are used in ROS wrapper as they don't send a # response packet, ROS wrapper gets motor states at a set rate #.
def set_multi_torque_limit
def set_p_gain
def set_position
def set_position_and_speed
def set_punch
def set_return_delay_time
def set_speed
def set_torque_enabled
 These functions can send a single command to a single servo #.
def set_torque_limit
def set_voltage_limit_max
def set_voltage_limit_min
def set_voltage_limits
def sync_write
def test_bit
def write

Public Attributes

 port_name
 readback_echo
 ser
 serial_mutex

Private Member Functions

def __read_response
def __write_serial

Detailed Description

Provides low level IO with the Dynamixel servos through pyserial. Has the
ability to write instruction packets, request and read register value
packets, send and receive a response to a ping packet, and send a SYNC WRITE
multi-servo instruction packet.

Definition at line 55 of file dynamixel_io.py.


Constructor & Destructor Documentation

def dynamixel_driver.dynamixel_io.DynamixelIO.__init__ (   self,
  port,
  baudrate,
  readback_echo = False 
)
Constructor takes serial port and baudrate as arguments. 

Definition at line 62 of file dynamixel_io.py.

Destructor calls DynamixelIO.close 

Definition at line 75 of file dynamixel_io.py.


Member Function Documentation

def dynamixel_driver.dynamixel_io.DynamixelIO.__read_response (   self,
  servo_id 
) [private]

Definition at line 95 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.__write_serial (   self,
  data 
) [private]

Definition at line 88 of file dynamixel_io.py.

Be nice, close the serial port.

Definition at line 79 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.exception_on_error (   self,
  error_code,
  servo_id,
  command_failed 
)

Definition at line 978 of file dynamixel_io.py.

Returns the min and max angle limits from the specified servo.

Definition at line 841 of file dynamixel_io.py.

Reads the servo's current consumption (if supported by model) 

Definition at line 902 of file dynamixel_io.py.

Reads the servo's drive mode. 

Definition at line 856 of file dynamixel_io.py.

Returns the id, goal, position, error, speed, load, voltage, temperature
and moving values from the specified servo.

Definition at line 926 of file dynamixel_io.py.

Reads the servo's firmware version. 

Definition at line 827 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.get_led (   self,
  servo_id 
)
Get status of the LED. Boolean return values:
    True - LED is on,
    False - LED is off.

Definition at line 964 of file dynamixel_io.py.

Servo status access functions #.

Reads the servo's model number (e.g. 12 for AX-12+). 

Definition at line 820 of file dynamixel_io.py.

Reads the servo's position value from its registers. 

Definition at line 877 of file dynamixel_io.py.

Reads the servo's return delay time. 

Definition at line 834 of file dynamixel_io.py.

Reads the servo's speed value from its registers. 

Definition at line 885 of file dynamixel_io.py.

Reads the servo's voltage. 

Definition at line 895 of file dynamixel_io.py.

Returns the min and max voltage limits from the specified servo.

Definition at line 863 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.ping (   self,
  servo_id 
)
Ping the servo with "servo_id". This causes the servo to return a
"status packet". This can tell us if the servo is attached and powered,
and if so, if there are any errors.

Definition at line 218 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.read (   self,
  servo_id,
  address,
  size 
)
Read "size" bytes of data from servo with "servo_id" starting at the
register with "address". "address" is an integer between 0 and 57. It is
recommended to use the constants in module dynamixel_const for readability.

To read the position from servo with id 1, the method should be called
like:
    read(1, DXL_GOAL_POSITION_L, 2)

Definition at line 112 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_acceleration (   self,
  servo_id,
  acceleration 
)
Sets the acceleration. The unit is 8.583 Degree / sec^2.
0 - acceleration control disabled, 1-254 - valid range for acceleration.

Definition at line 510 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_angle_limit_ccw (   self,
  servo_id,
  angle_ccw 
)
Set the max (CCW) angle of rotation limit.

Definition at line 304 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_angle_limit_cw (   self,
  servo_id,
  angle_cw 
)
Set the min (CW) angle of rotation limit.

Definition at line 292 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_angle_limits (   self,
  servo_id,
  min_angle,
  max_angle 
)
Set the min (CW) and max (CCW) angle of rotation limits.

Definition at line 316 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_baud_rate (   self,
  servo_id,
  baud_rate 
)
Sets servo communication speed. The range from 0 to 254.

Definition at line 272 of file dynamixel_io.py.

The error between goal position and present position in CCW direction.
The range of the value is 0 to 255, and the unit is the same as Goal Position.
The greater the value, the more difference occurs.

Definition at line 414 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_compliance_margin_cw (   self,
  servo_id,
  margin 
)
The error between goal position and present position in CW direction.
The range of the value is 0 to 255, and the unit is the same as Goal Position.
The greater the value, the more difference occurs.

Definition at line 403 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_compliance_margins (   self,
  servo_id,
  margin_cw,
  margin_ccw 
)
The error between goal position and present position in CCW direction.
The range of the value is 0 to 255, and the unit is the same as Goal Position.
The greater the value, the more difference occurs.

Definition at line 425 of file dynamixel_io.py.

Sets the level of Torque near the goal position in CCW direction.
Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained.

Definition at line 446 of file dynamixel_io.py.

Sets the level of Torque near the goal position in CW direction.
Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained.

Definition at line 436 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_compliance_slopes (   self,
  servo_id,
  slope_cw,
  slope_ccw 
)
Sets the level of Torque near the goal position in CW/CCW direction.
Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained.

Definition at line 456 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_d_gain (   self,
  servo_id,
  d_gain 
)
Sets the value of derivative action of PID controller.
Gain value is in range 0 to 254.

Definition at line 466 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_drive_mode (   self,
  servo_id,
  is_slave = False,
  is_reverse = False 
)
Sets the drive mode for EX-106 motors

Definition at line 331 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_goal_torque (   self,
  servo_id,
  torque 
)
Set the servo to torque control mode (similar to wheel mode, but controlling the torque)
Valid values are from -1023 to 1023.
Anything outside this range or 'None' disables torque control.

Definition at line 575 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_i_gain (   self,
  servo_id,
  i_gain 
)
Sets the value of integral action of PID controller.
Gain value is in range 0 to 254.

Definition at line 476 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_id (   self,
  old_id,
  new_id 
)

These function modify EEPROM data which persists after power cycle #.

Sets a new unique number to identify a motor. The range from 1 to 253
(0xFD) can be used.

Definition at line 262 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_led (   self,
  servo_id,
  led_state 
)
Turn the LED of servo motor on/off.
Possible boolean state values:
    True - turn the LED on,
    False - turn the LED off.

Definition at line 625 of file dynamixel_io.py.

Set different CCW compliance margin for multiple servos.
Should be called as such:
set_multi_compliance_margin_ccw( ( (id1, margin1), (id2, margin2), (id3, margin3) ) )

Definition at line 662 of file dynamixel_io.py.

Set different CW compliance margin for multiple servos.
Should be called as such:
set_multi_compliance_margin_cw( ( (id1, margin1), (id2, margin2), (id3, margin3) ) )

Definition at line 654 of file dynamixel_io.py.

Set different CW and CCW compliance margins for multiple servos.
Should be called as such:
set_multi_compliance_margins( ( (id1, cw_margin1, ccw_margin1), (id2, cw_margin2, ccw_margin2) ) )

Definition at line 670 of file dynamixel_io.py.

Set different CCW compliance slope for multiple servos.
Should be called as such:
set_multi_compliance_slope_ccw( ( (id1, slope1), (id2, slope2), (id3, slope3) ) )

Definition at line 686 of file dynamixel_io.py.

Set different CW compliance slope for multiple servos.
Should be called as such:
set_multi_compliance_slope_cw( ( (id1, slope1), (id2, slope2), (id3, slope3) ) )

Definition at line 678 of file dynamixel_io.py.

Set different CW and CCW compliance slopes for multiple servos.
Should be called as such:
set_multi_compliance_slopes( ( (id1, cw_slope1, ccw_slope1), (id2, cw_slope2, ccw_slope2) ) )

Definition at line 694 of file dynamixel_io.py.

Set different positions for multiple servos.
Should be called as such:
set_multi_position( ( (id1, position1), (id2, position2), (id3, position3) ) )

Definition at line 721 of file dynamixel_io.py.

Set different positions and speeds for multiple servos.
Should be called as such:
set_multi_position_and_speed( ( (id1, position1, speed1), (id2, position2, speed2), (id3, position3, speed3) ) )

Definition at line 785 of file dynamixel_io.py.

Set different punch values for multiple servos.
NOTE: according to documentation, currently this value is not being used.
Should be called as such:
set_multi_punch( ( (id1, punch1), (id2, punch2), (id3, punch3) ) )

Definition at line 702 of file dynamixel_io.py.

Set different speeds for multiple servos.
Should be called as such:
set_multi_speed( ( (id1, speed1), (id2, speed2), (id3, speed3) ) )

Definition at line 741 of file dynamixel_io.py.

These functions can send multiple commands to multiple servos # These commands are used in ROS wrapper as they don't send a # response packet, ROS wrapper gets motor states at a set rate #.

Method to set multiple servos torque enabled.
Should be called as such:
set_multi_servos_to_torque_enabled( (id1, True), (id2, True), (id3, True) )

Definition at line 645 of file dynamixel_io.py.

Set different torque limits for multiple servos.
Should be called as such:
set_multi_torque_limit( ( (id1, torque1), (id2, torque2), (id3, torque3) ) )

Definition at line 767 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_p_gain (   self,
  servo_id,
  p_gain 
)
Sets the value of proportional action of PID controller.
Gain value is in range 0 to 254.

Definition at line 486 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_position (   self,
  servo_id,
  position 
)
Set the servo with servo_id to the specified goal position.
Position value must be positive.

Definition at line 528 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_position_and_speed (   self,
  servo_id,
  position,
  speed 
)
Set the servo with servo_id to specified position and speed.
Speed can be negative only if the dynamixel is in "freespin" mode.

Definition at line 603 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_punch (   self,
  servo_id,
  punch 
)
Sets the limit value of torque being reduced when the output torque is
decreased in the Compliance Slope area. In other words, it is the mimimum
torque. The initial value is 32 (0x20) and can be extended up to 1023
(0x3FF). (Refer to Compliance margin & Slope)

Definition at line 496 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_return_delay_time (   self,
  servo_id,
  delay 
)
Sets the delay time from the transmission of Instruction Packet until
the return of Status Packet. 0 to 254 (0xFE) can be used, and the delay
time per data value is 2 usec.

Definition at line 281 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_speed (   self,
  servo_id,
  speed 
)
Set the servo with servo_id to the specified goal speed.
Speed can be negative only if the dynamixel is in "freespin" mode.

Definition at line 541 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_torque_enabled (   self,
  servo_id,
  enabled 
)

These functions can send a single command to a single servo #.

Sets the value of the torque enabled register to 1 or 0. When the
torque is disabled the servo can be moved manually while the motor is
still powered.

Definition at line 392 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_torque_limit (   self,
  servo_id,
  torque 
)
Sets the value of the maximum torque limit for servo with id servo_id.
Valid values are 0 to 1023 (0x3FF), and the unit is about 0.1%.
For example, if the value is 512 only 50% of the maximum torque will be used.
If the power is turned on, the value of Max Torque (Address 14, 15) is used as the initial value.

Definition at line 560 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_voltage_limit_max (   self,
  servo_id,
  max_voltage 
)
Set the maximum voltage limit.
NOTE: the absolute min is 25v

Definition at line 356 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_voltage_limit_min (   self,
  servo_id,
  min_voltage 
)
Set the minimum voltage limit.
NOTE: the absolute min is 5v

Definition at line 342 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.set_voltage_limits (   self,
  servo_id,
  min_voltage,
  max_voltage 
)
Set the min and max voltage limits.
NOTE: the absolute min is 5v and the absolute max is 25v

Definition at line 370 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.sync_write (   self,
  address,
  data 
)
Use Broadcast message to send multiple servos instructions at the
same time. No "status packet" will be returned from any servos.
"address" is an integer between 0 and 49. It is recommended to use the
constants in module dynamixel_const for readability. "data" is a tuple of
tuples. Each tuple in "data" must contain the servo id followed by the
data that should be written from the starting address. The amount of
data can be as long as needed.

To set servo with id 1 to position 276 and servo with id 2 to position
550, the method should be called like:
    sync_write(DXL_GOAL_POSITION_L, ( (1, 20, 1), (2 ,38, 2) ))

Definition at line 185 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.test_bit (   self,
  number,
  offset 
)

Definition at line 253 of file dynamixel_io.py.

def dynamixel_driver.dynamixel_io.DynamixelIO.write (   self,
  servo_id,
  address,
  data 
)
Write the values from the "data" list to the servo with "servo_id"
starting with data[0] at "address", continuing through data[n-1] at
"address" + (n-1), where n = len(data). "address" is an integer between
0 and 49. It is recommended to use the constants in module dynamixel_const
for readability. "data" is a list/tuple of integers.

To set servo with id 1 to position 276, the method should be called
like:
    write(1, DXL_GOAL_POSITION_L, (20, 1))

Definition at line 146 of file dynamixel_io.py.


Member Data Documentation

Definition at line 62 of file dynamixel_io.py.

Definition at line 62 of file dynamixel_io.py.

Definition at line 62 of file dynamixel_io.py.

Definition at line 62 of file dynamixel_io.py.


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


dynamixel_driver
Author(s): Antons Rebguns, Cody Jorgensen
autogenerated on Wed Aug 26 2015 11:24:35