dynamixel Package

pypot.dynamixel.get_available_ports(only_free=False)[source]
pypot.dynamixel.find_port(ids, strict=True)[source]

Find the port with the specified attached motor ids.

Parameters:
  • ids (list) – list of motor ids to find
  • strict (bool) – specify if all ids should be find (when set to False, only half motor must be found)

Warning

If two (or more) ports are attached to the same list of motor ids the first match will be returned.

pypot.dynamixel.autodetect_robot()[source]

Creates a Robot by detecting dynamixel motors on all available ports.

io Package

class pypot.dynamixel.io.io.DxlIO(port, baudrate=1000000, timeout=0.05, use_sync_read=False, error_handler_cls=None, convert=True)[source]

Bases: pypot.dynamixel.io.abstract_io.AbstractDxlIO

At instanciation, it opens the serial port and sets the communication parameters.

Parameters:
  • port (string) – the serial port to use (e.g. Unix (/dev/tty…), Windows (COM…)).
  • baudrate (int) – default for new motors: 57600, for PyPot motors: 1000000
  • timeout (float) – read timeout in seconds
  • use_sync_read (bool) – whether or not to use the SYNC_READ instruction
  • error_handler (DxlErrorHandler) – set a handler that will receive the different errors
  • convert (bool) – whether or not convert values to units expressed in the standard system
Raises:

DxlError if the port is already used.

factory_reset()[source]

Reset all motors on the bus to their factory default settings.

get_control_mode(ids)[source]

Gets the mode (‘joint’ or ‘wheel’) for the specified motors.

set_wheel_mode(ids)[source]

Sets the specified motors to wheel mode.

set_joint_mode(ids)[source]

Sets the specified motors to joint mode.

set_control_mode(mode_for_id)[source]
set_angle_limit(limit_for_id, **kwargs)[source]

Sets the angle limit to the specified motors.

get_alarm_LED(ids, **kwargs)

Gets alarm LED from the specified motors.

get_alarm_shutdown(ids, **kwargs)

Gets alarm shutdown from the specified motors.

get_angle_limit(ids, **kwargs)

Gets angle limit from the specified motors.

get_compliance_margin(ids, **kwargs)

Gets compliance margin from the specified motors.

get_compliance_slope(ids, **kwargs)

Gets compliance slope from the specified motors.

get_drive_mode(ids, **kwargs)

Gets drive mode from the specified motors.

get_firmware(ids, **kwargs)

Gets firmware from the specified motors.

get_force_control_enable(ids, **kwargs)

Gets force control enable from the specified motors.

get_goal_acceleration(ids, **kwargs)

Gets goal acceleration from the specified motors.

get_goal_force(ids, **kwargs)

Gets goal force from the specified motors.

get_goal_position(ids, **kwargs)

Gets goal position from the specified motors.

get_goal_position_speed_load(ids, **kwargs)

Gets goal position speed load from the specified motors.

get_highest_temperature_limit(ids, **kwargs)

Gets highest temperature limit from the specified motors.

get_max_torque(ids, **kwargs)

Gets max torque from the specified motors.

get_moving_speed(ids, **kwargs)

Gets moving speed from the specified motors.

get_present_current(ids, **kwargs)

Gets present current from the specified motors.

get_present_load(ids, **kwargs)

Gets present load from the specified motors.

get_present_position(ids, **kwargs)

Gets present position from the specified motors.

get_present_position_speed_load(ids, **kwargs)

Gets present position speed load from the specified motors.

get_present_speed(ids, **kwargs)

Gets present speed from the specified motors.

get_present_temperature(ids, **kwargs)

Gets present temperature from the specified motors.

get_present_voltage(ids, **kwargs)

Gets present voltage from the specified motors.

get_punch(ids, **kwargs)

Gets punch from the specified motors.

get_return_delay_time(ids, **kwargs)

Gets return delay time from the specified motors.

get_torque_limit(ids, **kwargs)

Gets torque limit from the specified motors.

get_voltage_limit(ids, **kwargs)

Gets voltage limit from the specified motors.

is_led_on(ids, **kwargs)

Gets LED from the specified motors.

is_moving(ids, **kwargs)

Gets moving from the specified motors.

is_torque_enabled(ids, **kwargs)

Gets torque_enable from the specified motors.

set_alarm_LED(value_for_id, **kwargs)

Sets alarm LED to the specified motors.

