Class that manages multiple servos on a single Dynamixel Device
Definition at line 198 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.__init__ | ( | self, | |
dev = '/dev/ttyUSB0' , |
|||
baudrate = '57600' , |
|||
ids = None |
|||
) |
Accepts device file, baudrate, and a list of id numbers for servos (if known).
Definition at line 201 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.__encoder_to_bytes | ( | self, | |
id, | |||
n | |||
) | [private] |
convert encoder value to hi, lo bytes
Definition at line 731 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain._compliance_slope_to_step | ( | self, | |
val | |||
) | [private] |
Definition at line 507 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain._compliance_step_to_slope | ( | self, | |
step | |||
) | [private] |
Definition at line 525 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain._determine_series | ( | self, | |
code | |||
) | [private] |
Determine the series from the model number of servo with id.
Definition at line 250 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain._find_servos | ( | self, | |
ids = None |
|||
) | [private] |
Finds all servo IDs on the USB2Dynamixel, or check given ids
Definition at line 216 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain._id_on_device | ( | self, | |
id | |||
) | [private] |
check for a specific id on the dynamixel device. pings servo and reads id.
Definition at line 239 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.disable_cont_turn | ( | self, | |
id | |||
) |
Resets CCW angle limits to defaults to allow commands through 'move_angle' again.
Definition at line 360 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.disable_torque | ( | self, | |
id | |||
) |
Disable torque production by interrupting power to the motor.
Definition at line 443 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.disable_torque_control | ( | self, | |
id | |||
) |
Disable torque control mode. Goal position and moving speed will be used instead.
Definition at line 795 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.enable_cont_turn | ( | self, | |
id | |||
) |
Sets angle limits to zero, allowing continuous turning (good for wheels). After calling this method, simply use 'set_angvel' to command rotation. This rotation is proportional to torque according to Robotis documentation.
Definition at line 353 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.enable_torque | ( | self, | |
id | |||
) |
Enable torque production by impressing power to the motor.
Definition at line 438 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.enable_torque_control | ( | self, | |
id | |||
) |
Enable torque control mode. Goal position and moving speed will be ignored.
Definition at line 790 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.is_cont_turn_enabled | ( | self, | |
id | |||
) |
Return whether continuous turn is enabled based on the joint angle limits.
Definition at line 348 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.is_eeprom_locked | ( | self, | |
id | |||
) |
Return True if the EEPROM of servo at id is locked, False if not.
Definition at line 753 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.is_led_on | ( | self, | |
id | |||
) |
Return True if LED is ON, False if LED is off.
Definition at line 466 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.is_moving | ( | self, | |
id | |||
) |
Returns True if servo (id) is moving, False otherwise.
Definition at line 747 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.is_torque_control_enabled | ( | self, | |
id | |||
) |
Return True if servo at id is currently set for torque control, False otherwise.
Definition at line 785 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.is_torque_enabled | ( | self, | |
id | |||
) |
Return True if sending power to motor, False otherwise.
Definition at line 432 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.lock_eeprom | ( | self, | |
id | |||
) |
Lock the EEPROM of servo at ID (will prevent changes to EEPROM bits). Lock can only be reset by power-cycling the servo.
Definition at line 758 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.move_angle | ( | self, | |
id, | |||
ang, | |||
angvel = None , |
|||
blocking = False |
|||
) |
move servo with id to angle (radians) with velocity (rad/s)
Definition at line 682 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.move_angles_sync | ( | self, | |
ids, | |||
angs, | |||
angvels = None |
|||
) |
move servos with id's to angles with angvels using a single sync_write. clips angles to allowed range, and limits angvel to max allowed.
Definition at line 699 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.move_to_encoder | ( | self, | |
id, | |||
n | |||
) |
move to encoder position n
Definition at line 725 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_ang_angvel | ( | self, | |
id | |||
) |
returns the angular position and angular velocity from a single read
Definition at line 660 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_angle | ( | self, | |
id | |||
) |
returns the angle (radians) of servo at id.
Definition at line 632 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_angle_limits | ( | self, | |
id | |||
) |
Read the angle limits (in radians) set on the servo. Returns [cw_limit, ccw_limit]
Definition at line 338 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_angles | ( | self, | |
ids = None |
|||
) |
return a list of current joint angles for servos with given ids
Definition at line 637 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_angs_angvels | ( | self, | |
ids = None |
|||
) |
return lists of current angular positions and velocities for given ids
Definition at line 669 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_angvel | ( | self, | |
id | |||
) |
returns the angular velocity (rad/s) of servo at id.
Definition at line 645 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_angvels | ( | self, | |
ids = None |
|||
) |
return a list of current angular velocities for servos with given ids
Definition at line 652 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_baudrate | ( | self, | |
id | |||
) |
Read the currently set baudrate digit of servo with ID.
Definition at line 295 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_compliance_margins | ( | self, | |
id | |||
) |
Read the compliance margin (deadband around goal position) of servo with id. Returns [CW, CCW] angular deadband in radians (always positive).
Definition at line 477 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_compliance_slopes | ( | self, | |
id | |||
) |
Read the CW and CCW compliance slopes as steps from 1-7 (1=stiffer, 7=more flexible').
Definition at line 538 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_current | ( | self, | |
id | |||
) |
Read the current (in Amps) currently in the motor.
Definition at line 778 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_encoder | ( | self, | |
id | |||
) |
returns position in encoder ticks of servo at id.
Definition at line 625 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_firmware_version | ( | self, | |
id | |||
) |
Read the firmware version on the servo at id.
Definition at line 274 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_goal_acceleration | ( | self, | |
id | |||
) |
Definition at line 826 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_goal_angvel | ( | self, | |
id | |||
) |
Read the currently set desired moving speed of servo with id.
Definition at line 599 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_goal_position | ( | self, | |
id | |||
) |
Read the currently set goal angle in radians of servo with id.
Definition at line 592 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_goal_torque | ( | self, | |
id | |||
) |
Read the currently set goal torque (used in torque control mode). Units in Amps. Torque produces is a function of motor current.
Definition at line 800 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_load | ( | self, | |
id | |||
) |
Alias for read_torque.
Definition at line 448 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_max_torque | ( | self, | |
id | |||
) |
Read the current max torque setting (as a percentage of possible torque).
Definition at line 396 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_model_number | ( | self, | |
id | |||
) |
Read the model number (byte-code) of the servo at id.
Definition at line 268 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_pid_gains | ( | self, | |
id | |||
) |
Read the PID gains currently set on the servo. Returns: [kp, ki, kd] (gain coefficients)
Definition at line 557 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_punch | ( | self, | |
id | |||
) |
Read the currently set minimum motor current. UNITS UNKNOWN. Values in range 0 - 1023. Default: 0.
Definition at line 764 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_return_delay | ( | self, | |
id | |||
) |
Read the currently set Return Delay Time (in microseconds)
Definition at line 324 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_status_return_level | ( | self, | |
id | |||
) |
Read the current status return label of servo at id. 0 - returns status packet only for PING command 1 - returns status packet only for read commands 2 - returns sttaus packet for all commands
Definition at line 411 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_temperature | ( | self, | |
id | |||
) |
returns the temperature (Celcius) of servo (id).
Definition at line 371 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_temperature_limit | ( | self, | |
id | |||
) |
Read the temperature alarm threshold in degrees C. Default: 80C. Should not change.
Definition at line 365 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_torque | ( | self, | |
id | |||
) |
Read the current load as a percentage of (possibly) maximum torque. CW -> load < 0. CCW -> load > 0. Should be used for direction of torque only.
Definition at line 453 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_torque_limit | ( | self, | |
id | |||
) |
Read the currently set torque limit as a percentage of acheivable torque. Torque produced by the motor will be capped to this value.
Definition at line 605 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_voltage | ( | self, | |
id | |||
) |
returns voltage (Volts) seen by servo (id).
Definition at line 390 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.read_voltage_limits | ( | self, | |
id | |||
) |
Read the lower and upper voltage alarm limits. Defaults: 6.0V - 16.0V.
Definition at line 377 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_angle_limits | ( | self, | |
id, | |||
cw_limit = 0. , |
|||
ccw_limit = 2*math.pi |
|||
) |
Set the angular limits (in radians) on the motor. Should specify both cw and ccw limits
Definition at line 329 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_angvel | ( | self, | |
id, | |||
angvel | |||
) |
set angvel (rad/s) of servo id
Definition at line 741 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_baudrate | ( | self, | |
id, | |||
baudrate = 0x22 |
|||
) |
Set the baudrate of the servo at id. Smaller == Faster. Default: 34 -> 57600.
Definition at line 290 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_compliance_margins | ( | self, | |
id, | |||
cw = None , |
|||
ccw = None |
|||
) |
Definition at line 486 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_compliance_slopes | ( | self, | |
id, | |||
cw = None , |
|||
ccw = None |
|||
) |
Definition at line 544 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_goal_acceleration | ( | self, | |
id, | |||
ang_acc = 0 |
|||
) |
Set the goal acceleration (0 <--> 2018 rads/sec^2) If goal angular velocity is set to 0, will move with max acceleration. If goal acceleration is set to 0 (default), will move with max acceleration.
Definition at line 830 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_goal_torque | ( | self, | |
id, | |||
percent = 100 |
|||
) |
Set the goal torque as a percentage of the maximum torque. 100 % -> Max torque CCW. -100 % -> Max torque CW.
Definition at line 812 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_id | ( | self, | |
current_id, | |||
new_id | |||
) |
changes the servo id from current_id to new_id
Definition at line 279 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_led | ( | self, | |
id, | |||
on = True |
|||
) |
Set the status of the LED on or off.
Definition at line 472 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_max_torque | ( | self, | |
id, | |||
percent = 100 |
|||
) |
Set the max torque as a percent of possible torque. Will trigger alarm and shutdown if exceeded.
Definition at line 402 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_pid_gains | ( | self, | |
id, | |||
kp = 4. , |
|||
ki = 0. , |
|||
kd = 0. |
|||
) |
Set the PID gain coefficients on the servo. 0 <= kp < 31.875 0 <= ki < 124.5177 0 <= kd < 1.02
Definition at line 567 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_punch | ( | self, | |
id, | |||
value = 0 |
|||
) |
Set the minimum motor current. UNITS UNKNOWN. Values in range 0 - 1023. Default: 0.
Definition at line 771 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_return_delay | ( | self, | |
id, | |||
delay = 250 |
|||
) |
Set Return Delay Time (0-500 microseconds). Default=250.
Definition at line 310 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_status_return_level | ( | self, | |
id, | |||
level = 2 |
|||
) |
Set the current status return label of servo at id. 0 - returns status packet only for PING command 1 - returns status packet only for read commands 2 - returns sttaus packet for all commands
Definition at line 419 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_torque_limit | ( | self, | |
id, | |||
percent = None |
|||
) |
Set the torque limit as a percent of possible torque. Torque produced by the motor will be capped to this value.
Definition at line 612 of file lib_dynamixel.py.
def robotis.lib_dynamixel.Dynamixel_Chain.set_voltage_limits | ( | self, | |
id, | |||
lower = 6.0 , |
|||
upper = 16.0 |
|||
) |
Set the lower and upper voltage alarm limits. Defaults: 6.0V - 16.0V.
Definition at line 383 of file lib_dynamixel.py.
Definition at line 202 of file lib_dynamixel.py.