set_alarm_shutdown(value_for_id, **kwargs)

Sets alarm shutdown to the specified motors.

set_compliance_margin(value_for_id, **kwargs)

Sets compliance margin to the specified motors.

set_compliance_slope(value_for_id, **kwargs)

Sets compliance slope to the specified motors.

set_drive_mode(value_for_id, **kwargs)

Sets drive mode to the specified motors.

set_force_control_enable(value_for_id, **kwargs)

Sets force control enable to the specified motors.

set_goal_acceleration(value_for_id, **kwargs)

Sets goal acceleration to the specified motors.

set_goal_force(value_for_id, **kwargs)

Sets goal force to the specified motors.

set_goal_position(value_for_id, **kwargs)

Sets goal position to the specified motors.

set_goal_position_speed_load(value_for_id, **kwargs)

Sets goal position speed load to the specified motors.

set_highest_temperature_limit(value_for_id, **kwargs)

Sets highest temperature limit to the specified motors.

set_max_torque(value_for_id, **kwargs)

Sets max torque to the specified motors.

set_moving_speed(value_for_id, **kwargs)

Sets moving speed to the specified motors.

set_punch(value_for_id, **kwargs)

Sets punch to the specified motors.

set_return_delay_time(value_for_id, **kwargs)

Sets return delay time to the specified motors.

set_torque_limit(value_for_id, **kwargs)

Sets torque limit to the specified motors.

set_voltage_limit(value_for_id, **kwargs)

Sets voltage limit to the specified motors.

class pypot.dynamixel.io.io_320.Dxl320IO(port, baudrate=1000000, timeout=0.05, use_sync_read=False, error_handler_cls=None, convert=True)[source]

Bases: pypot.dynamixel.io.abstract_io.AbstractDxlIO

At instanciation, it opens the serial port and sets the communication parameters.

Parameters:
  • port (string) – the serial port to use (e.g. Unix (/dev/tty…), Windows (COM…)).
  • baudrate (int) – default for new motors: 57600, for PyPot motors: 1000000
  • timeout (float) – read timeout in seconds
  • use_sync_read (bool) – whether or not to use the SYNC_READ instruction
  • error_handler (DxlErrorHandler) – set a handler that will receive the different errors
  • convert (bool) – whether or not convert values to units expressed in the standard system
Raises:

DxlError if the port is already used.

set_wheel_mode(ids)[source]
set_joint_mode(ids)[source]
get_goal_position_speed_load(ids)[source]
set_goal_position_speed_load(value_for_ids)[source]
factory_reset(ids, except_ids=False, except_baudrate_and_ids=False)[source]

Reset all motors on the bus to their factory default settings.

get_LED_color(ids, **kwargs)

Gets LED color from the specified motors.

get_alarm_shutdown(ids, **kwargs)

Gets alarm shutdown from the specified motors.

get_angle_limit(ids, **kwargs)

Gets angle limit from the specified motors.

get_control_mode(ids, **kwargs)

Gets control mode from the specified motors.

get_firmware(ids, **kwargs)

Gets firmware from the specified motors.

get_goal_position(ids, **kwargs)

Gets goal position from the specified motors.

get_highest_temperature_limit(ids, **kwargs)

Gets highest temperature limit from the specified motors.

get_max_torque(ids, **kwargs)

Gets max torque from the specified motors.

get_moving_speed(ids, **kwargs)

Gets moving speed from the specified motors.

get_present_load(ids, **kwargs)

Gets present load from the specified motors.

get_present_position(ids, **kwargs)

Gets present position from the specified motors.

get_present_position_speed_load(ids, **kwargs)

Gets present position speed load from the specified motors.

get_present_speed(ids, **kwargs)

Gets present speed from the specified motors.

get_present_temperature(ids, **kwargs)

Gets present temperature from the specified motors.

get_present_voltage(ids, **kwargs)

Gets present voltage from the specified motors.

get_return_delay_time(ids, **kwargs)

Gets return delay time from the specified motors.

get_torque_limit(ids, **kwargs)

Gets torque limit from the specified motors.

get_voltage_limit(ids, **kwargs)

Gets voltage limit from the specified motors.

is_led_on(ids, **kwargs)

Gets LED from the specified motors.

is_moving(ids, **kwargs)

Gets moving from the specified motors.

is_torque_enabled(ids, **kwargs)

Gets torque_enable from the specified motors.

set_LED_color(value_for_id, **kwargs)

Sets LED color to the specified motors.

set_alarm_shutdown(value_for_id, **kwargs)

Sets alarm shutdown to the specified motors.

set_angle_limit(value_for_id, **kwargs)

Sets angle limit to the specified motors.

set_control_mode(value_for_id, **kwargs)

Sets control mode to the specified motors.

set_goal_position(value_for_id, **kwargs)

Sets goal position to the specified motors.

set_highest_temperature_limit(value_for_id, **kwargs)

Sets highest temperature limit to the specified motors.

set_max_torque(value_for_id, **kwargs)

Sets max torque to the specified motors.

set_moving_speed(value_for_id, **kwargs)

Sets moving speed to the specified motors.

set_return_delay_time(value_for_id, **kwargs)

Sets return delay time to the specified motors.

set_torque_limit(value_for_id, **kwargs)

Sets torque limit to the specified motors.

set_voltage_limit(value_for_id, **kwargs)

Sets voltage limit to the specified motors.

motor Module

class pypot.dynamixel.motor.DxlMotor(id, name=None, model='', direct=True, offset=0.0, broken=False, angle_limit=None)[source]

Bases: pypot.robot.motor.Motor

High-level class used to represent and control a generic dynamixel motor.

This class provides all level access to (see registers for an exhaustive list):
  • motor id
  • motor name
  • motor model
  • present position/speed/load
  • goal position/speed/load
  • compliant
  • motor orientation and offset
  • angle limit
  • temperature
  • voltage

This class represents a generic robotis motor and you define your own subclass for specific motors (see DxlMXMotor or DxlAXRXMotor).

Those properties are synchronized with the real motors values thanks to a DxlController.

goal_speed

Goal speed (in degrees per second) of the motor.

This property can be used to control your motor in speed. Setting a goal speed will automatically change the moving speed and sets the goal position as the angle limit.

Note

The motor will turn until reaching the angle limit. But this is not a wheel mode, so the motor will stop at its limits.

goto_position(position, duration, control=None, wait=False)[source]

Automatically sets the goal position and the moving speed to reach the desired position within the duration.

class pypot.dynamixel.motor.DxlAXRXMotor(id, name=None, model='', direct=True, offset=0.0, broken=False, angle_limit=None)[source]

Bases: pypot.dynamixel.motor.DxlMotor

This class represents the AX robotis motor.

This class adds access to:
  • compliance margin/slope (see the robotis website for details)
class pypot.dynamixel.motor.DxlMXMotor(id, name=None, model='', direct=True, offset=0.0, broken=False, angle_limit=None)[source]

Bases: pypot.dynamixel.motor.DxlMotor

This class represents the RX and MX robotis motor.

This class adds access to:
  • PID gains (see the robotis website for details)

This class represents the RX and MX robotis motor.

This class adds access to:
  • PID gains (see the robotis website for details)
class pypot.dynamixel.motor.DxlMX64106Motor(id, name=None, model='', direct=True, offset=0.0, broken=False, angle_limit=None)[source]

Bases: pypot.dynamixel.motor.DxlMXMotor

This class represents the MX-64 and MX-106 robotis motor.

This class adds access to:
  • present current

This class represents the RX and MX robotis motor.

This class adds access to:
  • PID gains (see the robotis website for details)
class pypot.dynamixel.motor.DxlXL320Motor(id, name=None, model='XL-320', direct=True, offset=0.0, broken=False, angle_limit=None)[source]

Bases: pypot.dynamixel.motor.DxlMXMotor

control_mode

This class represents the XL-320 robotis motor.

class pypot.dynamixel.motor.DxlSRMotor(id, name=None, model='', direct=True, offset=0.0, broken=False, angle_limit=None)[source]

Bases: pypot.dynamixel.motor.DxlMotor

This class represents the robotis motor found in the seed robotics hand.

This class adds access to:
  • force control enable
  • goal force
  • present current

This class represents the robotis motor found in the seed robotics hand.

This class adds access to:
  • PID gains (see the robotis website for details)
  • force control enable
  • goal force
class pypot.dynamixel.motor.SafeCompliance(motor, frequency=50)[source]

Bases: pypot.utils.stoppablethread.StoppableLoopThread

This class creates a controller to active compliance only if the current motor position is included in the angle limit, else the compliance is turned off.

update()[source]

Update method called at the pre-defined frequency.

teardown()[source]

Teardown method call just after the run.

DxlMotor.registers = ['registers', 'goal_speed', 'compliant', 'safe_compliant', 'angle_limit', 'present_load', 'id', 'present_temperature', 'moving_speed', 'torque_limit', 'goal_position', 'upper_limit', 'lower_limit', 'name', 'present_speed', 'present_voltage', 'present_position', 'model']

controller Module

class pypot.dynamixel.controller.DxlController(io, motors, sync_freq, synchronous, mode, regname, varname=None)[source]

Bases: pypot.robot.controller.MotorsController

working_motors
synced_motors
setup()[source]

Setup method call just before the run.

update()[source]

Update method called at the pre-defined frequency.

get_register(motors, disable_sync_read=False)[source]

Gets the value from the specified register and sets it to the DxlMotor.

set_register(motors)[source]

Gets the value from DxlMotor and sets it to the specified register.

class pypot.dynamixel.controller.AngleLimitRegisterController(io, motors, sync_freq, synchronous)[source]

Bases: pypot.dynamixel.controller.DxlController

synced_motors
get_register(motors)[source]

Gets the value from the specified register and sets it to the DxlMotor.

class pypot.dynamixel.controller.PosSpeedLoadDxlController(io, motors, sync_freq)[source]

Bases: pypot.dynamixel.controller.DxlController

setup()[source]

Setup method call just before the run.

update()[source]

Update method called at the pre-defined frequency.

get_present_position_speed_load(motors)[source]
set_goal_position_speed_load(motors)[source]

error Module

class pypot.dynamixel.error.DxlErrorHandler[source]

Bases: object

This class is used to represent all the error that you can/should handle.

The errors can be of two types:

  • communication error (timeout, communication)
  • motor error (voltage, limit, overload…)

This class was designed as an abstract class and so you should write your own handler by subclassing this class and defining the apropriate behavior for your program.

Warning

The motor error should be overload carrefuly as they can indicate important mechanical issue.

handle_timeout(timeout_error)[source]
handle_communication_error(communication_error)[source]
handle_input_voltage_error(instruction_packet)[source]
handle_angle_limit_error(instruction_packet)[source]
handle_overheating_error(instruction_packet)[source]
handle_range_error(instruction_packet)[source]
handle_checksum_error(instruction_packet)[source]
handle_overload_error(instruction_packet)[source]
handle_instruction_error(instruction_packet)[source]
handle_none_error(instruction_packet)[source]
class pypot.dynamixel.error.BaseErrorHandler[source]

Bases: pypot.dynamixel.error.DxlErrorHandler

This class is a basic handler that just skip the communication errors.

handle_timeout(timeout_error)[source]
handle_communication_error(com_error)[source]
handle_none_error(instruction_packet)[source]

conversion Module

This module describes all the conversion method used to transform value from the representation used by the dynamixel motor to a more standard form (e.g. degrees, volt…).

For compatibility issue all comparison method should be written in the following form (even if the model is not actually used):
  • def my_conversion_from_dxl_to_si(value, model): …
  • def my_conversion_from_si_to_dxl(value, model): …

Note

If the control is readonly you only need to write the dxl_to_si conversion.

pypot.dynamixel.conversion.dxl_to_degree(value, model)[source]
pypot.dynamixel.conversion.degree_to_dxl(value, model)[source]
pypot.dynamixel.conversion.dxl_to_speed(value, model)[source]
pypot.dynamixel.conversion.speed_to_dxl(value, model)[source]
pypot.dynamixel.conversion.dxl_to_torque(value, model)[source]
pypot.dynamixel.conversion.torque_to_dxl(value, model)[source]
pypot.dynamixel.conversion.dxl_to_load(value, model)[source]
pypot.dynamixel.conversion.dxl_to_acceleration(value, model)[source]

Converts from ticks to degress/second^2

pypot.dynamixel.conversion.acceleration_to_dxl(value, model)[source]

Converts from degrees/second^2 to ticks

pypot.dynamixel.conversion.dxl_to_pid(value, model)[source]
pypot.dynamixel.conversion.pid_to_dxl(value, model)[source]
pypot.dynamixel.conversion.dxl_to_model(value, dummy=None)[source]
pypot.dynamixel.conversion.check_bit(value, offset)[source]
pypot.dynamixel.conversion.dxl_to_drive_mode(value, model)[source]
pypot.dynamixel.conversion.drive_mode_to_dxl(value, model)[source]
pypot.dynamixel.conversion.dxl_to_baudrate(value, model)[source]
pypot.dynamixel.conversion.baudrate_to_dxl(value, model)[source]
pypot.dynamixel.conversion.dxl_to_rdt(value, model)[source]
pypot.dynamixel.conversion.rdt_to_dxl(value, model)[source]
pypot.dynamixel.conversion.dxl_to_temperature(value, model)[source]
pypot.dynamixel.conversion.temperature_to_dxl(value, model)[source]
pypot.dynamixel.conversion.dxl_to_current(value, model)[source]
pypot.dynamixel.conversion.dxl_to_voltage(value, model)[source]
pypot.dynamixel.conversion.voltage_to_dxl(value, model)[source]
pypot.dynamixel.conversion.dxl_to_status(value, model)[source]
pypot.dynamixel.conversion.status_to_dxl(value, model)[source]
pypot.dynamixel.conversion.dxl_to_alarm(value, model)[source]
pypot.dynamixel.conversion.decode_error(error_code)[source]
pypot.dynamixel.conversion.alarm_to_dxl(value, model)[source]
pypot.dynamixel.conversion.XL320LEDColors

alias of pypot.dynamixel.conversion.Colors

pypot.dynamixel.conversion.dxl_to_led_color(value, model)[source]
pypot.dynamixel.conversion.led_color_to_dxl(value, model)[source]
pypot.dynamixel.conversion.dxl_to_control_mode(value, _)[source]
pypot.dynamixel.conversion.control_mode_to_dxl(mode, _)[source]
pypot.dynamixel.conversion.dxl_to_bool(value, model)[source]
pypot.dynamixel.conversion.bool_to_dxl(value, model)[source]
pypot.dynamixel.conversion.dxl_decode(data)[source]
pypot.dynamixel.conversion.dxl_decode_all(data, nb_elem)[source]
pypot.dynamixel.conversion.dxl_code(value, length)[source]
pypot.dynamixel.conversion.dxl_code_all(value, length, nb_elem)[source]

protocol Package

v1 Module

class pypot.dynamixel.protocol.v1.DxlInstruction[source]

Bases: object

PING = 1
READ_DATA = 2
WRITE_DATA = 3
RESET = 6
SYNC_WRITE = 131
SYNC_READ = 132
class pypot.dynamixel.protocol.v1.DxlPacketHeader[source]

Bases: pypot.dynamixel.protocol.v1.DxlPacketHeader

This class represents the header of a Dxl Packet.

They are constructed as follows [0xFF, 0xFF, ID, LENGTH] where:
  • ID represents the ID of the motor who received (resp. sent) the intruction (resp. status) packet.
  • LENGTH represents the length of the rest of the packet

Create new instance of DxlPacketHeader(id, packet_length)

length = 4
marker = bytearray(b'\xff\xff')
classmethod from_string(data)[source]
class pypot.dynamixel.protocol.v1.DxlInstructionPacket[source]

Bases: pypot.dynamixel.protocol.v1.DxlInstructionPacket

This class is used to represent a dynamixel instruction packet.

An instruction packet is constructed as follows: [0xFF, 0xFF, ID, LENGTH, INSTRUCTION, PARAM 1, PARAM 2, …, PARAM N, CHECKSUM]

(for more details see http://support.robotis.com/en/product/dxl_main.htm)

Create new instance of DxlInstructionPacket(id, instruction, parameters)

to_array()[source]
to_string()[source]
length
checksum
class pypot.dynamixel.protocol.v1.DxlPingPacket[source]

Bases: pypot.dynamixel.protocol.v1.DxlInstructionPacket

This class is used to represent ping packet.

class pypot.dynamixel.protocol.v1.DxlResetPacket[source]

Bases: pypot.dynamixel.protocol.v1.DxlInstructionPacket

This class is used to represent reset packet.

class pypot.dynamixel.protocol.v1.DxlReadDataPacket[source]

Bases: pypot.dynamixel.protocol.v1.DxlInstructionPacket

This class is used to represent read data packet (to read value).

class pypot.dynamixel.protocol.v1.DxlSyncReadPacket[source]

Bases: pypot.dynamixel.protocol.v1.DxlInstructionPacket

This class is used to represent sync read packet (to synchronously read values).

class pypot.dynamixel.protocol.v1.DxlWriteDataPacket[source]

Bases: pypot.dynamixel.protocol.v1.DxlInstructionPacket

This class is used to reprensent write data packet (to write value).

class pypot.dynamixel.protocol.v1.DxlSyncWritePacket[source]

Bases: pypot.dynamixel.protocol.v1.DxlInstructionPacket

This class is used to represent sync write packet (to synchronously write values).

class pypot.dynamixel.protocol.v1.DxlStatusPacket[source]

Bases: pypot.dynamixel.protocol.v1.DxlStatusPacket

This class is used to represent a dynamixel status packet.

A status packet is constructed as follows: [0xFF, 0xFF, ID, LENGTH, ERROR, PARAM 1, PARAM 2, …, PARAM N, CHECKSUM]

(for more details see http://support.robotis.com/en/product/dxl_main.htm)

Create new instance of DxlStatusPacket(id, error, parameters)

classmethod from_string(data)[source]

v2 Module

class pypot.dynamixel.protocol.v2.DxlInstruction[source]

Bases: object

PING = 1
READ_DATA = 2
WRITE_DATA = 3
RESET = 6
SYNC_READ = 130
SYNC_WRITE = 131
class pypot.dynamixel.protocol.v2.DxlPacketHeader[source]

Bases: pypot.dynamixel.protocol.v2.DxlPacketHeader

This class represents the header of a Dxl Packet.

They are constructed as follows [0xFF, 0xFF, 0xFD, 0x00, ID, LEN_L, LEN_H] where:
  • ID represents the ID of the motor who received (resp. sent) the intruction (resp. status) packet.
  • LEN_L, LEN_H represents the length of the rest of the packet

Create new instance of DxlPacketHeader(id, packet_length)

length = 7
marker = bytearray(b'\xff\xff\xfd\x00')
classmethod from_string(data)[source]
class pypot.dynamixel.protocol.v2.DxlInstructionPacket[source]

Bases: pypot.dynamixel.protocol.v2.DxlInstructionPacket

This class is used to represent a dynamixel instruction packet.

An instruction packet is constructed as follows: [0xFF, 0xFF, 0xFD, 0x00, ID, LEN_L, LEN_H, INST, PARAM 1, PARAM 2, …, PARAM N, CRC_L, CRC_H]

(for more details see http://support.robotis.com/en/product/dxl_main.htm)

Create new instance of DxlInstructionPacket(id, instruction, parameters)

to_array()[source]
to_string()[source]
length
checksum
class pypot.dynamixel.protocol.v2.DxlPingPacket[source]

Bases: pypot.dynamixel.protocol.v2.DxlInstructionPacket

This class is used to represent ping packet.

class pypot.dynamixel.protocol.v2.DxlResetPacket[source]

Bases: pypot.dynamixel.protocol.v2.DxlInstructionPacket

This class is used to represent factory reset packet.

class pypot.dynamixel.protocol.v2.DxlReadDataPacket[source]

Bases: pypot.dynamixel.protocol.v2.DxlInstructionPacket

This class is used to represent read data packet (to read value).

class pypot.dynamixel.protocol.v2.DxlSyncReadPacket[source]

Bases: pypot.dynamixel.protocol.v2.DxlInstructionPacket

This class is used to represent sync read packet (to synchronously read values).

class pypot.dynamixel.protocol.v2.DxlWriteDataPacket[source]

Bases: pypot.dynamixel.protocol.v2.DxlInstructionPacket

This class is used to reprensent write data packet (to write value).

class pypot.dynamixel.protocol.v2.DxlSyncWritePacket[source]

Bases: pypot.dynamixel.protocol.v2.DxlInstructionPacket

This class is used to represent sync write packet (to synchronously write values).

class pypot.dynamixel.protocol.v2.DxlStatusPacket[source]

Bases: pypot.dynamixel.protocol.v2.DxlStatusPacket

This class is used to represent a dynamixel status packet.

A status packet is constructed as follows: [0xFF, 0xFF, 0xFD, 0x00, ID, LEN_L, LEN_H, 0x55, ERROR, PARAM 1, PARAM 2, …, PARAM N, CRC_L, CRC_H]

(for more details see http://support.robotis.com/en/product/dxl_main.htm)

Create new instance of DxlStatusPacket(id, error, parameters)

classmethod from_string(data)[source]
pypot.dynamixel.protocol.v2.crc16(data_blk, data_blk_size, crc_accum=0)[source]